path_planning/rrt_star/
rrt_star.rs

1/* Copyright (C) 2020 Dylan Staatz - All Rights Reserved. */
2
3use kdtree::KdTree;
4use nalgebra::storage::Storage;
5use nalgebra::{Const, SVector, VectorSlice};
6use num_traits::Float;
7use petgraph::stable_graph::NodeIndex;
8use rayon::iter::{IntoParallelIterator, ParallelIterator};
9use serde::{de::DeserializeOwned, Deserialize, Serialize};
10
11use crate::cspace::CSpace;
12use crate::error::{InvalidParamError, Result};
13use crate::obstacles::{Obstacle, ObstacleSpace};
14use crate::path_planner::{MoveGoal, PathPlanner, RobotSpecs};
15use crate::scalar::Scalar;
16use crate::trajectories::{
17  FullTrajOwned, FullTrajRefOwned, FullTrajectory, Trajectory,
18};
19use crate::util::math::unit_d_ball_vol;
20
21use super::{Node, RrtStarTree};
22
23/// RRT* generic parameters
24#[derive(Debug, Clone, PartialEq, Serialize, Deserialize)]
25#[serde(bound(
26  serialize = "X: Serialize",
27  deserialize = "X: DeserializeOwned"
28))]
29pub struct RrtStarParams<X> {
30  pub min_cost: X,
31  pub portion: X,
32  pub delta: X,
33  pub gamma: X,
34}
35
36/// RRT* Serializable State information
37#[derive(Debug, Serialize, Deserialize)]
38#[serde(bound(
39  serialize = "X: Serialize, CS::Traj: Serialize, OS: Serialize",
40  deserialize = "X: DeserializeOwned, CS::Traj: DeserializeOwned, OS: DeserializeOwned",
41))]
42pub struct RrtStarState<X, CS, OS, const N: usize>
43where
44  X: Scalar,
45  CS: CSpace<X, N>,
46  OS: ObstacleSpace<X, CS, N>,
47  CS::Traj: Trajectory<X, N>,
48{
49  /// All the nodes with their associated costs and edges that connect them
50  pub tree: RrtStarTree<X, CS::Traj, N>,
51
52  /// The current path being travelled from some point to a node in the tree
53  pub current_path: Option<(SVector<X, N>, CS::Traj, NodeIndex)>,
54
55  /// The last know current pose of the system
56  pub pose: SVector<X, N>,
57
58  /// Tracks the obstacles in the space
59  pub obs_space: OS,
60
61  /// Shrinking ball radius
62  pub radius: X,
63
64  /// Robot specifications
65  pub robot_specs: RobotSpecs<X>,
66
67  // Algorithm Parameters
68  pub params: RrtStarParams<X>,
69}
70
71impl<X, CS, OS, const N: usize> Clone for RrtStarState<X, CS, OS, N>
72where
73  X: Scalar,
74  CS: CSpace<X, N>,
75  OS: ObstacleSpace<X, CS, N>,
76{
77  fn clone(&self) -> Self {
78    Self {
79      tree: self.tree.clone(),
80      current_path: self.current_path.clone(),
81      pose: self.pose.clone(),
82      obs_space: self.obs_space.clone(),
83      radius: self.radius.clone(),
84      robot_specs: self.robot_specs.clone(),
85      params: self.params.clone(),
86    }
87  }
88}
89
90/// RRT* implementation
91pub struct RrtStar<X, CS, OS, const N: usize>
92where
93  X: Scalar,
94  CS: CSpace<X, N>,
95  OS: ObstacleSpace<X, CS, N>,
96{
97  /// All the serializable state information.
98  state: RrtStarState<X, CS, OS, N>,
99
100  /// For fast nearest neighbor searching
101  kdtree: KdTree<X, NodeIndex, [X; N]>,
102
103  /// Configuration space
104  cspace: CS,
105}
106
107impl<X, CS, OS, const N: usize> PathPlanner<X, CS, OS, N>
108  for RrtStar<X, CS, OS, N>
109where
110  X: Scalar,
111  CS: CSpace<X, N> + Send + Sync,
112  CS::Traj: Send + Sync,
113  OS: ObstacleSpace<X, CS, N> + Send + Sync,
114  OS::Obs: Send + Sync,
115{
116  type Params = RrtStarParams<X>;
117  type State = RrtStarState<X, CS, OS, N>;
118
119  fn new(
120    init: SVector<X, N>,
121    goal: SVector<X, N>,
122    robot_specs: RobotSpecs<X>,
123    cspace: CS,
124    obs_space: OS,
125    params: Self::Params,
126  ) -> Result<Self> {
127    let tree = RrtStarTree::new(goal.clone());
128    let current_path = None;
129    let pose = init.clone();
130
131    let mut kdtree: KdTree<X, NodeIndex, [X; N]> = KdTree::new(N.into());
132    kdtree
133      .add(goal.into(), tree.get_goal_idx())
134      .expect("kdtree error");
135
136    let radius = params.delta;
137
138    // Validate robot_radius are greater than 0
139    if !(X::zero() < robot_specs.robot_radius) {
140      Err(InvalidParamError {
141        parameter_name: "robot_specs.robot_radius",
142        parameter_value: format!("{:?}", robot_specs.robot_radius),
143      })?;
144    }
145
146    // Validate sensor_radius are greater than 0
147    if !(X::zero() < robot_specs.sensor_radius) {
148      Err(InvalidParamError {
149        parameter_name: "robot_specs.sensor_radius",
150        parameter_value: format!("{:?}", robot_specs.sensor_radius),
151      })?;
152    }
153
154    // Validate min_cost is in [0, delta)
155    if !(X::zero() <= params.min_cost && params.min_cost < params.delta) {
156      Err(InvalidParamError {
157        parameter_name: "params.min_cost",
158        parameter_value: format!("{:?}", params.min_cost),
159      })?;
160    }
161
162    // Validate portion is between 0 and 1
163    if !(X::zero() < params.portion && params.portion < X::one()) {
164      Err(InvalidParamError {
165        parameter_name: "params.portion",
166        parameter_value: format!("{:?}", params.portion),
167      })?;
168    }
169
170    let state = RrtStarState {
171      tree,
172      current_path,
173      pose,
174      obs_space,
175      radius,
176      robot_specs,
177      params,
178    };
179
180    let mut new = Self {
181      state,
182      kdtree,
183      cspace,
184    };
185
186    new.state.radius = new.shrinking_ball_radius();
187    new.check_gamma();
188
189    // Check that the init and goal locations are in free space
190    if !new.is_free(&init) {
191      Err(InvalidParamError {
192        parameter_name: "init",
193        parameter_value: format!("{:?}", init),
194      })?;
195    }
196    if !new.is_free(&goal) {
197      Err(InvalidParamError {
198        parameter_name: "goal",
199        parameter_value: format!("{:?}", goal),
200      })?;
201    }
202
203    Ok(new)
204  }
205
206  fn create_node(&mut self) -> &Self::State {
207    // Continue to sample points until one is found
208    loop {
209      if let Some(()) = self.try_create_node() {
210        break;
211      }
212    }
213
214    // Update the new radius now that we changed self.count()
215    self.state.radius = self.shrinking_ball_radius();
216    self.get_state()
217  }
218
219  fn sample_node(&mut self) -> Option<&Self::State> {
220    self.try_create_node()?;
221
222    // Update the new radius now if we changed self.count()
223    self.state.radius = self.shrinking_ball_radius();
224    Some(self.get_state())
225  }
226
227  fn check_sensors(&mut self) {
228    let added = self
229      .state
230      .obs_space
231      .check_sensors(&self.state.pose, self.state.robot_specs.sensor_radius);
232
233    if !added.is_empty() {
234      // Copy out the added obstacles into a temporary obstacle space
235      let obs = self
236        .state
237        .obs_space
238        .get_obstacles(&added[..])
239        .into_iter()
240        .cloned()
241        .collect();
242      let added_obs_space = OS::new(obs);
243
244      // Add to environment possibly creating orphans
245      self.add_obstacle_to_environment(added_obs_space);
246
247      // Cleanup
248      // if the current target has been orphaned, remove it
249      if let Some((_, _, move_goal_idx)) = self.state.current_path {
250        if self.state.tree.is_orphan(move_goal_idx) {
251          self.state.current_path = None;
252        }
253      }
254
255      // // TODO: BUG:
256      // // removing from tree without removing from kdtree will cause problems
257      // self.state.tree.clear_orphans();
258    }
259  }
260
261  fn get_obs_space(&self) -> &OS {
262    &self.state.obs_space
263  }
264
265  fn get_obs_space_mut(&mut self) -> &mut OS {
266    &mut self.state.obs_space
267  }
268
269  fn get_cspace(&self) -> &CS {
270    &self.cspace
271  }
272
273  fn get_cspace_mut(&mut self) -> &mut CS {
274    &mut self.cspace
275  }
276
277  fn check_nodes(&mut self, use_obs_space: bool, use_cspace: bool) {
278    if !(use_obs_space || use_cspace) {
279      // Nothing to do
280      return;
281    }
282
283    let all_nodes = self.state.tree.all_nodes().collect::<Vec<_>>();
284    let tree = &self.state.tree;
285    let cspace = &self.cspace;
286    let obs_space = &self.state.obs_space;
287
288    let iter = all_nodes.into_par_iter().filter_map(|u_idx| {
289      let u = tree.get_node(u_idx).state();
290
291      // Check cspace and/or obs_space if required
292      if (use_cspace && !cspace.is_free(u))
293        || (use_obs_space && !obs_space.is_free(u))
294      {
295        Some(u_idx)
296      } else {
297        None
298      }
299    });
300    let vec = iter.collect::<Vec<_>>();
301
302    for u_idx in vec {
303      self.state.tree.add_orphan(u_idx);
304    }
305    // // TODO: BUG:
306    // // removing from tree without removing from kdtree will cause problems
307    // self.state.tree.clear_orphans();
308  }
309
310  fn update_pose(
311    &mut self,
312    pose: SVector<X, N>,
313    nearest: bool,
314  ) -> Option<MoveGoal<X, N>> {
315    self.state.pose = pose;
316    log::info!("Updating pose to {:?}", <[X; N]>::from(pose));
317
318    // Check sensors from this new pose
319    self.check_sensors();
320
321    if !nearest {
322      // Check that the next move goal is still valid for this new pose,
323      // if so, return it
324      // otherwise, determine a new move goal
325      if let Some((start_pose, _, move_goal_idx)) = self.state.current_path {
326        let move_goal = self.state.tree.get_node(move_goal_idx).state();
327        let pose_ref = pose.index((.., 0));
328        let mg_ref = move_goal.index((.., 0));
329
330        if let Some(new_trajectory) = self.cspace.trajectory(pose_ref, mg_ref) {
331          if self.trajectory_free(&new_trajectory) {
332            // Trajectory is valid
333            let init_dist_err = self.cspace.cost(&start_pose, move_goal);
334            let rel_dist_err = self.cspace.cost(&pose, move_goal);
335
336            if init_dist_err > rel_dist_err {
337              // We are closer to the move goal than initially
338
339              if init_dist_err - rel_dist_err
340                > init_dist_err * self.state.params.portion
341                || rel_dist_err < self.state.params.min_cost
342              {
343                // We have reached the goal we were aiming for
344
345                // Check if we have reach the global goal node
346                if self.state.tree.get_goal_idx() == move_goal_idx {
347                  log::info!("Reached the finish!");
348                  return Some(MoveGoal::Finished);
349                }
350
351                // Find the first viable parent in the optimal path that is more
352                // than min_cost away
353                log::info!("Reached move goal, looking for next along path");
354                let res = self.find_move_goal_along_path(&pose, move_goal_idx);
355
356                // Update if found
357                if let Some((new_trajectory, new_move_goal_idx)) = res {
358                  self.state.current_path =
359                    Some((pose, new_trajectory, new_move_goal_idx));
360                  log::info!("New move goal found");
361                  return Some(MoveGoal::New(*self.get_current_path()?.end()));
362                } else {
363                  log::info!("No valid move goal along path");
364                }
365              } else {
366                // Keep the same move goal
367                log::info!("Keeping same move goal");
368                return Some(MoveGoal::Old(*self.get_current_path()?.end()));
369              }
370            } else {
371              // We are farther from the move goal than initial
372
373              if rel_dist_err - init_dist_err
374                > init_dist_err * self.state.params.portion
375              {
376                // We are out of range of the goal we were aiming for
377                // Falling through to look for a new path
378                log::info!("Out of range of move goal");
379              } else {
380                // Keep the same move goal
381                log::info!("Keeping same move goal");
382                return Some(MoveGoal::Old(*self.get_current_path()?.end()));
383              }
384            }
385          } else {
386            // Trajectory is blocked by an obstacle
387            log::info!("Current move goal blocked by obstacle");
388          }
389        } else {
390          // The trajectory is invalid
391          log::info!("Trajectory to current move goal infesible");
392        }
393      }
394    }
395
396    // The current move goal is invalid, find a new one
397    log::info!("Move goal invalid, looking for a new one");
398    self.state.current_path = self.find_new_path(pose);
399    Some(MoveGoal::New(*self.get_current_path()?.end()))
400  }
401
402  fn get_tree(&self) -> Vec<FullTrajRefOwned<X, CS::Traj, N>> {
403    unimplemented!()
404  }
405
406  fn get_current_path(&self) -> Option<FullTrajOwned<X, CS::Traj, N>> {
407    let path = self.state.current_path.as_ref()?.clone();
408    let start = path.0;
409    let end = self.state.tree.get_node(path.2).state().clone();
410    let traj = path.1;
411
412    Some(FullTrajOwned::new(start, end, traj))
413  }
414
415  fn get_path_to_goal(&self) -> Option<Vec<SVector<X, N>>> {
416    Some(
417      self
418        .state
419        .tree
420        .get_optimal_path(self.state.current_path.as_ref()?.2)?
421        .map(|node_idx| self.state.tree.get_node(node_idx).state().clone())
422        .collect(),
423    )
424  }
425
426  fn get_last_pose(&self) -> &SVector<X, N> {
427    &self.state.pose
428  }
429
430  fn get_state(&self) -> &Self::State {
431    &self.state
432  }
433
434  fn get_goal(&self) -> &SVector<X, N> {
435    self.state.tree.get_goal().state()
436  }
437
438  fn count(&self) -> usize {
439    assert_eq!(self.kdtree.size(), self.state.tree.node_count());
440    self.state.tree.node_count() + 1
441  }
442}
443
444impl<X, CS, OS, const N: usize> RrtStar<X, CS, OS, N>
445where
446  X: Scalar,
447  CS: CSpace<X, N> + Send + Sync,
448  CS::Traj: Send + Sync,
449  OS: ObstacleSpace<X, CS, N> + Send + Sync,
450  OS::Obs: Send + Sync,
451{
452  /// Try to place a new node in the tree, returns None when unsuccessful
453  fn try_create_node(&mut self) -> Option<()> {
454    let mut v = self.cspace.sample();
455    let (cost, v_nearest) = self.nearest(&v);
456
457    if cost > self.state.params.delta {
458      self
459        .cspace
460        .saturate(&mut v, v_nearest, self.state.params.delta);
461    }
462
463    match self.is_free(&v) {
464      true => {
465        let (v, v_near) = self.extend(v)?;
466        self.rewire_neighbors(v, v_near);
467        Some(())
468      }
469      false => None,
470    }
471  }
472
473  /// Returns the updated shrinking ball radius
474  fn shrinking_ball_radius(&self) -> X {
475    let dims = X::from(N).unwrap();
476    let num_vertices = X::from(self.count()).unwrap();
477
478    let temp = <X as Float>::ln(num_vertices) / num_vertices;
479    let temp = <X as Float>::powf(temp, <X as Float>::recip(dims));
480
481    <X as Float>::min(self.state.params.gamma * temp, self.state.params.delta)
482  }
483
484  /// Warn if gamma is too low for a connected graph
485  fn check_gamma(&self) {
486    let d = X::from(N).unwrap();
487    let one = X::one();
488    let two = one + one;
489    let one_over_d = <X as Float>::recip(d);
490    let volume = self.cspace.volume();
491
492    let temp1 = <X as Float>::powf(two * (one + one_over_d), one_over_d);
493    let temp2 = <X as Float>::powf(volume / unit_d_ball_vol(N), one_over_d);
494
495    let min_gamma = temp1 * temp2;
496
497    log::info!(
498      "Gamma: {:?}, Minimum Gamma: {:?}, volume: {:?}",
499      self.state.params.gamma,
500      min_gamma,
501      volume
502    );
503
504    // Assert
505    if !(self.state.params.gamma > min_gamma) {
506      log::warn!("Gamma is too small to gaurantee a conected graph");
507    }
508  }
509
510  /// Find the nearest node to v and the cost to get to it
511  fn nearest(&self, v: &SVector<X, N>) -> (X, &SVector<X, N>) {
512    let vec = self
513      .kdtree
514      .nearest(v.into(), 1, &|a, b| {
515        let a = VectorSlice::<X, Const<N>>::from_slice(a);
516        let b = VectorSlice::<X, Const<N>>::from_slice(b);
517        self.cspace.cost(&a, &b)
518      })
519      .unwrap();
520    let (cost, &v_nearest_idx) = vec.first().unwrap();
521    let v_nearest = self.state.tree.get_node(v_nearest_idx).state();
522    (*cost, v_nearest)
523  }
524
525  /// Try to extend the tree to include the given node
526  fn extend(
527    &mut self,
528    v: SVector<X, N>,
529  ) -> Option<(NodeIndex, Vec<NodeIndex>)> {
530    let v_near = self.near(&v);
531
532    let mut v = Node::new(v);
533    let (trajectory, parent_idx) = self.find_parent(&mut v, &v_near)?;
534
535    let (v_idx, _) = self.state.tree.add_node(v, parent_idx, trajectory);
536    self
537      .kdtree
538      .add(
539        self.state.tree.get_node(v_idx).state().clone().into(),
540        v_idx,
541      )
542      .expect("kdtree error");
543
544    Some((v_idx, v_near))
545  }
546
547  /// Return vector of nodes that are within self.state.radius
548  fn near(&self, v: &SVector<X, N>) -> Vec<NodeIndex> {
549    let result = self.kdtree.within(v.into(), self.state.radius, &|a, b| {
550      let a = VectorSlice::<X, Const<N>>::from_slice(a);
551      let b = VectorSlice::<X, Const<N>>::from_slice(b);
552      self.cspace.cost(&a, &b)
553    });
554
555    match result {
556      Ok(vec) => vec.iter().map(|&(_, &id)| id).collect(),
557      Err(kdtree::ErrorKind::ZeroCapacity) => vec![],
558      _ => panic!("kdtree error"),
559    }
560  }
561
562  /// Searchs u_near for the best selection of a parent for v that minimzes the look-ahead cost estimate
563  /// Returns Some(trajectory_to_parent, parent_idx) if a fesiable parent was found
564  fn find_parent(
565    &self,
566    v: &mut Node<X, N>,
567    u_near: &Vec<NodeIndex>,
568  ) -> Option<(CS::Traj, NodeIndex)> {
569    let mut parent = None;
570
571    for &u_idx in u_near {
572      // Check each node for a valid trajectory, searching keeping track of minimum viable path
573      let u = self.state.tree.get_node(u_idx);
574      let v_ref = v.state().index((.., 0));
575      let u_ref = u.state().index((.., 0));
576
577      // Check System dynamics
578      if let Some(trajectory) = self.cspace.trajectory(v_ref, u_ref) {
579        // Check cost actually makes the minimum cost go down
580        let cost = trajectory.cost();
581        if v.cost > cost + u.cost {
582          // Check trajectory for intersections with obstacles
583          if self.trajectory_free(&trajectory) {
584            parent = Some((trajectory.to_trajectory(), u_idx));
585            v.cost = cost + u.cost;
586          }
587        }
588      }
589    }
590    parent
591  }
592
593  /// Rewires incoming neighbors to v if doing so lowers the cost of u
594  fn rewire_neighbors(&mut self, v_idx: NodeIndex, v_near: Vec<NodeIndex>) {
595    for u_idx in v_near {
596      if self.state.tree.is_parent(v_idx, u_idx) {
597        continue;
598      }
599
600      // Gather data
601      let u = self.state.tree.get_node(u_idx);
602      let v = self.state.tree.get_node(v_idx);
603      let u_ref = u.state().index((.., 0));
604      let v_ref = v.state().index((.., 0));
605
606      // Check trajectory u -> v
607      if let Some(trajectory) = self.cspace.trajectory(u_ref, v_ref) {
608        let v_cost = v.cost;
609        let trajectory_cost = trajectory.cost();
610
611        // Check if cost is lower through v
612        if u.cost > trajectory_cost + v_cost {
613          // Check trajectory for intersections with obstacles
614          if self.trajectory_free(&trajectory) {
615            let trajectory = trajectory.to_trajectory();
616            let u = self.state.tree.get_node_mut(u_idx);
617            u.cost = trajectory_cost + v_cost;
618            self.state.tree.update_edge(u_idx, v_idx, trajectory);
619          }
620        }
621      }
622    }
623  }
624
625  /// Updates the tree nodes and edges that become blocked by this obstacle
626  fn add_obstacle_to_environment<O>(&mut self, obstacle: O)
627  where
628    O: Obstacle<X, CS, N> + Send + Sync,
629  {
630    // Find all the edges that intersect with the obstacle
631    let tree_ref = &self.state.tree;
632    let iter = tree_ref.all_edges().collect::<Vec<_>>();
633    let iter = iter.into_par_iter().filter_map(|edge_idx| {
634      let trajectory = self.state.tree.get_trajectory(edge_idx);
635      match obstacle.trajectory_free(&trajectory) {
636        true => None,
637        false => {
638          let (v_idx, _u_idx) = self.state.tree.get_endpoints(edge_idx);
639          Some(v_idx)
640        }
641      }
642    });
643
644    // Compute this iterator
645    let vec: Vec<_> = iter.collect();
646
647    for v_idx in vec {
648      self.state.tree.add_orphan(v_idx);
649    }
650  }
651
652  /// Find the first viable parent in the optimal path that is more than min_cost away
653  ///
654  /// panics if move_goal_idx is an orphan
655  fn find_move_goal_along_path(
656    &self,
657    pose: &SVector<X, N>,
658    move_goal_idx: NodeIndex,
659  ) -> Option<(CS::Traj, NodeIndex)> {
660    // This is an invariant, if the move_goal exists then the optimal path exists
661    let mut optimal_path_iter =
662      self.state.tree.get_optimal_path(move_goal_idx).unwrap();
663
664    optimal_path_iter.next(); // Pop off the current goal (move_goal_idx)
665
666    // Seach the path for the first viable node that is more than min_cost away
667    for node_idx in optimal_path_iter {
668      let node = self.state.tree.get_node(node_idx).state();
669
670      if let Some(trajectory) =
671        self.cspace.trajectory(pose.clone(), node.clone())
672      {
673        if self.trajectory_free(&trajectory) {
674          // Valid trajectory, see if it is longer than min_cost
675          let cost = trajectory.cost();
676          if self.state.params.min_cost < cost {
677            return Some((trajectory.to_trajectory(), node_idx));
678          }
679          continue;
680        }
681      }
682      // Invalid trajectory, cut off search if farther than delta
683      let cost = self.cspace.cost(pose, node);
684      if self.state.params.delta < cost {
685        log::info!("Cutting search along path short");
686        return None;
687      }
688    }
689    None
690  }
691
692  /// Check that the given coordinate does not intersect with any obstacles
693  fn is_free(&self, v: &SVector<X, N>) -> bool {
694    self.cspace.is_free(v) && self.state.obs_space.is_free(v)
695  }
696
697  /// Check that the given trajectory does not intersect with any obstacles
698  fn trajectory_free<TF, S1, S2>(&self, t: &TF) -> bool
699  where
700    TF: FullTrajectory<X, CS::Traj, S1, S2, N>,
701    S1: Storage<X, Const<N>>,
702    S2: Storage<X, Const<N>>,
703  {
704    self.state.obs_space.trajectory_free(t)
705  }
706
707  /// The current move goal is unreachable, this looks for a new one
708  /// Returns Some new move goal if one is viable
709  fn find_new_path(
710    &self,
711    pose: SVector<X, N>,
712  ) -> Option<(SVector<X, N>, CS::Traj, NodeIndex)> {
713    // Create temporary Node as the given pose
714    let mut pose_node = Node::new(pose);
715
716    // Create Iterator over all points in cost order
717    let cost_func = |a: &[X], b: &[X]| {
718      let a = VectorSlice::<X, Const<N>>::from_slice(a);
719      let b = VectorSlice::<X, Const<N>>::from_slice(b);
720      self.cspace.cost(&a, &b)
721    };
722    let mut iter = self
723      .kdtree
724      .iter_nearest(pose.as_slice(), &cost_func)
725      .unwrap();
726
727    // Create first batch to determine the initial batch size
728    let mut batch = Vec::new();
729    loop {
730      match iter.next() {
731        Some((cost, &idx)) => {
732          batch.push(idx);
733          if cost >= self.state.radius {
734            break;
735          }
736        }
737        None => break,
738      }
739    }
740
741    // Search the first batch
742    log::info!("Searching {:?} nearest nodes", batch.len());
743    if let Some((traj, idx)) = self.find_parent(&mut pose_node, &batch) {
744      log::info!("Found new move goal");
745      return Some((pose, traj, idx));
746    }
747
748    // Search for a viable target in batches that double in size each loop
749    // up until the cost is greater than delta
750    loop {
751      // Reset and create new batch of double size
752      let batch_size = 2 * batch.len();
753      batch.clear();
754      while let Some((cost, &idx)) = iter.next() {
755        if self.state.params.delta < cost {
756          log::info!("Cutting search short");
757          break;
758        }
759
760        batch.push(idx);
761        if batch.len() >= batch_size {
762          break;
763        }
764      }
765
766      // Iterator stopped giving elements, we have searched every node
767      if batch.is_empty() {
768        log::info!("End of search, no new move goal found");
769        return None;
770      }
771
772      // Search the batch
773      log::info!("Searching next {:?} nearest nodes", batch.len());
774      if let Some((traj, idx)) = self.find_parent(&mut pose_node, &batch) {
775        log::info!("Found new move goal");
776        return Some((pose, traj, idx));
777      }
778    }
779  }
780}
781
782#[cfg(test)]
783mod tests {
784
785  use parry3d::math::Isometry;
786  use parry3d::shape::{Ball, Cuboid, SharedShape};
787  use rand::SeedableRng;
788
789  use crate::cspace::EuclideanSpace;
790  use crate::obstacles::obstacles_3d_f32::{Obstacle3df32, ObstacleSpace3df32};
791  use crate::rng::RNG;
792  use crate::util::bounds::Bounds;
793
794  use super::*;
795
796  const SEED: u64 = 0xe580e2e93fd6b040;
797
798  #[test]
799  fn test_rrt_star() {
800    let init = [5.0, 0.5, 5.0].into();
801    let goal = [-5.0, 0.5, -5.0].into();
802
803    let robot_specs = RobotSpecs {
804      robot_radius: 0.1,
805      sensor_radius: 2.0,
806    };
807
808    let bounds = Bounds::new([-5.0, 0.0, -5.0].into(), [5.0, 1.0, 5.0].into());
809    let cspace = EuclideanSpace::new(bounds, RNG::seed_from_u64(SEED)).unwrap();
810
811    let ball = Obstacle3df32::with_offset(
812      SharedShape::new(Ball::new(0.5)),
813      Isometry::translation(0.0, 0.5, 0.0),
814    );
815
816    let cube = Obstacle3df32::with_offset(
817      SharedShape::new(Cuboid::new([0.5, 0.5, 0.5].into())),
818      Isometry::translation(2.5, 0.5, 2.5),
819    );
820
821    let obs_space = ObstacleSpace3df32::from(vec![ball, cube]);
822
823    let params = RrtStarParams {
824      min_cost: 0.0,
825      portion: 0.1,
826      delta: 1.0,
827      gamma: 1067.0,
828    };
829
830    let mut rrt_star =
831      RrtStar::new(init, goal, robot_specs, cspace, obs_space, params).unwrap();
832
833    let path = loop {
834      rrt_star.create_node();
835      rrt_star.update_pose(init, false);
836      if let Some(path) = rrt_star.get_path_to_goal() {
837        break path;
838      }
839    };
840
841    let mut cost = 0.0;
842    for i in 0..path.len() - 1 {
843      cost += path[i].metric_distance(&path[i + 1]);
844    }
845    println!("{:?}", rrt_star.count());
846    println!("{:?}", rrt_star.state.radius);
847    println!("{:?}", path);
848    println!("{:?}", cost);
849  }
850
851  #[test]
852  fn test_serialize_rrt_star_state() {
853    let init = [5.0, 0.5, 5.0].into();
854    let goal = [-5.0, 0.5, -5.0].into();
855
856    let robot_specs = RobotSpecs {
857      robot_radius: 0.1,
858      sensor_radius: 2.0,
859    };
860
861    let bounds = Bounds::new([-5.0, 0.0, -5.0].into(), [5.0, 1.0, 5.0].into());
862    let cspace = EuclideanSpace::new(bounds, RNG::seed_from_u64(SEED)).unwrap();
863
864    let ball = Obstacle3df32::with_offset(
865      SharedShape::new(Ball::new(0.5)),
866      Isometry::translation(0.0, 0.5, 0.0),
867    );
868
869    let cube = Obstacle3df32::with_offset(
870      SharedShape::new(Cuboid::new([0.5, 0.5, 0.5].into())),
871      Isometry::translation(2.5, 0.5, 2.5),
872    );
873
874    let obs_space = ObstacleSpace3df32::from(vec![ball, cube]);
875
876    let params = RrtStarParams {
877      min_cost: 0.0,
878      portion: 0.1,
879      delta: 1.0,
880      gamma: 1067.0,
881    };
882
883    let mut rrt_star =
884      RrtStar::new(init, goal, robot_specs, cspace, obs_space, params).unwrap();
885
886    loop {
887      rrt_star.create_node();
888      rrt_star.update_pose(init, false);
889      if let Some(_) = rrt_star.get_path_to_goal() {
890        break;
891      }
892    }
893
894    let state = rrt_star.get_state();
895    let v = bincode::serialize(&state).unwrap();
896    let _: RrtStarState<f32, EuclideanSpace<f32, 3>, ObstacleSpace3df32, 3> =
897      bincode::deserialize(&v).unwrap();
898  }
899}