Skip to content

Commit 737e2e6

Browse files
committed
Merge remote-tracking branch 'origin/chris_linear_obstacles' into main_nav
2 parents 0fd3f12 + bd2be4e commit 737e2e6

File tree

4 files changed

+106
-24
lines changed

4 files changed

+106
-24
lines changed

drivetrain/controlStrategies/autoDrive.py

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,16 @@
1-
from wpimath.geometry import Pose2d, Rotation2d, Translation2d
1+
from wpimath.geometry import Pose2d, Translation2d
22
from wpimath.trajectory import Trajectory
33
from drivetrain.controlStrategies.holonomicDriveController import HolonomicDriveController
44
from drivetrain.drivetrainCommand import DrivetrainCommand
55
from navigation.obstacleDetector import ObstacleDetector
66
from utils.signalLogging import log
77
from utils.singleton import Singleton
8-
from navigation.repulsorFieldPlanner import RepulsorFieldPlanner
8+
from navigation.repulsorFieldPlanner import GOAL_PICKUP, GOAL_SPEAKER, RepulsorFieldPlanner
99
from drivetrain.drivetrainPhysical import MAX_DT_LINEAR_SPEED
1010
from utils.allianceTransformUtils import transform
1111

1212

13-
GOAL_PICKUP = Pose2d.fromFeet(40,5,Rotation2d.fromDegrees(0.0))
14-
GOAL_SPEAKER = Pose2d.fromFeet(3,20,Rotation2d.fromDegrees(180.0))
13+
1514
SPEED_SCALAR = 0.75
1615

1716
class AutoDrive(metaclass=Singleton):

navigation/obstacles.py

Lines changed: 86 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -5,9 +5,9 @@
55

66
# Generic and specifc types of obstacles that repel a robot
77
class Obstacle:
8-
def __init__(self, strength:float=1.0, forceIsPositive:bool=True, radius:float = 0.25):
8+
def __init__(self, strength:float=1.0, radius:float = 0.25):
99
self.strength = strength
10-
self.forceIsPositive = forceIsPositive
10+
self.forceIsPositive = True
1111

1212
# Force uses a logistic function to calculate push magnitiude as a fucntion of distance from center.
1313
# The radius offsets the center to get a larger or smaller obstacle
@@ -17,6 +17,9 @@ def __init__(self, strength:float=1.0, forceIsPositive:bool=True, radius:float =
1717
# Parameter to logistic funciton for how steeply the force transitions from "none" to "lots" about the radius
1818
self.fieldSteepness = 3.5
1919

20+
def setForceInverted(self, isInverted)->None:
21+
self.forceIsPositive = not isInverted
22+
2023
def getForceAtPosition(self, position:Translation2d)->Force:
2124
return Force()
2225

@@ -36,9 +39,9 @@ def getTelemTrans(self)->list[Translation2d]:
3639
# A point obstacle is defined as round, centered at a specific point, with a specific radius
3740
# It pushes the robot away radially outward from its center
3841
class PointObstacle(Obstacle):
39-
def __init__(self, location:Translation2d, strength:float=1.0, forceIsPositive:bool=True, radius:float = 0.3):
42+
def __init__(self, location:Translation2d, strength:float=1.0, radius:float = 0.3):
4043
self.location = location
41-
super().__init__(strength, forceIsPositive,radius)
44+
super().__init__(strength,radius)
4245

4346
def getForceAtPosition(self, position: Translation2d) -> Force:
4447
deltaX = self.location.x - position.x
@@ -48,8 +51,10 @@ def getForceAtPosition(self, position: Translation2d) -> Force:
4851
unitY = deltaY/dist
4952
forceMag = self._distToForceMag(dist)
5053
return Force(-1.0*unitX*forceMag, -1.0*unitY*forceMag)
54+
5155
def getDist(self, position:Translation2d)->float:
5256
return (position - self.location).norm()
57+
5358
def getTelemTrans(self) -> list[Translation2d]:
5459
return [self.location]
5560

@@ -58,9 +63,9 @@ def getTelemTrans(self) -> list[Translation2d]:
5863
# They push the robot away along a perpendicular direction
5964
# with the specific direction determined by forceIsPositive
6065
class HorizontalObstacle(Obstacle):
61-
def __init__(self, y:float, strength:float=1.0, forceIsPositive:bool=True, radius:float = 0.5):
66+
def __init__(self, y:float, strength:float=1.0, radius:float = 0.5):
6267
self.y=y
63-
super().__init__(strength, forceIsPositive,radius)
68+
super().__init__(strength,radius)
6469

6570

6671
def getForceAtPosition(self, position: Translation2d) -> Force:
@@ -73,12 +78,84 @@ def getTelemTrans(self) -> list[Translation2d]:
7378
return []
7479

7580
class VerticalObstacle(Obstacle):
76-
def __init__(self, x:float, strength:float=1.0, forceIsPositive:bool=True, radius:float = 0.5):
81+
def __init__(self, x:float, strength:float=1.0, radius:float = 0.5):
7782
self.x=x
78-
super().__init__(strength, forceIsPositive,radius)
83+
super().__init__(strength,radius)
7984

8085
def getForceAtPosition(self, position: Translation2d) -> Force:
8186
return Force(self._distToForceMag(self.x - position.X()), 0)
8287

8388
def getDist(self, position: Translation2d) -> float:
84-
return abs(position.x - self.x)
89+
return abs(position.x - self.x)
90+
91+
# Describes a field force that exists along a line segment with a start and end point
92+
class LinearObstacle(Obstacle):
93+
def __init__(self, start:Translation2d, end:Translation2d, strength:float=0.75, radius:float = 0.4):
94+
self.start = start
95+
self.end = end
96+
super().__init__(strength,radius)
97+
98+
def _shortestTransToSegment(self, point: Translation2d) -> Translation2d:
99+
# Vector from start to end of the segment
100+
segment_vector_x = self.end.X() - self.start.X()
101+
segment_vector_y = self.end.Y() - self.start.Y()
102+
103+
# Segment length squared (to avoid a square root operation)
104+
segment_length_squared = segment_vector_x ** 2 + segment_vector_y ** 2
105+
106+
# Vector from start of the segment to the point
107+
start_to_point_x = point.X() - self.start.X()
108+
start_to_point_y = point.Y() - self.start.Y()
109+
110+
# Project the point onto the line (infinite line, not the segment)
111+
t = (start_to_point_x * segment_vector_x + start_to_point_y * segment_vector_y) / segment_length_squared
112+
113+
# Clamp t to the range [0, 1] to restrict it to the segment
114+
t = max(0, min(1, t))
115+
116+
# Calculate the closest point on the segment
117+
closest_point_x = self.start.X() + t * segment_vector_x
118+
closest_point_y = self.start.Y() + t * segment_vector_y
119+
120+
# Return the shortest vector from the point to the closest point on the segment
121+
return Translation2d(closest_point_x - point.X(), closest_point_y - point.Y())
122+
123+
def getDist(self, position: Translation2d) -> float:
124+
return self._shortestTransToSegment(position).norm()
125+
126+
# Field formation that pushes the robot toward and along a line between start/end
127+
class Lane(LinearObstacle):
128+
129+
def getForceAtPosition(self, position: Translation2d) -> Force:
130+
toSeg = self._shortestTransToSegment(position)
131+
toSegUnit = toSeg/toSeg.norm()
132+
133+
alongSeg = (self.end - self.start)
134+
alongSegUnit = alongSeg/alongSeg.norm()
135+
136+
forceDir = alongSegUnit * 0.75 + toSegUnit * 0.25
137+
forceDirUnit = forceDir/forceDir.norm()
138+
unitX = forceDirUnit.X()
139+
unitY = forceDirUnit.Y()
140+
141+
dist = toSeg.norm()
142+
forceMag = self._distToForceMag(dist)
143+
144+
return Force(unitX*forceMag, unitY*forceMag)
145+
146+
# Field formation that pushes the robot uniformly away from the line
147+
class Wall(LinearObstacle):
148+
149+
def getForceAtPosition(self, position: Translation2d) -> Force:
150+
toSeg = self._shortestTransToSegment(position)
151+
toSegUnit = toSeg/toSeg.norm()
152+
153+
unitX = toSegUnit.X() * -1.0
154+
unitY = toSegUnit.Y() * -1.0
155+
156+
dist = toSeg.norm()
157+
forceMag = self._distToForceMag(dist)
158+
159+
return Force(unitX*forceMag, unitY*forceMag)
160+
161+

navigation/repulsorFieldPlanner.py

Lines changed: 15 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
from wpimath.geometry import Pose2d, Translation2d
1+
from wpimath.geometry import Pose2d, Translation2d, Rotation2d
22

33
from utils.mapLookup2d import MapLookup2D
44
from utils.signalLogging import log
@@ -22,7 +22,7 @@
2222
TRANSIENT_OBS_DECAY_PER_LOOP = 0.1
2323

2424
# Obstacles come in two main flavors: Fixed and Transient.
25-
# Transient obstacles decay and disaapear over time. They are things like other robots, or maybe gamepieces we don't want to drive through.
25+
# Transient obstacles decay and disappear over time. They are things like other robots, or maybe gamepieces we don't want to drive through.
2626
# Fixed obstacles are things like field elements or walls with fixed, known positions. They are always present and do not decay over time.
2727

2828
# Fixed Obstacles - Six posts in the middle of the field from 2024
@@ -36,12 +36,19 @@
3636
]
3737

3838
# Fixed Obstacles - Outer walls of the field
39-
WALLS = [
40-
HorizontalObstacle(y=0.0, forceIsPositive=True),
41-
HorizontalObstacle(y=FIELD_Y_M, forceIsPositive=False),
42-
VerticalObstacle(x=0.0, forceIsPositive=True),
43-
VerticalObstacle(x=FIELD_X_M, forceIsPositive=False)
44-
]
39+
B_WALL = HorizontalObstacle(y=0.0)
40+
T_WALL = HorizontalObstacle(y=FIELD_Y_M)
41+
T_WALL.setForceInverted(True)
42+
43+
L_WALL = VerticalObstacle(x=0.0)
44+
R_WALL = VerticalObstacle(x=FIELD_X_M)
45+
R_WALL.setForceInverted(True)
46+
47+
WALLS = [B_WALL, T_WALL, L_WALL, R_WALL]
48+
49+
# Happy Constants for the goal poses we may want to drive to
50+
GOAL_PICKUP = Pose2d.fromFeet(40,5,Rotation2d.fromDegrees(0.0))
51+
GOAL_SPEAKER = Pose2d.fromFeet(3,20,Rotation2d.fromDegrees(180.0))
4552

4653
# Usually, the path planner assumes we traverse the path at a fixed velocity
4754
# However, near the goal, we'd like to slow down. This map defines how we ramp down

vectorPlotter.py

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -2,9 +2,8 @@
22
import math
33
import matplotlib.pyplot as plt
44
import numpy as np
5-
from drivetrain.controlStrategies.autoDrive import GOAL_PICKUP
6-
from navigation.repulsorFieldPlanner import RepulsorFieldPlanner
7-
from wpimath.geometry import Pose2d, Translation2d, Rotation2d
5+
from navigation.repulsorFieldPlanner import RepulsorFieldPlanner, GOAL_PICKUP, GOAL_SPEAKER
6+
from wpimath.geometry import Translation2d
87
import matplotlib.pyplot as plt
98
import numpy as np
109
from navigation.navConstants import *

0 commit comments

Comments
 (0)