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