5
5
6
6
# Generic and specifc types of obstacles that repel a robot
7
7
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 ):
9
9
self .strength = strength
10
- self .forceIsPositive = forceIsPositive
10
+ self .forceIsPositive = True
11
11
12
12
# Force uses a logistic function to calculate push magnitiude as a fucntion of distance from center.
13
13
# 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 =
17
17
# Parameter to logistic funciton for how steeply the force transitions from "none" to "lots" about the radius
18
18
self .fieldSteepness = 3.5
19
19
20
+ def setForceInverted (self , isInverted )-> None :
21
+ self .forceIsPositive = not isInverted
22
+
20
23
def getForceAtPosition (self , position :Translation2d )-> Force :
21
24
return Force ()
22
25
@@ -36,9 +39,9 @@ def getTelemTrans(self)->list[Translation2d]:
36
39
# A point obstacle is defined as round, centered at a specific point, with a specific radius
37
40
# It pushes the robot away radially outward from its center
38
41
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 ):
40
43
self .location = location
41
- super ().__init__ (strength , forceIsPositive , radius )
44
+ super ().__init__ (strength ,radius )
42
45
43
46
def getForceAtPosition (self , position : Translation2d ) -> Force :
44
47
deltaX = self .location .x - position .x
@@ -48,8 +51,10 @@ def getForceAtPosition(self, position: Translation2d) -> Force:
48
51
unitY = deltaY / dist
49
52
forceMag = self ._distToForceMag (dist )
50
53
return Force (- 1.0 * unitX * forceMag , - 1.0 * unitY * forceMag )
54
+
51
55
def getDist (self , position :Translation2d )-> float :
52
56
return (position - self .location ).norm ()
57
+
53
58
def getTelemTrans (self ) -> list [Translation2d ]:
54
59
return [self .location ]
55
60
@@ -58,9 +63,9 @@ def getTelemTrans(self) -> list[Translation2d]:
58
63
# They push the robot away along a perpendicular direction
59
64
# with the specific direction determined by forceIsPositive
60
65
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 ):
62
67
self .y = y
63
- super ().__init__ (strength , forceIsPositive , radius )
68
+ super ().__init__ (strength ,radius )
64
69
65
70
66
71
def getForceAtPosition (self , position : Translation2d ) -> Force :
@@ -73,12 +78,84 @@ def getTelemTrans(self) -> list[Translation2d]:
73
78
return []
74
79
75
80
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 ):
77
82
self .x = x
78
- super ().__init__ (strength , forceIsPositive , radius )
83
+ super ().__init__ (strength ,radius )
79
84
80
85
def getForceAtPosition (self , position : Translation2d ) -> Force :
81
86
return Force (self ._distToForceMag (self .x - position .X ()), 0 )
82
87
83
88
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
+
0 commit comments