Skip to content

Commit ce0d3ec

Browse files
committed
Merge branch 's2025' into Control_Stanley
2 parents 91e4cd2 + fbb1368 commit ce0d3ec

170 files changed

Lines changed: 16334 additions & 678 deletions

File tree

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

GEMstack/knowledge/defaults/computation_graph.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ components:
2222
inputs: [vehicle, roadgraph]
2323
outputs: vehicle_lane
2424
- parking_detection:
25-
inputs: obstacles
25+
inputs: all
2626
outputs: [goal, obstacles]
2727
- sign_detection:
2828
inputs: [vehicle, roadgraph]

GEMstack/knowledge/defaults/current.yaml

Lines changed: 6 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,6 @@ vehicle: !include ../vehicle/gem_e4.yaml
77
model_predictive_controller:
88
dt: 0.1
99
lookahead: 20
10-
1110
control:
1211
recovery:
1312
brake_amount : 0.5
@@ -42,11 +41,11 @@ control:
4241
#configure the simulator, if using
4342
simulator:
4443
dt: 0.01
45-
real_time_multiplier: 1.0 # make the simulator run faster than real time by making this > 1
44+
real_time_multiplier: 1.0 # make the simulator run faster than real time by making this > 1
4645
gnss_emulator:
47-
dt: 0.1 # 10Hz
48-
#position_noise: 0.1 # 10cm noise
49-
#orientation_noise: 0.04 # 2.3 degrees noise
46+
dt: 0.1 #10Hz
47+
#position_noise: 0.1 #10cm noise
48+
#orientation_noise: 0.04 #2.3 degrees noise
5049
#velocity_noise:
51-
# constant: 0.04 # 4cm/s noise
52-
# linear: 0.02 # 2% noise
50+
# constant: 0.04 #4cm/s noise
51+
# linear: 0.02 #2% noise

GEMstack/knowledge/defaults/rrt_param.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@ map:
1111
# vehicle info
1212
vehicle:
1313
heading_limit: 0.5235987756 # vehicle heading difference limit per rrt step_size (pi/6 in radians)
14-
half_width: 0.8 # vehicle half width in meter
14+
half_width: 0.6 # vehicle half width in meter
1515
# algorithm parameters
1616
rrt:
1717
time_limit: 10 # in sec

GEMstack/knowledge/routes/summoning_roadgraph_highbay.json

Lines changed: 1 addition & 1 deletion
Large diffs are not rendered by default.

GEMstack/knowledge/routes/summoning_roadgraph_sim.json

Lines changed: 1 addition & 1 deletion
Large diffs are not rendered by default.

GEMstack/onboard/perception/cone_detection.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -506,4 +506,4 @@ def box_to_fake_obstacle(box):
506506

507507

508508
if __name__ == '__main__':
509-
pass
509+
pass

GEMstack/onboard/perception/parking_detection.py

Lines changed: 19 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@
44
from sensor_msgs.msg import PointCloud2
55
from typing import Dict
66
from ..component import Component
7-
from ...state import ObjectPose, ObjectFrameEnum, Obstacle, ObstacleMaterialEnum
7+
from ...state import ObjectPose, ObjectFrameEnum, Obstacle, ObstacleMaterialEnum, ObstacleStateEnum, AllState
88
from ..interface.gem import GEMInterface
99
from .utils.constants import *
1010
from .utils.math_utils import *
@@ -77,7 +77,7 @@ def rate(self) -> float:
7777
return 10.0 # Hz
7878

7979
def state_inputs(self) -> list:
80-
return ['obstacles']
80+
return ['all']
8181

8282
def state_outputs(self) -> list:
8383
return ['goal', 'obstacles']
@@ -149,14 +149,14 @@ def visualize(self,
149149
self.pub_cones_centers_pc2.publish(ros_cones_centers_pc2)
150150

151151

152-
def update(self, cone_obstacles: Dict[str, Obstacle]):
152+
def update(self, state: AllState):
153153
# Initial variables
154154
parking_goals = []
155155
best_parking_spots = []
156156
parking_obstacles_poses = []
157157
parking_obstacles_dims = []
158158
grouped_ordered_ground_centers_2D = []
159-
159+
cone_obstacles = state.obstacles
160160
# Populate cone points
161161
cone_pts_3D = []
162162
for cone in cone_obstacles.values():
@@ -231,7 +231,7 @@ def update(self, cone_obstacles: Dict[str, Obstacle]):
231231
yaw=yaw,
232232
pitch=0.0,
233233
roll=0.0,
234-
frame=ObjectFrameEnum.CURRENT
234+
frame=ObjectFrameEnum.START
235235
)
236236
new_obstacle = Obstacle(
237237
pose=obstacle_pose,
@@ -240,7 +240,7 @@ def update(self, cone_obstacles: Dict[str, Obstacle]):
240240
material=ObstacleMaterialEnum.BARRIER,
241241
collidable=True
242242
)
243-
parking_obstacles[obstacle_id] = new_obstacle
243+
parking_obstacles[f"parking_obstacle_{obstacle_id}"] = new_obstacle
244244
obstacle_id += 1
245245

246246
# Constructing goal pose
@@ -253,8 +253,19 @@ def update(self, cone_obstacles: Dict[str, Obstacle]):
253253
yaw=yaw,
254254
pitch=0.0,
255255
roll=0.0,
256-
frame=ObjectFrameEnum.CURRENT
256+
frame=ObjectFrameEnum.START
257257
)
258258

259+
DISTANCE_THRESHOLD = 8.0
260+
if self.euclidean_distance((x,y), state) > DISTANCE_THRESHOLD: # we are not close enough to the parking spot
261+
return None
262+
259263
new_state = [goal_pose, parking_obstacles]
260-
return new_state
264+
return new_state
265+
266+
def euclidean_distance(self, point, state):
267+
x, y = point
268+
vehicle_x = state.vehicle.pose.x
269+
vehicle_y = state.vehicle.pose.y
270+
distance = np.sqrt((x - vehicle_x) ** 2 + (y - vehicle_y) ** 2)
271+
return distance

GEMstack/onboard/planning/astar.py

Lines changed: 267 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,267 @@
1+
""" generic A-Star path searching algorithm (https://github.com/jrialland/python-astar/blob/master/tests/basic/test_basic.py) """
2+
# @TODO make it so we return the best path as discussed in class
3+
# In class, we discussed that we should have a terminal function
4+
# which approximates the cost_to_go and returns the path to the node
5+
# with the least cost_to_go + terminal_cost
6+
7+
from abc import ABC, abstractmethod
8+
from typing import Callable, Dict, Iterable, Union, TypeVar, Generic
9+
from math import inf as infinity
10+
from operator import attrgetter
11+
import heapq
12+
13+
# introduce generic type
14+
T = TypeVar("T")
15+
16+
17+
################################################################################
18+
class SearchNode(Generic[T]):
19+
"""Representation of a search node"""
20+
21+
__slots__ = ("data", "gscore", "fscore", "tscore", "closed", "came_from", "in_openset", "cache")
22+
23+
def __init__(
24+
self, data: T, gscore: float = infinity, fscore: float = infinity, tscore:float = infinity
25+
) -> None:
26+
self.data = data
27+
self.gscore = gscore
28+
self.fscore = fscore
29+
self.tscore = tscore
30+
self.closed = False
31+
self.in_openset = False
32+
self.came_from: Union[None, SearchNode[T]] = None
33+
self.cache: Any = None
34+
35+
def __lt__(self, b: "SearchNode[T]") -> bool:
36+
"""Natural order is based on the fscore value & is used by heapq operations"""
37+
return self.fscore < b.fscore
38+
39+
40+
################################################################################
41+
class SearchNodeDict(Dict[T, SearchNode[T]]):
42+
"""A dict that returns a new SearchNode when a key is missing"""
43+
44+
def __missing__(self, k) -> SearchNode[T]:
45+
v = SearchNode(k)
46+
self.__setitem__(k, v)
47+
return v
48+
49+
50+
################################################################################
51+
SNType = TypeVar("SNType", bound=SearchNode)
52+
53+
54+
class OpenSet(Generic[SNType]):
55+
def __init__(self) -> None:
56+
self.heap: list[SNType] = []
57+
58+
def push(self, item: SNType) -> None:
59+
item.in_openset = True
60+
heapq.heappush(self.heap, item)
61+
62+
def pop(self) -> SNType:
63+
item = heapq.heappop(self.heap)
64+
item.in_openset = False
65+
return item
66+
67+
def remove(self, item: SNType) -> None:
68+
idx = self.heap.index(item)
69+
item.in_openset = False
70+
item = self.heap.pop()
71+
if idx < len(self.heap):
72+
self.heap[idx] = item
73+
# Fix heap invariants
74+
heapq._siftup(self.heap, idx)
75+
heapq._siftdown(self.heap, 0, idx)
76+
77+
def __len__(self) -> int:
78+
return len(self.heap)
79+
80+
81+
################################################################################*
82+
83+
84+
class AStar(ABC, Generic[T]):
85+
__slots__ = ()
86+
87+
@abstractmethod
88+
def heuristic_cost_estimate(self, current: T, goal: T) -> float:
89+
"""
90+
Computes the estimated (rough) distance between a node and the goal.
91+
The second parameter is always the goal.
92+
93+
This method must be implemented in a subclass.
94+
"""
95+
raise NotImplementedError
96+
97+
@abstractmethod
98+
def terminal_cost_estimate(self, current: T, goal: T) -> float:
99+
"""Computes the estimated distance between a node and the goal.
100+
This function is called after all iterations of A* have been run
101+
and is used to determine the closest node to the goal found so far.
102+
103+
This method must be implemented in a subclass.
104+
105+
Args:
106+
current (T): Current T
107+
goal (T): goal T
108+
109+
Returns:
110+
float: _description_
111+
"""
112+
raise NotImplementedError
113+
114+
def distance_between(self, n1: T, n2: T) -> float:
115+
"""
116+
Gives the real distance between two adjacent nodes n1 and n2 (i.e n2
117+
belongs to the list of n1's neighbors).
118+
n2 is guaranteed to belong to the list returned by the call to neighbors(n1).
119+
120+
This method (or "path_distance_between") must be implemented in a subclass.
121+
"""
122+
raise NotImplementedError
123+
124+
def path_distance_between(self, n1: SearchNode[T], n2: SearchNode[T]) -> float:
125+
"""
126+
Gives the real distance between the node n1 and its neighbor n2.
127+
n2 is guaranteed to belong to the list returned by the call to
128+
path_neighbors(n1).
129+
130+
Calls "distance_between"`by default.
131+
"""
132+
return self.distance_between(n1.data, n2.data)
133+
134+
def neighbors(self, node: T) -> Iterable[T]:
135+
"""
136+
For a given node, returns (or yields) the list of its neighbors.
137+
138+
This method (or "path_neighbors") must be implemented in a subclass.
139+
"""
140+
raise NotImplementedError
141+
142+
def path_neighbors(self, node: SearchNode[T]) -> Iterable[T]:
143+
"""
144+
For a given node, returns (or yields) the list of its reachable neighbors.
145+
Calls "neighbors" by default.
146+
"""
147+
return self.neighbors(node.data)
148+
149+
def _neighbors(self, current: SearchNode[T], search_nodes: SearchNodeDict[T]) -> Iterable[SearchNode]:
150+
return (search_nodes[n] for n in self.path_neighbors(current))
151+
152+
def is_goal_reached(self, current: T, goal: T) -> bool:
153+
"""
154+
Returns true when we can consider that 'current' is the goal.
155+
The default implementation simply compares `current == goal`, but this
156+
method can be overwritten in a subclass to provide more refined checks.
157+
"""
158+
return current == goal
159+
160+
def reconstruct_path(self, last: SearchNode, reversePath=False) -> Iterable[T]:
161+
def _gen():
162+
current = last
163+
while current:
164+
yield current.data
165+
current = current.came_from
166+
167+
if reversePath:
168+
return _gen()
169+
else:
170+
return reversed(list(_gen()))
171+
172+
def astar(
173+
self, start: T, goal: T, reversePath: bool = False, iterations: int = 5000
174+
) -> Union[Iterable[T], None]:
175+
if self.is_goal_reached(start, goal):
176+
return [start]
177+
178+
openSet: OpenSet[SearchNode[T]] = OpenSet()
179+
searchNodes: SearchNodeDict[T] = SearchNodeDict()
180+
startNode = searchNodes[start] = SearchNode(
181+
start, gscore=0.0, fscore=self.heuristic_cost_estimate(start, goal)
182+
)
183+
openSet.push(startNode)
184+
bestNode = startNode
185+
186+
iteration = 0
187+
188+
while openSet and iteration < iterations:
189+
current = openSet.pop()
190+
191+
if self.is_goal_reached(current.data, goal):
192+
return self.reconstruct_path(current, reversePath)
193+
194+
current.closed = True
195+
196+
for neighbor in self._neighbors(current, searchNodes):
197+
if neighbor.closed:
198+
continue
199+
200+
gscore = current.gscore + self.path_distance_between(current, neighbor)
201+
202+
if gscore >= neighbor.gscore:
203+
continue
204+
205+
fscore = gscore + self.heuristic_cost_estimate(
206+
neighbor.data, goal
207+
)
208+
tscore = self.terminal_cost_estimate(
209+
neighbor.data, goal
210+
)
211+
212+
# print(f"Checking node: {neighbor.data} with tscore {tscore}")
213+
if tscore < bestNode.tscore:
214+
# print(f"Found a better node: {neighbor.data} with tscore {tscore}")
215+
bestNode = neighbor
216+
217+
if neighbor.in_openset:
218+
if neighbor.fscore < fscore:
219+
# the new path to this node isn't better
220+
continue
221+
222+
# we have to remove the item from the heap, as its score has changed
223+
openSet.remove(neighbor)
224+
225+
# update the node
226+
neighbor.came_from = current
227+
neighbor.gscore = gscore
228+
neighbor.fscore = fscore
229+
neighbor.tscore = tscore
230+
231+
openSet.push(neighbor)
232+
233+
iteration += 1
234+
235+
# print("Warning: A* search failed to find a path")
236+
return self.reconstruct_path(bestNode, reversePath)
237+
238+
239+
################################################################################
240+
U = TypeVar("U")
241+
242+
243+
def find_path(
244+
start: U,
245+
goal: U,
246+
neighbors_fnct: Callable[[U], Iterable[U]],
247+
reversePath=False,
248+
heuristic_cost_estimate_fnct: Callable[[U, U], float] = lambda a, b: infinity,
249+
distance_between_fnct: Callable[[U, U], float] = lambda a, b: 1.0,
250+
is_goal_reached_fnct: Callable[[U, U], bool] = lambda a, b: a == b,
251+
) -> Union[Iterable[U], None]:
252+
"""A non-class version of the path finding algorithm"""
253+
254+
class FindPath(AStar):
255+
def heuristic_cost_estimate(self, current: U, goal: U) -> float:
256+
return heuristic_cost_estimate_fnct(current, goal) # type: ignore
257+
258+
def distance_between(self, n1: U, n2: U) -> float:
259+
return distance_between_fnct(n1, n2)
260+
261+
def neighbors(self, node) -> Iterable[U]:
262+
return neighbors_fnct(node) # type: ignore
263+
264+
def is_goal_reached(self, current: U, goal: U) -> bool:
265+
return is_goal_reached_fnct(current, goal)
266+
267+
return FindPath().astar(start, goal, reversePath)

0 commit comments

Comments
 (0)