Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
lattice_generator.py
1 # Copyright (c) 2021, Matthew Booker
2 #
3 # Licensed under the Apache License, Version 2.0 (the "License");
4 # you may not use this file except in compliance with the License.
5 # You may obtain a copy of the License at
6 #
7 # http://www.apache.org/licenses/LICENSE-2.0
8 #
9 # Unless required by applicable law or agreed to in writing, software
10 # distributed under the License is distributed on an "AS IS" BASIS,
11 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 # See the License for the specific language governing permissions and
13 # limitations under the License. Reserved.
14 
15 from collections import defaultdict
16 from enum import Enum
17 from typing import Any, Dict, List, Tuple, TypedDict
18 
19 from nav2_smac_planner.lattice_primitives.helper import angle_difference, interpolate_yaws
20 from nav2_smac_planner.lattice_primitives.trajectory import (AnyFloat, FloatNDArray, Path,
21  Trajectory, TrajectoryParameters)
22 from nav2_smac_planner.lattice_primitives.trajectory_generator import TrajectoryGenerator
23 import numpy as np
24 from rtree import index
25 
26 
27 class ConfigDict(TypedDict):
28  grid_resolution: float
29  turning_radius: float
30  stopping_threshold: int
31  num_of_headings: int
32  motion_model: str
33 
34 
36  """
37  Handles all the logic for computing the minimal control set.
38 
39  Computes the minimal control set for a vehicle given its parameters.
40  Includes handling the propagating and searching along wavefronts as
41  well as determining if a trajectory is part of the minimal set based
42  on previously added trajectories.
43  """
44 
45  class MotionModel(Enum):
46  """An Enum used for determining the motion model to use."""
47 
48  ACKERMANN = 1
49  DIFF = 2
50  OMNI = 3
51 
52  class Flip(Enum):
53  """An Enum used for determining how a trajectory should be flipped."""
54 
55  X = 1
56  Y = 2
57  BOTH = 3
58 
59  def __init__(self, config: ConfigDict):
60  """Init the lattice generator from the user supplied config."""
61  self.trajectory_generatortrajectory_generator = TrajectoryGenerator(config)
62  self.grid_resolutiongrid_resolution = config['grid_resolution']
63  self.turning_radiusturning_radius = config['turning_radius']
64  self.stopping_thresholdstopping_threshold = config['stopping_threshold']
65  self.num_of_headingsnum_of_headings = config['num_of_headings']
66  self.headingsheadings = self._get_heading_discretization_get_heading_discretization(config['num_of_headings'])
67 
68  self.motion_modelmotion_model = self.MotionModelMotionModel[config['motion_model'].upper()]
69 
70  self.DISTANCE_THRESHOLDDISTANCE_THRESHOLD = 0.5 * self.grid_resolutiongrid_resolution
71  self.ROTATION_THRESHOLDROTATION_THRESHOLD = 0.5 * (2 * np.pi / self.num_of_headingsnum_of_headings)
72 
73  def _get_wave_front_points(self, pos: int) -> FloatNDArray:
74  """
75  Calculate the end points that lie on the wave front.
76 
77  Uses the user supplied grid resolution to calculate the
78  valid end points that lie on a wave front at a discrete
79  interval away from the origin.
80 
81  Args:
82  pos: int
83  The number of discrete intervals of grid resolution
84  away from the origin to generate the wave points at
85 
86  Returns
87  -------
88  np.array
89  An array of coordinates
90 
91  """
92  positions = []
93 
94  max_point_coord = self.grid_resolutiongrid_resolution * pos
95 
96  for i in range(pos):
97  varying_point_coord = self.grid_resolutiongrid_resolution * i
98 
99  # Change the y and keep x at max
100  positions.append((max_point_coord, varying_point_coord))
101 
102  # Change the x and keep y at max
103  positions.append((varying_point_coord, max_point_coord))
104 
105  # Append the corner
106  positions.append((max_point_coord, max_point_coord))
107 
108  return np.array(positions)
109 
110  def _get_heading_discretization(self, number_of_headings: int) -> List[int]:
111  """
112  Calculate the heading discretization based on the number of headings.
113 
114  Does not uniformly generate headings but instead generates a set of
115  discrete headings that is better suited for straight line trajectories.
116 
117  Args:
118  number_of_headings: int
119  The number of headings to discretize a 360 degree turn into
120 
121  Returns
122  -------
123  list
124  A list of headings in radians
125 
126  """
127  max_val = int(number_of_headings / 8)
128 
129  outer_edge_x = []
130  outer_edge_y = []
131 
132  # Generate points that lie on the perimeter of the surface
133  # of a square with sides of length max_val
134  for i in range(-max_val, max_val + 1):
135  outer_edge_x.extend([i, i])
136  outer_edge_y.extend([-max_val, max_val])
137 
138  if i != max_val and i != -max_val:
139  outer_edge_x.extend([-max_val, max_val])
140  outer_edge_y.extend([i, i])
141 
142  return sorted([np.arctan2(j, i) for i, j in zip(outer_edge_x, outer_edge_y)])
143 
144  def _point_to_line_distance(self, p1: FloatNDArray, p2: FloatNDArray,
145  q: FloatNDArray) -> AnyFloat:
146  """
147  Return the shortest distance from a point to a line segment.
148 
149  Args:
150  p1: np.array(2,)
151  Start point of line segment
152  p2: np.array(2,)
153  End point of line segment
154  q: np.array(2,)
155  Point to get distance away from line of
156 
157  Returns
158  -------
159  float
160  The shortest distance between q and line segment p1p2
161 
162  """
163  # Get back the l2-norm without the square root
164  l2 = np.inner(p1 - p2, p1 - p2)
165 
166  if l2 == 0:
167  return np.linalg.norm(p1 - q)
168 
169  # Ensure t lies in [0, 1]
170  t = max(0, min(1, np.dot(q - p1, p2 - p1) / l2))
171  projected_point = p1 + t * (p2 - p1)
172 
173  return np.linalg.norm(q - projected_point)
174 
175  def _is_minimal_trajectory(
176  self, trajectory: Trajectory, prior_end_poses: index.Rtree
177  ) -> bool:
178  """
179  Determine whether a trajectory is a minimal trajectory.
180 
181  Uses an RTree for speedup.
182 
183  Args:
184  trajectory: Trajectory
185  The trajectory to check
186  prior_end_poses: RTree
187  An RTree holding the current minimal set of trajectories
188 
189  Returns
190  -------
191  bool
192  True if the trajectory is a minimal trajectory otherwise false
193 
194  """
195  # Iterate over line segments in the trajectory
196  for x1, y1, x2, y2, yaw in zip(
197  trajectory.path.xs[:-1],
198  trajectory.path.ys[:-1],
199  trajectory.path.xs[1:],
200  trajectory.path.ys[1:],
201  trajectory.path.yaws[:-1],
202  ):
203 
204  p1 = np.array([x1, y1])
205  p2 = np.array([x2, y2])
206 
207  # Create a bounding box search region
208  # around the line segment
209  left_bb = min(x1, x2) - self.DISTANCE_THRESHOLDDISTANCE_THRESHOLD
210  right_bb = max(x1, x2) + self.DISTANCE_THRESHOLDDISTANCE_THRESHOLD
211  top_bb = max(y1, y2) + self.DISTANCE_THRESHOLDDISTANCE_THRESHOLD
212  bottom_bb = min(y1, y2) - self.DISTANCE_THRESHOLDDISTANCE_THRESHOLD
213 
214  # For any previous end points in the search region we
215  # check the distance to that point and the angle
216  # difference. If they are within threshold then this
217  # trajectory can be composed from a previous trajectory
218  for prior_end_pose in prior_end_poses.intersection(
219  (left_bb, bottom_bb, right_bb, top_bb), objects='raw'
220  ):
221  if (
222  self._point_to_line_distance_point_to_line_distance(p1, p2, prior_end_pose[:-1])
223  < self.DISTANCE_THRESHOLDDISTANCE_THRESHOLD
224  and angle_difference(yaw, prior_end_pose[-1])
225  < self.ROTATION_THRESHOLDROTATION_THRESHOLD
226  ):
227  return False
228 
229  return True
230 
231  def _compute_min_trajectory_length(self) -> float:
232  """
233  Compute the minimum trajectory length for the given parameters.
234 
235  The minimum trajectory length is defined as the length needed
236  for the sharpest possible turn to move from 0 degrees to the next
237  discrete heading. Since the distance between headings is not uniform
238  we take the smallest possible difference.
239 
240  Returns
241  -------
242  float
243  The minimal length of a trajectory
244 
245  """
246  # Compute arc length for a turn that moves from 0 degrees to
247  # the minimum heading difference
248  heading_diff = [
249  abs(self.headingsheadings[i + 1] - self.headingsheadings[i])
250  for i in range(len(self.headingsheadings) - 1)
251  ]
252 
253  return self.turning_radiusturning_radius * min(heading_diff)
254 
255  def _generate_minimal_spanning_set(self) -> Dict[float, List[Trajectory]]:
256  """
257  Generate the minimal spanning set.
258 
259  Iteratves over all possible trajectories and keeps only those that
260  are part of the minimal set.
261 
262  Returns
263  -------
264  dict
265  A dictionary where the key is the start_angle and the value is
266  a list of trajectories that begin at that angle
267 
268  """
269  quadrant1_end_poses: Dict[int, List[Tuple[Any, int]]] = defaultdict(list)
270 
271  # Since we only compute for quadrant 1 we only need headings between
272  # 0 and 90 degrees
273  initial_headings = sorted(
274  filter(lambda x: 0 <= x and x <= np.pi / 2, self.headingsheadings)
275  )
276 
277  # Use the minimum trajectory length to find the starting wave front
278  min_trajectory_length = self._compute_min_trajectory_length_compute_min_trajectory_length()
279  wave_front_start_pos = int(
280  np.round(min_trajectory_length / self.grid_resolutiongrid_resolution)
281  )
282 
283  for start_heading in initial_headings:
284  iterations_without_trajectory = 0
285 
286  prior_end_poses = index.Index()
287 
288  wave_front_cur_pos = wave_front_start_pos
289 
290  # To get target headings: sort headings radially and remove those
291  # that are more than 90 degrees away
292  target_headings = sorted(
293  self.headingsheadings, key=lambda x: (abs(x - start_heading), -x)
294  )
295  target_headings = list(
296  filter(lambda x: abs(start_heading - x) <= np.pi / 2, target_headings)
297  )
298 
299  while iterations_without_trajectory < self.stopping_thresholdstopping_threshold:
300  iterations_without_trajectory += 1
301 
302  # Generate x,y coordinates for current wave front
303  positions = self._get_wave_front_points_get_wave_front_points(wave_front_cur_pos)
304 
305  for target_point in positions:
306  for target_heading in target_headings:
307  # Use 10% of grid separation for finer granularity
308  # when checking if trajectory overlaps another already
309  # seen trajectory
310  trajectory = self.trajectory_generatortrajectory_generator.generate_trajectory(
311  target_point,
312  start_heading,
313  target_heading,
314  0.1 * self.grid_resolutiongrid_resolution,
315  )
316 
317  if trajectory is not None:
318  # Check if path overlaps something in minimal
319  # spanning set
320  if self._is_minimal_trajectory_is_minimal_trajectory(trajectory, prior_end_poses):
321 
322  # Add end pose to minimal set
323  new_end_pose = np.array(
324  [target_point[0], target_point[1], target_heading]
325  )
326 
327  quadrant1_end_poses[start_heading].append(
328  (target_point, target_heading)
329  )
330 
331  # Create a new bounding box in the RTree
332  # for this trajectory
333  left_bb = target_point[0] - self.DISTANCE_THRESHOLDDISTANCE_THRESHOLD
334  right_bb = target_point[0] + self.DISTANCE_THRESHOLDDISTANCE_THRESHOLD
335  bottom_bb = target_point[1] - self.DISTANCE_THRESHOLDDISTANCE_THRESHOLD
336  top_bb = target_point[1] + self.DISTANCE_THRESHOLDDISTANCE_THRESHOLD
337 
338  prior_end_poses.insert(
339  0,
340  (left_bb, bottom_bb, right_bb, top_bb),
341  new_end_pose,
342  )
343 
344  iterations_without_trajectory = 0
345 
346  wave_front_cur_pos += 1
347 
348  # Once we have found the minimal trajectory set for quadrant 1
349  # we can leverage symmetry to create the complete minimal set
350  return self._create_complete_minimal_spanning_set_create_complete_minimal_spanning_set(quadrant1_end_poses)
351 
352  def _flip_angle(self, angle: int, flip_type: Flip) -> float:
353  """
354  Return the the appropriate flip of the angle in self.headings.
355 
356  Args:
357  angle: float
358  The angle to flip
359  flip_type: Flip
360  Whether to flip acrpss X axis, Y axis, or both
361 
362  Returns
363  -------
364  float
365  The angle in self.heading that is the appropriate flip
366 
367  """
368  angle_idx = self.headingsheadings.index(angle)
369 
370  if flip_type == self.FlipFlip.X:
371  heading_idx = (self.num_of_headingsnum_of_headings / 2 - 1) - angle_idx - 1
372  elif flip_type == self.FlipFlip.Y:
373  heading_idx = self.num_of_headingsnum_of_headings - angle_idx - 2
374  elif flip_type == self.FlipFlip.BOTH:
375  heading_idx = (
376  angle_idx - (self.num_of_headingsnum_of_headings / 2)
377  ) % self.num_of_headingsnum_of_headings
378  else:
379  raise Exception(f'Unsupported flip type: {flip_type}')
380 
381  return self.headingsheadings[int(heading_idx)]
382 
383  def _create_complete_minimal_spanning_set(
384  self, single_quadrant_minimal_set: Dict[int, List[Tuple[Any, int]]]
385  ) -> Dict[float, List[Trajectory]]:
386  """
387  Create the full minimal spanning set from a single quadrant set.
388 
389  Exploits the symmetry between the quadrants to create the full set.
390  This is done by flipping every trajectory in the first quadrant across
391  either the X-axis, Y-axis, or both axes.
392 
393  Args:
394  single_quadrant_minimal_set: dict
395  The minimal set for quadrant 1 (positive x and positive y)
396 
397  Returns
398  -------
399  dict
400  The complete minimal spanning set containing the trajectories
401  in all quadrants
402 
403  """
404  all_trajectories: Dict[float, List[Trajectory]] = defaultdict(list)
405 
406  for start_angle in single_quadrant_minimal_set.keys():
407 
408  for end_point, end_angle in single_quadrant_minimal_set[start_angle]:
409 
410  x, y = end_point
411 
412  # Prevent double adding trajectories that lie on axes
413  # (i.e. start and end angle are either both 0 or both pi/2)
414  if start_angle == 0 and end_angle == 0:
415  unflipped_start_angle = 0.0
416  flipped_x_start_angle = np.pi
417 
418  unflipped_end_angle = 0.0
419  flipped_x_end_angle = np.pi
420 
421  # Generate trajectories from calculated parameters
422  unflipped_trajectory = (
423  self.trajectory_generatortrajectory_generator.generate_trajectory(
424  np.array([x, y]),
425  unflipped_start_angle,
426  unflipped_end_angle,
427  self.grid_resolutiongrid_resolution,
428  )
429  )
430  flipped_x_trajectory = (
431  self.trajectory_generatortrajectory_generator.generate_trajectory(
432  np.array([-x, -y]),
433  flipped_x_start_angle,
434  flipped_x_end_angle,
435  self.grid_resolutiongrid_resolution,
436  )
437  )
438 
439  if unflipped_trajectory is None or flipped_x_trajectory is None:
440  raise ValueError('No trajectory was found')
441 
442  all_trajectories[
443  unflipped_trajectory.parameters.start_angle
444  ].append(unflipped_trajectory)
445 
446  all_trajectories[
447  flipped_x_trajectory.parameters.start_angle
448  ].append(flipped_x_trajectory)
449 
450  elif abs(start_angle) == np.pi / 2 and abs(end_angle) == np.pi / 2:
451  unflipped_start_angle = np.pi / 2
452  flipped_y_start_angle = -np.pi / 2
453 
454  unflipped_end_angle = np.pi / 2
455  flipped_y_end_angle = -np.pi / 2
456 
457  # Generate trajectories from calculated parameters
458  unflipped_trajectory = (
459  self.trajectory_generatortrajectory_generator.generate_trajectory(
460  np.array([-x, y]),
461  unflipped_start_angle,
462  unflipped_end_angle,
463  self.grid_resolutiongrid_resolution,
464  )
465  )
466 
467  flipped_y_trajectory = (
468  self.trajectory_generatortrajectory_generator.generate_trajectory(
469  np.array([x, -y]),
470  flipped_y_start_angle,
471  flipped_y_end_angle,
472  self.grid_resolutiongrid_resolution,
473  )
474  )
475 
476  if unflipped_trajectory is None or flipped_y_trajectory is None:
477  raise ValueError('No trajectory was found')
478 
479  all_trajectories[
480  unflipped_trajectory.parameters.start_angle
481  ].append(unflipped_trajectory)
482  all_trajectories[
483  flipped_y_trajectory.parameters.start_angle
484  ].append(flipped_y_trajectory)
485 
486  else:
487  unflipped_start_angle = start_angle
488  flipped_x_start_angle = self._flip_angle_flip_angle(start_angle, self.FlipFlip.X)
489  flipped_y_start_angle = self._flip_angle_flip_angle(start_angle, self.FlipFlip.Y)
490  flipped_xy_start_angle = self._flip_angle_flip_angle(
491  start_angle, self.FlipFlip.BOTH
492  )
493 
494  unflipped_end_angle = end_angle
495  flipped_x_end_angle = self._flip_angle_flip_angle(end_angle, self.FlipFlip.X)
496  flipped_y_end_angle = self._flip_angle_flip_angle(end_angle, self.FlipFlip.Y)
497  flipped_xy_end_angle = self._flip_angle_flip_angle(end_angle, self.FlipFlip.BOTH)
498 
499  # Generate trajectories from calculated parameters
500  unflipped_trajectory = (
501  self.trajectory_generatortrajectory_generator.generate_trajectory(
502  np.array([x, y]),
503  unflipped_start_angle,
504  unflipped_end_angle,
505  self.grid_resolutiongrid_resolution,
506  )
507  )
508  flipped_x_trajectory = (
509  self.trajectory_generatortrajectory_generator.generate_trajectory(
510  np.array([-x, y]),
511  flipped_x_start_angle,
512  flipped_x_end_angle,
513  self.grid_resolutiongrid_resolution,
514  )
515  )
516  flipped_y_trajectory = (
517  self.trajectory_generatortrajectory_generator.generate_trajectory(
518  np.array([x, -y]),
519  flipped_y_start_angle,
520  flipped_y_end_angle,
521  self.grid_resolutiongrid_resolution,
522  )
523  )
524  flipped_xy_trajectory = (
525  self.trajectory_generatortrajectory_generator.generate_trajectory(
526  np.array([-x, -y]),
527  flipped_xy_start_angle,
528  flipped_xy_end_angle,
529  self.grid_resolutiongrid_resolution,
530  )
531  )
532 
533  if (unflipped_trajectory is None or flipped_y_trajectory is None or
534  flipped_x_trajectory is None or flipped_xy_trajectory is None):
535  raise ValueError('No trajectory was found')
536 
537  all_trajectories[
538  unflipped_trajectory.parameters.start_angle
539  ].append(unflipped_trajectory)
540  all_trajectories[
541  flipped_x_trajectory.parameters.start_angle
542  ].append(flipped_x_trajectory)
543  all_trajectories[
544  flipped_y_trajectory.parameters.start_angle
545  ].append(flipped_y_trajectory)
546  all_trajectories[
547  flipped_xy_trajectory.parameters.start_angle
548  ].append(flipped_xy_trajectory)
549 
550  return all_trajectories
551 
552  def _handle_motion_model(self, spanning_set: Dict[float, List[Trajectory]]
553  ) -> Dict[float, List[Trajectory]]:
554  """
555  Add the appropriate motions for the user supplied motion model.
556 
557  Ackerman: No additional trajectories
558 
559  Diff: In place turns to the right and left
560 
561  Omni: Diff + Sliding movements to right and left
562 
563  Args:
564  spanning set: dict
565  The minimal spanning set
566 
567  Returns
568  -------
569  dict
570  The minimal spanning set with additional trajectories based
571  on the motion model
572 
573  """
574  if self.motion_modelmotion_model == self.MotionModelMotionModel.ACKERMANN:
575  return spanning_set
576 
577  elif self.motion_modelmotion_model == self.MotionModelMotionModel.DIFF:
578  diff_spanning_set = self._add_in_place_turns_add_in_place_turns(spanning_set)
579  return diff_spanning_set
580 
581  elif self.motion_modelmotion_model == self.MotionModelMotionModel.OMNI:
582  omni_spanning_set = self._add_in_place_turns_add_in_place_turns(spanning_set)
583  omni_spanning_set = self._add_horizontal_motions_add_horizontal_motions(omni_spanning_set)
584  return omni_spanning_set
585 
586  else:
587  print('No handling implemented for Motion Model: ' + f'{self.motion_model}')
588  raise NotImplementedError
589 
590  def _add_in_place_turns(self, spanning_set: Dict[float, List[Trajectory]]
591  ) -> Dict[float, List[Trajectory]]:
592  """
593  Add in place turns to the spanning set.
594 
595  In place turns are trajectories with only a rotational component and
596  only shift a single angular heading step
597 
598  Args:
599  spanning_set: dict
600  The minimal spanning set
601 
602  Returns
603  -------
604  dict
605  The minimal spanning set containing additional in place turns
606  for each start angle
607 
608  """
609  all_angles = sorted(spanning_set.keys())
610 
611  for idx, start_angle in enumerate(all_angles):
612  prev_angle_idx = idx - 1 if idx - 1 >= 0 else len(all_angles) - 1
613  next_angle_idx = idx + 1 if idx + 1 < len(all_angles) else 0
614 
615  prev_angle = all_angles[prev_angle_idx]
616  next_angle = all_angles[next_angle_idx]
617 
618  left_turn_params = TrajectoryParameters.no_arc(
619  end_point=np.array([0, 0]),
620  start_angle=start_angle,
621  end_angle=next_angle,
622  )
623  right_turn_params = TrajectoryParameters.no_arc(
624  end_point=np.array([0, 0]),
625  start_angle=start_angle,
626  end_angle=prev_angle,
627  )
628 
629  # Calculate number of steps needed to rotate by roughly 10 degrees
630  # for each pose
631  angle_dif = angle_difference(start_angle, next_angle)
632  steps = int(round(angle_dif / np.deg2rad(10))) + 1
633 
634  position = np.full(steps, 0)
635  left_yaws = interpolate_yaws(start_angle, next_angle, True, steps)
636  right_yaws = interpolate_yaws(start_angle, prev_angle, False, steps)
637 
638  left_turn_path = Path(xs=position, ys=position, yaws=left_yaws)
639  right_turn_path = Path(xs=position, ys=position, yaws=right_yaws)
640 
641  left_turn = Trajectory(parameters=left_turn_params, path=left_turn_path)
642  right_turn = Trajectory(parameters=right_turn_params, path=right_turn_path)
643 
644  spanning_set[start_angle].append(left_turn)
645  spanning_set[start_angle].append(right_turn)
646 
647  return spanning_set
648 
649  def _add_horizontal_motions(self, spanning_set: Dict[float, List[Trajectory]]
650  ) -> Dict[float, List[Trajectory]]:
651  """
652  Add horizontal sliding motions to the spanning set.
653 
654  The horizontal sliding motions are simply straight line trajectories
655  at 90 degrees to every start angle in the spanning set. The yaw of these
656  trajectories is the same as the start angle for which it is generated.
657 
658  Args:
659  spanning_set: dict
660  The minimal spanning set
661 
662  Returns
663  -------
664  dict
665  The minimal spanning set containing additional sliding motions
666  for each start angle
667 
668  """
669  # Calculate the offset in the headings list that represents an
670  # angle change of 90 degrees
671  idx_offset = int(self.num_of_headingsnum_of_headings / 4)
672 
673  for idx, angle in enumerate(self.headingsheadings):
674 
675  # Copy the straight line trajectory for the start angle that
676  # is 90 degrees to the left
677  left_angle_idx = int((idx + idx_offset) % self.num_of_headingsnum_of_headings)
678  left_angle = self.headingsheadings[left_angle_idx]
679  left_trajectories = spanning_set[left_angle]
680  left_straight_trajectory = next(
681  t for t in left_trajectories if t.parameters.end_angle == left_angle
682  )
683 
684  # Copy the straight line trajectory for the start angle that
685  # is 90 degrees to the right
686  right_angle_idx = int((idx - idx_offset) % self.num_of_headingsnum_of_headings)
687  right_angle = self.headingsheadings[right_angle_idx]
688  right_trajectories = spanning_set[right_angle]
689  right_straight_trajectory = next(
690  t for t in right_trajectories if t.parameters.end_angle == right_angle
691  )
692 
693  yaws = np.full(
694  len(left_straight_trajectory.path.xs), angle, dtype=np.float64
695  )
696 
697  # Create a new set of parameters that represents
698  # the left sliding motion
699  parmas_l = left_straight_trajectory.parameters
700  left_motion_parameters = TrajectoryParameters(
701  parmas_l.turning_radius,
702  parmas_l.x_offset,
703  parmas_l.y_offset,
704  parmas_l.end_point,
705  angle,
706  angle,
707  parmas_l.left_turn,
708  parmas_l.arc_start_point,
709  parmas_l.arc_end_point,
710  )
711 
712  # Create a new set of parameters that represents
713  # the right sliding motion
714  params_r = right_straight_trajectory.parameters
715  right_motion_parameters = TrajectoryParameters(
716  params_r.turning_radius,
717  params_r.x_offset,
718  params_r.y_offset,
719  params_r.end_point,
720  angle,
721  angle,
722  params_r.left_turn,
723  parmas_l.arc_start_point,
724  parmas_l.arc_end_point,
725  )
726 
727  left_motion = Trajectory(
728  parameters=left_motion_parameters,
729  path=Path(
730  xs=left_straight_trajectory.path.xs,
731  ys=left_straight_trajectory.path.ys,
732  yaws=yaws,
733  ),
734  )
735 
736  right_motion = Trajectory(
737  parameters=right_motion_parameters,
738  path=Path(
739  xs=right_straight_trajectory.path.xs,
740  ys=right_straight_trajectory.path.ys,
741  yaws=yaws,
742  ),
743  )
744 
745  spanning_set[angle].append(left_motion)
746  spanning_set[angle].append(right_motion)
747 
748  return spanning_set
749 
750  def run(self) -> Dict[float, List[Trajectory]]:
751  """
752  Run the lattice generator.
753 
754  Returns
755  -------
756  dict
757  The minimal spanning set including additional motions for the
758  specified motion model
759 
760  """
761  complete_spanning_set = self._generate_minimal_spanning_set_generate_minimal_spanning_set()
762 
763  return self._handle_motion_model_handle_motion_model(complete_spanning_set)
Dict[float, List[Trajectory]] _add_horizontal_motions(self, Dict[float, List[Trajectory]] spanning_set)
bool _is_minimal_trajectory(self, Trajectory trajectory, index.Rtree prior_end_poses)
float _flip_angle(self, int angle, Flip flip_type)
List[int] _get_heading_discretization(self, int number_of_headings)
Dict[float, List[Trajectory]] _add_in_place_turns(self, Dict[float, List[Trajectory]] spanning_set)
Dict[float, List[Trajectory]] _generate_minimal_spanning_set(self)
Dict[float, List[Trajectory]] _create_complete_minimal_spanning_set(self, Dict[int, List[Tuple[Any, int]]] single_quadrant_minimal_set)
AnyFloat _point_to_line_distance(self, FloatNDArray p1, FloatNDArray p2, FloatNDArray q)
Dict[float, List[Trajectory]] _handle_motion_model(self, Dict[float, List[Trajectory]] spanning_set)