Skip to content

Commit

Permalink
Adding fixed obstacles back to telemetry
Browse files Browse the repository at this point in the history
  • Loading branch information
gerth2 committed Nov 15, 2024
1 parent 1e66d90 commit e632fbc
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 12 deletions.
4 changes: 3 additions & 1 deletion drivetrain/poseEstimation/drivetrainPoseTelemetry.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ def __init__(self):
wpilib.SmartDashboard.putData("DT Pose 2D", self.field)
self.curTraj = Trajectory()
self.curTrajWaypoints = []
self.fixedObstacles = []
self.fullObstacles = []
self.thirdObstacles = []
self.almostGoneObstacles = []
Expand Down Expand Up @@ -58,7 +59,7 @@ def addVisionObservations(self, observations:list[CameraPoseObservation]):
self.visionPoses.append(obs.estFieldPose)

def setCurObstacles(self, obstacles):
self.fullObstacles, self.thirdObstacles, self.almostGoneObstacles = obstacles
self.fixedObstacles, self.fullObstacles, self.thirdObstacles, self.almostGoneObstacles = obstacles

def clearVisionObservations(self):
self.visionPoses = []
Expand All @@ -77,6 +78,7 @@ def update(self, estPose:Pose2d, moduleAngles):
self.field.getObject("desPose").setPose(self.desPose)
self.field.getObject("desTraj").setTrajectory(self.curTraj)
self.field.getObject("desTrajWaypoints").setPoses(self.curTrajWaypoints)
self.field.getObject("curObstaclesFixed").setPoses([Pose2d(x, Rotation2d()) for x in self.fixedObstacles])
self.field.getObject("curObstaclesFull").setPoses([Pose2d(x, Rotation2d()) for x in self.fullObstacles])
self.field.getObject("curObstaclesThird").setPoses([Pose2d(x, Rotation2d()) for x in self.thirdObstacles])
self.field.getObject("curObstaclesAlmostGone").setPoses([Pose2d(x, Rotation2d()) for x in self.almostGoneObstacles])
Expand Down
24 changes: 13 additions & 11 deletions navigation/repulsorFieldPlanner.py
Original file line number Diff line number Diff line change
Expand Up @@ -166,25 +166,27 @@ def _decayObservations(self):
# Fully decayed obstacles have zero or negative strength.
self.transientObstcales = [x for x in self.transientObstcales if x.strength > 0.0]

def getObstacleStrengths(self):
#these are all Translation 2ds, or should be, but we can't say that if we want to return all 3.
fullTransientObstacles =[]
thirdTransientObstacles = []
almostGoneTransientObstacles = []
def getObstacleStrengths(self) -> tuple[list[Translation2d], list[Translation2d], list[Translation2d], list[Translation2d]]:
#these are all Translation 2ds, or should be, but we can't say that if we want to return all 4.
fixedObstacleTranslations = []
fullTransientObstacleTranslations =[]
thirdTransientObstacleTranslations = []
almostGoneTransientObstacleTranslations = []

# Fixed obstacles are full strength
# Fixed obstacles
for x in self.fixedObstacles:
fullTransientObstacles.extend(x.getTelemTrans())
fixedObstacleTranslations.extend(x.getTelemTrans())

# Transient Obstacles
for x in self.transientObstcales:
if x.strength > .5:
fullTransientObstacles.extend(x.getTelemTrans())
fullTransientObstacleTranslations.extend(x.getTelemTrans())
elif x.strength > .33:
thirdTransientObstacles.extend(x.getTelemTrans())
thirdTransientObstacleTranslations.extend(x.getTelemTrans())
else:
almostGoneTransientObstacles.extend(x.getTelemTrans())
almostGoneTransientObstacleTranslations.extend(x.getTelemTrans())

return fullTransientObstacles, thirdTransientObstacles, almostGoneTransientObstacles
return fixedObstacleTranslations, fullTransientObstacleTranslations, thirdTransientObstacleTranslations, almostGoneTransientObstacleTranslations

def getObstacleTransList(self) -> list[Translation2d]:
"""
Expand Down

0 comments on commit e632fbc

Please sign in to comment.