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