path_planning/rrtx/
rrtx.rs

1/* Copyright (C) 2020 Dylan Staatz - All Rights Reserved. */
2
3use std::collections::HashSet;
4
5use kdtree::KdTree;
6use nalgebra::storage::Storage;
7use nalgebra::{Const, SVector, VectorSlice};
8use num_traits::Float;
9use petgraph::stable_graph::NodeIndex;
10use priority_queue::PriorityQueue;
11use rayon::iter::{IntoParallelIterator, ParallelExtend, ParallelIterator};
12use serde::{de::DeserializeOwned, Deserialize, Serialize};
13
14use crate::cspace::CSpace;
15use crate::error::{InvalidParamError, Result};
16use crate::obstacles::{Obstacle, ObstacleSpace};
17use crate::path_planner::{MoveGoal, PathPlanner, RobotSpecs};
18use crate::scalar::Scalar;
19use crate::trajectories::{FullTrajOwned, FullTrajRefOwned, FullTrajectory};
20use crate::util::math::unit_d_ball_vol;
21
22use super::{Cost, NeighborSet, NeighborType, Node, Priority, RrtxGraph};
23
24/// Rrtx generic parameters
25#[derive(Debug, Clone, PartialEq, Serialize, Deserialize)]
26#[serde(bound(
27  serialize = "X: Serialize",
28  deserialize = "X: DeserializeOwned"
29))]
30pub struct RrtxParams<X> {
31  pub min_cost: X,
32  pub portion: X,
33  pub delta: X,
34  pub gamma: X,
35  pub eps: X,
36}
37
38/// Rrtx Serializable State information
39#[derive(Debug, Serialize, Deserialize)]
40#[serde(bound(
41  serialize = "X: Serialize, CS::Traj: Serialize, OS: Serialize",
42  deserialize = "X: DeserializeOwned, CS::Traj: DeserializeOwned, OS: DeserializeOwned",
43))]
44pub struct RrtxState<X, CS, OS, const N: usize>
45where
46  X: Scalar,
47  CS: CSpace<X, N>,
48  OS: ObstacleSpace<X, CS, N>,
49{
50  /// All the nodes with their associated costs and edges that connect them
51  pub graph: RrtxGraph<X, CS::Traj, N>,
52
53  /// The current path being travelled from some point to a node in the graph
54  /// and the trajectory of how to get there
55  pub current_path: Option<(SVector<X, N>, CS::Traj, NodeIndex)>,
56
57  /// The last know current pose of the system
58  pub pose: SVector<X, N>,
59
60  /// Tracks the obstacles in the space
61  pub obs_space: OS,
62
63  /// Shrinking ball radius
64  pub radius: X,
65
66  /// Robot specifications
67  pub robot_specs: RobotSpecs<X>,
68
69  // Algorithm Parameters
70  pub params: RrtxParams<X>,
71}
72
73impl<X, CS, OS, const N: usize> Clone for RrtxState<X, CS, OS, N>
74where
75  X: Scalar,
76  CS: CSpace<X, N>,
77  OS: ObstacleSpace<X, CS, N>,
78{
79  fn clone(&self) -> Self {
80    Self {
81      graph: self.graph.clone(),
82      current_path: self.current_path.clone(),
83      pose: self.pose.clone(),
84      obs_space: self.obs_space.clone(),
85      radius: self.radius.clone(),
86      robot_specs: self.robot_specs.clone(),
87      params: self.params.clone(),
88    }
89  }
90}
91
92/// Rrtx implementation
93pub struct Rrtx<X, CS, OS, const N: usize>
94where
95  X: Scalar,
96  CS: CSpace<X, N>,
97  OS: ObstacleSpace<X, CS, N>,
98{
99  /// All the serializable state information.
100  state: RrtxState<X, CS, OS, N>,
101
102  /// Priority queue
103  queue: PriorityQueue<NodeIndex, Priority<X>>,
104
105  /// For fast nearest neighbor searching
106  kdtree: KdTree<X, NodeIndex, [X; N]>,
107
108  /// Describes the configuration space
109  cspace: CS,
110
111  /// The number of sampled points
112  sampled: usize,
113}
114
115impl<X, CS, OS, const N: usize> PathPlanner<X, CS, OS, N> for Rrtx<X, CS, OS, N>
116where
117  X: Scalar,
118  CS: CSpace<X, N> + Send + Sync,
119  CS::Traj: Send + Sync,
120  OS: ObstacleSpace<X, CS, N> + Send + Sync,
121  OS::Obs: Send + Sync,
122{
123  type Params = RrtxParams<X>;
124  type State = RrtxState<X, CS, OS, N>;
125
126  fn new(
127    init: SVector<X, N>,
128    goal: SVector<X, N>,
129    robot_specs: RobotSpecs<X>,
130    cspace: CS,
131    obs_space: OS,
132    params: Self::Params,
133  ) -> Result<Self> {
134    let graph = RrtxGraph::new(goal.clone());
135    let current_path = None;
136    let pose = init.clone();
137
138    let queue = PriorityQueue::new();
139
140    let mut kdtree: KdTree<X, NodeIndex, [X; N]> = KdTree::new(N.into());
141    kdtree.add(goal.into(), graph.get_goal_idx())?;
142
143    let radius = params.delta;
144
145    // Validate robot_radius are greater than 0
146    if !(X::zero() < robot_specs.robot_radius) {
147      Err(InvalidParamError {
148        parameter_name: "robot_specs.robot_radius",
149        parameter_value: format!("{:?}", robot_specs.robot_radius),
150      })?;
151    }
152
153    // Validate sensor_radius are greater than 0
154    if !(X::zero() < robot_specs.sensor_radius) {
155      Err(InvalidParamError {
156        parameter_name: "robot_specs.sensor_radius",
157        parameter_value: format!("{:?}", robot_specs.sensor_radius),
158      })?;
159    }
160
161    // Validate min_cost is in [0, delta)
162    if !(X::zero() <= params.min_cost && params.min_cost < params.delta) {
163      Err(InvalidParamError {
164        parameter_name: "params.min_cost",
165        parameter_value: format!("{:?}", params.min_cost),
166      })?;
167    }
168
169    // Validate portion is in (0, 1)
170    if !(X::zero() < params.portion && params.portion < X::one()) {
171      Err(InvalidParamError {
172        parameter_name: "params.portion",
173        parameter_value: format!("{:?}", params.portion),
174      })?;
175    }
176
177    let state = RrtxState {
178      graph,
179      current_path,
180      pose,
181      obs_space,
182      radius,
183      robot_specs,
184      params,
185    };
186
187    let mut new = Self {
188      state,
189      queue,
190      kdtree,
191      cspace,
192      sampled: 0,
193    };
194
195    new.state.radius = new.shrinking_ball_radius();
196    new.check_gamma();
197
198    // Check that the init and goal locations are in free space
199    if !new.is_free(&init) {
200      Err(InvalidParamError {
201        parameter_name: "init",
202        parameter_value: format!("{:?}", init),
203      })?;
204    }
205    if !new.is_free(&goal) {
206      Err(InvalidParamError {
207        parameter_name: "goal",
208        parameter_value: format!("{:?}", goal),
209      })?;
210    }
211
212    Ok(new)
213  }
214
215  fn create_node(&mut self) -> &Self::State {
216    // Continue to sample points until one is found
217    loop {
218      if let Some(()) = self.try_create_node() {
219        break;
220      }
221      self.log_sampling_ratio();
222    }
223
224    // Update the new radius now that we changed self.count()
225    self.state.radius = self.shrinking_ball_radius();
226    log::debug!("Shrinking ball radius: {:?}", self.state.radius);
227    self.get_state()
228  }
229
230  fn sample_node(&mut self) -> Option<&Self::State> {
231    self.try_create_node()?;
232
233    // Update the new radius now that we changed self.count()
234    self.state.radius = self.shrinking_ball_radius();
235    log::debug!("Shrinking ball radius: {:?}", self.state.radius);
236    Some(self.get_state())
237  }
238
239  fn check_sensors(&mut self) {
240    let added = self
241      .state
242      .obs_space
243      .check_sensors(&self.state.pose, self.state.robot_specs.sensor_radius);
244
245    if !added.is_empty() {
246      log::info!("Found {:?} obstacles", added.len());
247
248      // Add newly added obstacles to the environment possibly creating orphans
249      let added = self.state.obs_space.get_obstacles_as_obstacle_space(&added);
250
251      // Add to environment possibly creating orphans
252      self.add_obstacle_to_environment(&added);
253
254      log::info!("Added {:?} obstacles to the environment", added.count());
255
256      // Cleanup
257      self.propagate_descendants();
258      if let Some((_, _, idx)) = self.state.current_path {
259        self.verrify_queue(idx);
260      }
261      log::info!("Reducing inconsistency");
262      self.reduce_inconsistency();
263
264      // TODO: validate path is still viable
265    }
266
267    // if let Some(current_path) = self.state.current_path.as_ref() {
268    //   let path_to_goal = self
269    //     .state
270    //     .graph
271    //     .get_optimal_path(current_path.2)
272    //     .unwrap()
273    //     .collect::<Vec<_>>();
274
275    //   let last_idx = path_to_goal.last().unwrap().clone();
276
277    //   if last_idx != self.state.graph.get_goal_idx() {
278    //     self.state.current_path = None;
279    //   }
280    // }
281  }
282
283  fn get_obs_space(&self) -> &OS {
284    &self.state.obs_space
285  }
286
287  fn get_obs_space_mut(&mut self) -> &mut OS {
288    &mut self.state.obs_space
289  }
290
291  fn get_cspace(&self) -> &CS {
292    &self.cspace
293  }
294
295  fn get_cspace_mut(&mut self) -> &mut CS {
296    &mut self.cspace
297  }
298
299  fn check_nodes(&mut self, check_obs_space: bool, check_cspace: bool) {
300    if !(check_obs_space || check_cspace) {
301      // Nothing to do
302      return;
303    }
304
305    // Set of edges that have been invalidated by either the cspace or obs_space
306    let mut orphaned = false;
307
308    if check_cspace {
309      let mut invalidated_edges = Vec::new();
310
311      // Check that all nodes are valid in the cspace
312      let all_nodes = self.state.graph.all_nodes().collect::<Vec<_>>();
313      let graph_ref = &self.state.graph;
314      let cspace_ref = &self.cspace;
315
316      let iter = all_nodes.into_par_iter().filter_map(|u_idx| {
317        let u = graph_ref.get_node(u_idx).state();
318
319        // Check cspace
320        if !cspace_ref.is_free(u) {
321          // Return list ouer all edges with u
322          let edges = graph_ref
323            .neighbor_set(u_idx, NeighborSet::Incoming)
324            // .chain(graph_ref.neighbor_set(u_idx, NeighborSet::Outgoing))
325            .map(|(edge_idx, _)| {
326              let (v_idx, u_idx) = self.state.graph.get_endpoints(edge_idx);
327              (v_idx, edge_idx, u_idx)
328            });
329
330          Some(edges)
331        } else {
332          None
333        }
334      });
335      invalidated_edges.par_extend(iter.flatten_iter());
336
337      // Proccess invalidated edges
338      for &(v_idx, edge_idx, u_idx) in &invalidated_edges {
339        self.state.graph.set_infinite_edge_cost(edge_idx);
340
341        // if the parent of v is u, make v an orphan
342        if self.state.graph.is_parent(v_idx, u_idx) {
343          self.verrify_orphan(v_idx);
344          orphaned = true;
345        }
346
347        // if u is the current target, remove it
348        if let Some((_, _, move_goal_idx)) = self.state.current_path {
349          if move_goal_idx == u_idx {
350            self.state.current_path = None;
351          }
352        }
353      }
354
355      // Permanetly delete non-free nodes from the graph
356      for &(_v_idx, _edge_idx, u_idx) in &invalidated_edges {
357        if self.state.graph.check_node(u_idx) {
358          self.delete_node(u_idx);
359        }
360      }
361    }
362
363    if check_obs_space {
364      let mut invalidated_edges = HashSet::new();
365
366      // Check that all edges are valid in the obs_space
367      let all_edges = self.state.graph.all_edges().collect::<Vec<_>>();
368      let graph_ref = &self.state.graph;
369      let obs_space_ref = &self.state.obs_space;
370
371      let iter = all_edges
372        .into_par_iter()
373        .filter_map(|edge_idx| {
374          let trajectory = graph_ref.get_trajectory(edge_idx)?;
375          match obs_space_ref.trajectory_free(&trajectory) {
376            true => None,
377            false => Some(edge_idx),
378          }
379        })
380        .map(|edge_idx| {
381          let (v_idx, u_idx) = self.state.graph.get_endpoints(edge_idx);
382          (v_idx, edge_idx, u_idx)
383        });
384      invalidated_edges.par_extend(iter);
385
386      // Proccess invalidated edges
387      for &(v_idx, edge_idx, u_idx) in &invalidated_edges {
388        self.state.graph.set_infinite_edge_cost(edge_idx);
389
390        // if the parent of v is u, make v an orphan
391        if self.state.graph.is_parent(v_idx, u_idx) {
392          self.verrify_orphan(v_idx);
393          orphaned = true;
394        }
395
396        // if u is the current target, remove it
397        if let Some((_, _, move_goal_idx)) = self.state.current_path {
398          if move_goal_idx == u_idx {
399            self.state.current_path = None;
400          }
401        }
402      }
403
404      // invalidated_edges.into_par_iter()
405    }
406
407    // if nodes were orphaned
408    if orphaned {
409      self.propagate_descendants();
410      if let Some((_, _, idx)) = self.state.current_path {
411        self.verrify_queue(idx);
412      }
413      log::info!("Reducing inconsistency");
414      self.reduce_inconsistency();
415    }
416  }
417
418  fn update_pose(
419    &mut self,
420    pose: SVector<X, N>,
421    nearest: bool,
422  ) -> Option<MoveGoal<X, N>> {
423    self.state.pose = pose;
424    log::info!(
425      "Updating pose to {:?}, cost to local goal: {:?}",
426      <[X; N]>::from(pose),
427      self.get_cost_to_move_goal()
428    );
429
430    // Check sensors from this new pose
431    self.check_sensors();
432
433    if !nearest {
434      // Check that the next move goal is still valid for this new pose,
435      // if so, return it
436      // otherwise, determine a new move goal
437      if let Some((start_pose, _, move_goal_idx)) = self.state.current_path {
438        let move_goal = self.state.graph.get_node(move_goal_idx).state();
439        let pose_ref = pose.index((.., 0));
440        let mg_ref = move_goal.index((.., 0));
441
442        if let Some(new_trajectory) = self.cspace.trajectory(pose_ref, mg_ref) {
443          if self.trajectory_free(&new_trajectory) {
444            // Trajectory is valid
445            let init_dist_err = self.cspace.cost(&start_pose, move_goal);
446            let rel_dist_err = self.cspace.cost(&pose, move_goal);
447
448            if init_dist_err > rel_dist_err {
449              // We are closer to the move goal than initially
450
451              if init_dist_err - rel_dist_err
452                > init_dist_err * self.state.params.portion
453                || rel_dist_err < self.state.params.min_cost
454              {
455                // We have reached the goal we were aiming for
456
457                // Check if we have reach the global goal node
458                if self.state.graph.get_goal_idx() == move_goal_idx {
459                  log::info!("  - Reached the finish!");
460                  return Some(MoveGoal::Finished);
461                }
462
463                // Find the first viable parent in the optimal path that is more
464                // than min_cost away
465                log::info!(
466                  "  - Reached move goal, looking for next along path"
467                );
468                let res = self.find_move_goal_along_path(&pose, move_goal_idx);
469
470                // Update if found
471                if let Some((new_trajectory, new_move_goal_idx)) = res {
472                  self.state.current_path =
473                    Some((pose, new_trajectory, new_move_goal_idx));
474                  log::info!("  - New move goal found");
475                  return Some(MoveGoal::New(*self.get_current_path()?.end()));
476                } else {
477                  log::info!("  - No valid move goal along path");
478                }
479              } else {
480                // Keep the same move goal
481                // log::info!("  - Keeping same move goal");
482                return Some(MoveGoal::Old(*self.get_current_path()?.end()));
483              }
484            } else {
485              // We are farther from the move goal than initial
486
487              if rel_dist_err - init_dist_err
488                > init_dist_err * self.state.params.portion
489              {
490                // We are out of range of the goal we were aiming for
491                // Falling through to look for a new path
492                log::info!("  - Out of range of move goal");
493              } else {
494                // Keep the same move goal
495                log::info!("  - Keeping same move goal");
496                return Some(MoveGoal::Old(*self.get_current_path()?.end()));
497              }
498            }
499          } else {
500            // Trajectory is blocked by an obstacle
501            log::info!("  - Current move goal blocked by obstacle");
502          }
503        } else {
504          // The trajectory is invalid
505          log::info!("  - Trajectory to current move goal infesible");
506        }
507      }
508    }
509
510    // The current move goal is invalid, find a new one
511    log::info!("  - Move goal invalid, looking for a new one");
512    self.state.current_path = self.find_new_path(pose);
513    Some(MoveGoal::New(*self.get_current_path()?.end()))
514  }
515
516  fn get_tree(&self) -> Vec<FullTrajRefOwned<X, CS::Traj, N>> {
517    self
518      .state
519      .graph
520      .all_edges()
521      .filter(|&edge_idx| self.state.graph.get_edge(edge_idx).is_parent())
522      .filter_map(|edge_idx| self.state.graph.get_trajectory(edge_idx))
523      .collect()
524  }
525
526  fn get_current_path(&self) -> Option<FullTrajOwned<X, CS::Traj, N>> {
527    let path = self.state.current_path.as_ref()?.clone();
528    let start = path.0;
529    let end = self.state.graph.get_node(path.2).state().clone();
530    let traj = path.1;
531
532    Some(FullTrajOwned::new(start, end, traj))
533  }
534
535  fn get_path_to_goal(&self) -> Option<Vec<SVector<X, N>>> {
536    let path_to_goal = self
537      .state
538      .graph
539      .get_optimal_path(self.state.current_path.as_ref()?.2)?
540      .collect::<Vec<_>>();
541
542    let last_idx = path_to_goal.last().unwrap().clone();
543
544    if last_idx != self.state.graph.get_goal_idx() {
545      log::error!(
546        "Invalid node in path to goal: {} at {:?}",
547        last_idx.index(),
548        <[X; N]>::from(self.state.graph.get_node(last_idx).state().clone())
549      );
550      panic!("If path to goal is valid, it should lead to the goal");
551    }
552
553    Some(
554      path_to_goal
555        .into_iter()
556        .map(|node_idx| self.state.graph.get_node(node_idx).state().clone())
557        .collect(),
558    )
559  }
560
561  fn get_last_pose(&self) -> &SVector<X, N> {
562    &self.state.pose
563  }
564
565  fn get_state(&self) -> &Self::State {
566    &self.state
567  }
568
569  fn get_goal(&self) -> &SVector<X, N> {
570    self.state.graph.get_goal().state()
571  }
572
573  fn count(&self) -> usize {
574    // assert_eq!(self.kdtree.size(), self.state.graph.node_count());
575    self.state.graph.node_count() + 1
576  }
577}
578
579impl<X, CS, OS, const N: usize> Rrtx<X, CS, OS, N>
580where
581  X: Scalar,
582  CS: CSpace<X, N> + Send + Sync,
583  CS::Traj: Send + Sync,
584  OS: ObstacleSpace<X, CS, N> + Send + Sync,
585  OS::Obs: Send + Sync,
586{
587  /// Try to place a new node in the graph, returns None when unsuccessful
588  fn try_create_node(&mut self) -> Option<()> {
589    let mut v = self.cspace.sample();
590    self.sampled += 1;
591
592    let (cost, v_nearest) = self.nearest(&v);
593
594    if cost > self.state.params.delta {
595      self
596        .cspace
597        .saturate(&mut v, v_nearest, self.state.params.delta);
598    }
599
600    match self.is_free(&v) {
601      true => {
602        let v_idx = self.extend(v)?;
603        self.rewire_neighbors(v_idx);
604        self.reduce_inconsistency();
605        Some(())
606      }
607      false => None,
608    }
609  }
610
611  fn log_sampling_ratio(&self) {
612    log::debug!(
613      "sampled: {:?}, added: {:?}, sampling_ratio: {:?}",
614      self.sampled,
615      self.count() - 1, // Don't count goal node
616      self.sampling_ratio()
617    );
618  }
619
620  fn sampling_ratio(&self) -> f64 {
621    let sampled = self.sampled;
622    let added = self.count() - 1; // Don't count goal node
623    (sampled as f64) / (added as f64)
624  }
625
626  /// Returns the updated shrinking ball radius
627  fn shrinking_ball_radius(&self) -> X {
628    let dims = X::from(N).unwrap();
629    let num_vertices = X::from(self.count()).unwrap();
630
631    let temp = <X as Float>::ln(num_vertices) / num_vertices;
632    let temp = <X as Float>::powf(temp, <X as Float>::recip(dims));
633
634    <X as Float>::min(self.state.params.gamma * temp, self.state.params.delta)
635  }
636
637  /// Warn if gamma is too low for a connected graph
638  fn check_gamma(&self) {
639    let d = X::from(N).unwrap();
640    let one = X::one();
641    let two = one + one;
642    let one_over_d = <X as Float>::recip(d);
643    let volume = self.cspace.volume();
644
645    let temp1 = <X as Float>::powf(two * (one + one_over_d), one_over_d);
646    let temp2 = <X as Float>::powf(volume / unit_d_ball_vol(N), one_over_d);
647
648    let min_gamma = temp1 * temp2;
649
650    log::info!(
651      "Gamma: {:?}, Minimum Gamma: {:?}, volume: {:?}",
652      self.state.params.gamma,
653      min_gamma,
654      volume
655    );
656
657    // Assert
658    if !(self.state.params.gamma > min_gamma) {
659      log::warn!("Gamma is too small to gaurantee a conected graph");
660    }
661  }
662
663  /// Find the nearest node to v and the cost to get to it
664  fn nearest(&self, v: &SVector<X, N>) -> (X, &SVector<X, N>) {
665    let (cost, v_nearest_idx) = self
666      .kdtree
667      .iter_nearest(v.into(), &|a, b| {
668        let a = VectorSlice::<X, Const<N>>::from_slice(a);
669        let b = VectorSlice::<X, Const<N>>::from_slice(b);
670        self.cspace.cost(&a, &b)
671      })
672      .expect("kdtree error")
673      .filter_map(|(cost, &idx)| match self.state.graph.check_node(idx) {
674        true => Some((cost, idx)),
675        false => None,
676      })
677      .next()
678      .unwrap();
679    // let (cost, v_nearest_idx) = iter.next().unwrap();
680    let v_nearest = self.state.graph.get_node(v_nearest_idx).state();
681    (cost, v_nearest)
682  }
683
684  /// Try to extend the graph to include the given node
685  /// Setup original and running neighbors
686  fn extend(&mut self, v: SVector<X, N>) -> Option<NodeIndex> {
687    let v_near = self.near(&v);
688
689    let mut v = Node::new(v);
690    let (_, parent_idx) = self.find_parent(&mut v, &v_near)?;
691
692    let v_idx = self.state.graph.add_node(v);
693    self
694      .kdtree
695      .add(
696        self.state.graph.get_node(v_idx).state().clone().into(),
697        v_idx,
698      )
699      .expect("kdtree error");
700
701    // Add edges
702    for u_idx in v_near {
703      // v -> u
704      let v_ref = self.state.graph.get_node(v_idx).state().index((.., 0));
705      let u_ref = self.state.graph.get_node(u_idx).state().index((.., 0));
706      let t_v_u = self.cspace.trajectory(v_ref, u_ref);
707
708      if let Some(trajectory) = t_v_u {
709        if self.trajectory_free(&trajectory) {
710          let traj_data = trajectory.to_trajectory();
711          // v -> u
712          self.state.graph.add_edge(
713            v_idx,
714            u_idx,
715            NeighborType::Original,
716            NeighborType::Running,
717            u_idx == parent_idx,
718            traj_data.clone(),
719          );
720
721          // TODO: Make this optional based on a function in CSpace
722          // u -> v
723          self.state.graph.add_edge(
724            u_idx,
725            v_idx,
726            NeighborType::Running,
727            NeighborType::Original,
728            false,
729            traj_data,
730          );
731        }
732      }
733
734      // // u -> v
735      // let u = self.state.graph.get_node(u_idx);
736      // let v = self.state.graph.get_node(v_idx);
737      // let t_u_v = self.cspace.trajectory(u.state(), v.state());
738
739      // if let Some(traj_data) = t_u_v {
740      //   let trajectory = FullTrajRef::new(u.state(), v.state(), &traj_data)v_ref, u_ref, trajectory;
741      //   if self.trajectory_free(&trajectory) {
742
743      //   }
744      // }
745    }
746
747    Some(v_idx)
748  }
749
750  /// Return vector of nodes that are within self.state.radius
751  fn near(&self, v: &SVector<X, N>) -> Vec<NodeIndex> {
752    let result = self.kdtree.within(v.into(), self.state.radius, &|a, b| {
753      let a = VectorSlice::<X, Const<N>>::from_slice(a);
754      let b = VectorSlice::<X, Const<N>>::from_slice(b);
755      self.cspace.cost(&a, &b)
756    });
757
758    match result {
759      Ok(vec) => vec
760        .into_iter()
761        .filter_map(|(_, &idx)| match self.state.graph.check_node(idx) {
762          true => Some(idx),
763          false => None,
764        })
765        .collect(),
766      Err(kdtree::ErrorKind::ZeroCapacity) => vec![],
767      _ => panic!("kdtree error"),
768    }
769  }
770
771  /// Searchs u_near for the best selection of a parent for v that minimzes the look-ahead cost estimate
772  /// Returns Some(trajectory_to_parent, parent_idx) if a fesiable parent was found
773  fn find_parent(
774    &self,
775    v: &mut Node<X, N>,
776    u_near: &Vec<NodeIndex>,
777  ) -> Option<(CS::Traj, NodeIndex)> {
778    let mut parent = None;
779
780    for &u_idx in u_near {
781      // Check each node for a valid trajectory, keeping track of minimum viable path
782      let u = self.state.graph.get_node(u_idx);
783      let v_ref = v.state().index((.., 0));
784      let u_ref = u.state().index((.., 0));
785
786      // Check System dynamics
787      if let Some(trajectory) = self.cspace.trajectory(v_ref, u_ref) {
788        // Check if cost is lower through u
789        let cost = trajectory.cost();
790        if v.cost.lmc > cost + u.cost.lmc {
791          // Check trajectory for intersections with obstacles
792          if self.trajectory_free(&trajectory) {
793            parent = Some((trajectory.to_trajectory(), u_idx));
794            v.cost.lmc = cost + u.cost.lmc
795          }
796        }
797      }
798    }
799    parent
800  }
801
802  /// Remove all edges that are shorter than self.state.radius
803  /// Except original neighbors and edges part of the optimal subtree
804  fn cull_neighbors(&mut self, v_idx: NodeIndex) {
805    // Iterate over all outgoing running neighbors
806    let mut out_run = self
807      .state
808      .graph
809      .neighbor_set_walker(v_idx, NeighborSet::RunningOutgoing);
810    while let Some((edge_idx, u_idx)) = out_run.next(&self.state.graph) {
811      let neighbor_edge = self.state.graph.get_edge(edge_idx);
812      let neighbor_edge_cost = self.state.graph.get_trajectory_cost(edge_idx);
813
814      if self.state.radius < neighbor_edge_cost && !neighbor_edge.is_parent() {
815        // remove running connections
816        self.state.graph.remove_running_neighbor(v_idx, u_idx);
817      }
818    }
819  }
820
821  /// Rewires incoming neighbors to v if doing so lowers the cost of u
822  fn rewire_neighbors(&mut self, v_idx: NodeIndex) {
823    let v = self.state.graph.get_node(v_idx);
824    if v.cost.g - v.cost.lmc > self.state.params.eps {
825      // Cull neighbors of v
826      self.cull_neighbors(v_idx);
827
828      // Iterate over all incoming neighbors
829      let mut incoming = self
830        .state
831        .graph
832        .neighbor_set_walker(v_idx, NeighborSet::Incoming);
833      while let Some((edge_idx, u_idx)) = incoming.next(&self.state.graph) {
834        // Skip the parent of v
835        if self.state.graph.is_parent(v_idx, u_idx) {
836          continue;
837        }
838
839        // Gather data
840        let v_cost = self.state.graph.get_node(v_idx).cost;
841        let edge_cost = self.state.graph.get_trajectory_cost(edge_idx);
842
843        // Check if u should be rewired
844        let u = self.state.graph.get_node_mut(u_idx);
845        if u.cost.lmc > edge_cost + v_cost.lmc {
846          // Update cost and new parent of u
847          u.cost.lmc = edge_cost + v_cost.lmc;
848          self.state.graph.change_parent(u_idx, v_idx).unwrap();
849
850          // Add u to queue if eps-inconsistent
851          let u = self.state.graph.get_node(u_idx);
852          if u.cost.g - u.cost.lmc > self.state.params.eps {
853            self.verrify_queue(u_idx)
854          }
855        }
856      }
857    }
858  }
859
860  /// Iterate through the queue, reducing the inconsistency of the graph
861  fn reduce_inconsistency(&mut self) {
862    while let Some((_, &priority_peek)) = self.queue.peek() {
863      // Empty queue if no valid move exists
864      if let Some((_, _, idx)) = self.state.current_path {
865        // Check that at least one of the other conditions are met on move_goal
866        let move_goal = self.state.graph.get_node(idx);
867        if !(priority_peek > move_goal.cost.priority()
868          || move_goal.cost.lmc != move_goal.cost.g
869          || move_goal.cost.g == X::infinity()
870          || self.queue.get(&idx).is_some())
871        {
872          break;
873        }
874      }
875
876      if let Some((v_idx, _)) = self.queue.pop() {
877        let v = self.state.graph.get_node(v_idx);
878        if v.cost.g - v.cost.lmc > self.state.params.eps {
879          self.update_lmc(v_idx);
880          self.rewire_neighbors(v_idx);
881        }
882
883        let v = self.state.graph.get_node_mut(v_idx);
884        v.cost.g = v.cost.lmc;
885      }
886    }
887  }
888
889  /// Handles the set of orphans that have acumulated as obstacles have been added
890  fn propagate_descendants(&mut self) {
891    log::info!("Propagating descendants");
892    // Orphans are already marked as they were added, see RrtxGraph::add_orphan
893
894    // Add all the non-orphan outgoing neighbors of orphans to the queue
895    let orphans: Vec<_> = self.state.graph.orphans().collect();
896    for &v_idx in &orphans {
897      // Iterate over all outgoing neighbors
898      let mut outgoing = self
899        .state
900        .graph
901        .neighbor_set_walker(v_idx, NeighborSet::Outgoing);
902      while let Some(u_idx) = outgoing.next_node(&self.state.graph) {
903        if !self.state.graph.is_orphan(u_idx) {
904          let u = self.state.graph.get_node_mut(u_idx);
905          u.cost.g = X::infinity();
906          self.verrify_queue(u_idx);
907        }
908      }
909    }
910
911    // Remove all orphans, remove parent connection, set cost to infinity
912    for v_idx in orphans {
913      self.state.graph.remove_orphan(v_idx);
914      let v = self.state.graph.get_node_mut(v_idx);
915
916      v.cost = Cost::infinity();
917
918      self.state.graph.remove_parent(v_idx);
919    }
920  }
921
922  /// Updates the graph nodes and edges that become blocked by this obstacle
923  fn add_obstacle_to_environment<O>(&mut self, obstacle: &O)
924  where
925    O: Obstacle<X, CS, N> + Send + Sync,
926  {
927    // Find all the edges that intersect with the obstacle
928    let graph_ref = &self.state.graph;
929    let iter = graph_ref.all_edges().collect::<Vec<_>>();
930    let iter = iter.into_par_iter().filter_map(|edge_idx| {
931      let trajectory = graph_ref.get_trajectory(edge_idx)?;
932      match obstacle.trajectory_free(&trajectory) {
933        true => None,
934        false => {
935          let (v_idx, u_idx) = graph_ref.get_endpoints(edge_idx);
936          Some((v_idx, edge_idx, u_idx))
937        }
938      }
939    });
940
941    // Compute this iterator
942    let vec: Vec<_> = iter.collect();
943
944    for (v_idx, edge_idx, u_idx) in vec {
945      self.state.graph.set_infinite_edge_cost(edge_idx);
946
947      // if the parent of v is u, make v an orphan
948      if self.state.graph.is_parent(v_idx, u_idx) {
949        self.verrify_orphan(v_idx);
950      }
951
952      // if u is the current target, remove it
953      if let Some((_, _, move_goal_idx)) = self.state.current_path {
954        if move_goal_idx == u_idx {
955          self.state.current_path = None;
956        }
957      }
958    }
959  }
960
961  /// Updates the graph nodes and edges that were previously blocked by this obstacle
962  fn _remove_obstacle_to_environment<O>(&mut self, obstacle: &O)
963  where
964    O: Obstacle<X, CS, N> + Send + Sync,
965  {
966    // Find all the edges that intersect with the obstacle
967    let graph_ref = &self.state.graph;
968    let iter = graph_ref.all_edges().collect::<Vec<_>>();
969    let iter = iter.into_par_iter().filter(|&edge_idx| {
970      match graph_ref.get_trajectory(edge_idx) {
971        Some(trajectory) => !obstacle.trajectory_free(&trajectory),
972        None => false,
973      }
974    });
975
976    // Filter out edges that intersect with any other obstacles
977    let obs_space_ref = &self.state.obs_space;
978    let iter =
979      iter.filter(|&edge_idx| match graph_ref.get_trajectory(edge_idx) {
980        Some(trajectory) => obs_space_ref.trajectory_free(&trajectory),
981        None => false,
982      });
983
984    // Add respective node indices
985    let iter = iter.filter_map(|edge_idx| {
986      let (v_idx, u_idx) = graph_ref.get_endpoints(edge_idx);
987      Some((v_idx, edge_idx, u_idx))
988    });
989
990    // Compute this iterator
991    let vec: Vec<_> = iter.collect();
992
993    for (v_idx, _, _) in vec.iter() {
994      // Iterate through outgoing edge of v
995      let mut outgoing = self
996        .state
997        .graph
998        .neighbor_set_walker(*v_idx, NeighborSet::Outgoing);
999      while let Some(neighbor_edge) = outgoing.next_edge(&self.state.graph) {
1000        // Only check edges that are in vec
1001        let opt = vec
1002          .iter()
1003          .find(|(_, edge_idx, _)| neighbor_edge == *edge_idx);
1004
1005        if let Some(n) = opt {
1006          let n1_ref = self.state.graph.get_node(n.0).state().index((.., 0));
1007          let n2_ref = self.state.graph.get_node(n.2).state().index((.., 0));
1008          let trajectory = self.cspace.trajectory(n1_ref, n2_ref);
1009          if let Some(trajectory) = trajectory {
1010            let trajectory = trajectory.to_trajectory();
1011            self.state.graph.update_trajectory(n.1, trajectory);
1012          };
1013        }
1014      }
1015
1016      // Update LMC
1017      self.update_lmc(*v_idx);
1018
1019      // Put v in queue if inconsistent
1020      let v = self.state.graph.get_node(*v_idx);
1021      if v.cost.lmc != v.cost.g {
1022        self.verrify_queue(*v_idx)
1023      }
1024    }
1025  }
1026
1027  /// Check that the given coordinate does not intersect with any obstacles
1028  fn is_free(&self, v: &SVector<X, N>) -> bool {
1029    self.cspace.is_free(v) && self.state.obs_space.is_free(v)
1030  }
1031
1032  /// Check that the given trajectory does not intersect with any obstacles
1033  fn trajectory_free<TF, S1, S2>(&self, t: &TF) -> bool
1034  where
1035    TF: FullTrajectory<X, CS::Traj, S1, S2, N>,
1036    S1: Storage<X, Const<N>>,
1037    S2: Storage<X, Const<N>>,
1038  {
1039    self.state.obs_space.trajectory_free(t)
1040  }
1041
1042  /// Verifies v is in the queue and updates it's spot with possibily new cost
1043  fn verrify_queue(&mut self, v_idx: NodeIndex) {
1044    let node = self.state.graph.get_node(v_idx);
1045    self.queue.push(v_idx, node.cost.priority());
1046  }
1047
1048  /// Ensures that v becomes an orphan
1049  fn verrify_orphan(&mut self, v_idx: NodeIndex) {
1050    self.queue.remove(&v_idx);
1051    self.state.graph.add_orphan(v_idx);
1052  }
1053
1054  /// Update the lmc of v by checking neighbors of v for a better cost path
1055  fn update_lmc(&mut self, v_idx: NodeIndex) {
1056    // Possibly remove some neighbors
1057    self.cull_neighbors(v_idx);
1058
1059    // Iterate over all outgoing neighbors
1060    let mut outgoing = self
1061      .state
1062      .graph
1063      .neighbor_set_walker(v_idx, NeighborSet::Outgoing);
1064    while let Some((edge_idx, u_idx)) = outgoing.next(&self.state.graph) {
1065      // Skip if u is an orphan
1066      if self.state.graph.is_orphan(u_idx) {
1067        continue;
1068      }
1069
1070      // Skip if v is the parent of u
1071      if self.state.graph.is_parent(u_idx, v_idx) {
1072        continue;
1073      }
1074
1075      // Gather data
1076      let edge_cost = self.state.graph.get_trajectory_cost(edge_idx);
1077      let u_cost = self.state.graph.get_node(u_idx).cost;
1078
1079      // Check if v should be rewired
1080      let v = self.state.graph.get_node_mut(v_idx);
1081      if v.cost.lmc > edge_cost + u_cost.lmc {
1082        // Update cost and new parent of v
1083        v.cost.lmc = edge_cost + u_cost.lmc;
1084        self.state.graph.change_parent(v_idx, u_idx).unwrap();
1085      }
1086    }
1087  }
1088
1089  /// Find the first viable parent in the optimal path that is more than min_cost away
1090  ///
1091  /// panics if move_goal_idx is an orphan
1092  fn find_move_goal_along_path(
1093    &self,
1094    pose: &SVector<X, N>,
1095    move_goal_idx: NodeIndex,
1096  ) -> Option<(CS::Traj, NodeIndex)> {
1097    // This is an invariant, if the move_goal exists then the optimal path exists
1098    let mut optimal_path_iter =
1099      self.state.graph.get_optimal_path(move_goal_idx).unwrap();
1100
1101    optimal_path_iter.next(); // Pop off the current goal (move_goal_idx)
1102
1103    // Seach the path for the first viable node that is more than min_cost away
1104    for node_idx in optimal_path_iter {
1105      log::info!("  --> Considering {:?}", node_idx);
1106      let node = self.state.graph.get_node(node_idx).state();
1107
1108      if let Some(trajectory) =
1109        self.cspace.trajectory(pose.clone(), node.clone())
1110      {
1111        log::info!("  --> CSpace Trajectory Valid");
1112        if self.trajectory_free(&trajectory) {
1113          let cost = trajectory.cost();
1114          log::info!("  --> Trajectory Free, cost: {:?}", cost);
1115
1116          // Valid trajectory, see if it is longer than min_cost,
1117          // disregarding min_cost if global goal is found
1118          if self.state.params.min_cost < cost
1119            || node_idx == self.state.graph.get_goal_idx()
1120          {
1121            return Some((trajectory.to_trajectory(), node_idx));
1122          }
1123          continue;
1124        }
1125      }
1126      // Invalid trajectory, cut off search if farther than delta
1127      let cost = self.cspace.cost(pose, node);
1128      if self.state.params.delta < cost {
1129        log::info!("Cutting search along path short");
1130        return None;
1131      }
1132    }
1133    None
1134  }
1135
1136  /// Irreversibly delete the specified node from both the queue and the graph
1137  ///
1138  /// panics if `idx` is invalid
1139  fn delete_node(&mut self, v_idx: NodeIndex) {
1140    // Remove from queue if in it
1141    self.queue.remove(&v_idx);
1142
1143    // remove from graph
1144    self.state.graph.delete_node(v_idx);
1145  }
1146
1147  /// The current move goal is unreachable, this looks for a new one
1148  /// Returns Some new move goal if one is viable
1149  fn find_new_path(
1150    &self,
1151    pose: SVector<X, N>,
1152  ) -> Option<(SVector<X, N>, CS::Traj, NodeIndex)> {
1153    // Create temporary Node as the given pose
1154    let mut pose_node = Node::new(pose);
1155
1156    // Create Iterator over all points in cost order
1157    let cost_func = |a: &[X], b: &[X]| {
1158      let a = VectorSlice::<X, Const<N>>::from_slice(a);
1159      let b = VectorSlice::<X, Const<N>>::from_slice(b);
1160      self.cspace.cost(&a, &b)
1161    };
1162    let mut iter = self
1163      .kdtree
1164      .iter_nearest(pose.as_slice(), &cost_func)
1165      .expect("kdtree error")
1166      .filter(|(_, &idx)| self.state.graph.check_node(idx));
1167
1168    // Create first batch to determine the initial batch size
1169    let mut batch = Vec::new();
1170    loop {
1171      match iter.next() {
1172        Some((cost, &idx)) => {
1173          if cost < self.state.params.min_cost {
1174            continue;
1175          }
1176          if cost >= self.state.radius {
1177            break;
1178          }
1179          batch.push(idx);
1180        }
1181        None => break,
1182      }
1183    }
1184
1185    // Search the first batch
1186    log::info!("  - Searching {:?} nearest nodes", batch.len());
1187    if let Some((traj, idx)) = self.find_parent(&mut pose_node, &batch) {
1188      log::info!("  - Found new move goal");
1189      return Some((pose, traj, idx));
1190    }
1191
1192    // Search for a viable target in batches that double in size each loop
1193    // up until the cost is greater than delta
1194    loop {
1195      // Reset and create new batch of double size
1196      let batch_size = 2 * batch.len();
1197      batch.clear();
1198      while let Some((cost, &idx)) = iter.next() {
1199        if cost < self.state.params.min_cost {
1200          continue;
1201        }
1202        if self.state.params.delta < cost {
1203          log::warn!(
1204            "  - Cutting search short, min_cost and delta are too restrictive"
1205          );
1206          break;
1207        }
1208
1209        batch.push(idx);
1210        if batch.len() >= batch_size {
1211          break;
1212        }
1213      }
1214
1215      // Iterator stopped giving elements, we have searched every node
1216      if batch.is_empty() {
1217        log::info!("  - End of search, no new move goal found");
1218        return None;
1219      }
1220
1221      // Search the batch
1222      log::info!("  - Searching next {:?} nearest nodes", batch.len());
1223      if let Some((traj, idx)) = self.find_parent(&mut pose_node, &batch) {
1224        log::info!("  - Found new move goal");
1225        return Some((pose, traj, idx));
1226      }
1227    }
1228  }
1229}
1230
1231#[cfg(test)]
1232mod tests {
1233
1234  use parry3d::math::Isometry;
1235  use parry3d::shape::{Ball, Cuboid, SharedShape};
1236  use rand::SeedableRng;
1237
1238  use crate::cspace::EuclideanSpace;
1239  use crate::obstacles::obstacles_3d_f32::{Obstacle3df32, ObstacleSpace3df32};
1240  use crate::rng::RNG;
1241  use crate::util::bounds::Bounds;
1242
1243  use super::*;
1244
1245  const SEED: u64 = 0xe580e2e93fd6b040;
1246
1247  #[test]
1248  fn test_rrtx() {
1249    let init = [5.0, 0.5, 5.0].into();
1250    let goal = [-5.0, 0.5, -5.0].into();
1251
1252    let robot_specs = RobotSpecs {
1253      robot_radius: 0.1,
1254      sensor_radius: 2.0,
1255    };
1256
1257    let bounds = Bounds::new([-5.0, 0.0, -5.0].into(), [5.0, 1.0, 5.0].into());
1258    let cspace = EuclideanSpace::new(bounds, RNG::seed_from_u64(SEED)).unwrap();
1259
1260    let ball = Obstacle3df32::with_offset(
1261      SharedShape::new(Ball::new(0.5)),
1262      Isometry::translation(0.0, 0.5, 0.0),
1263    );
1264
1265    let cube = Obstacle3df32::with_offset(
1266      SharedShape::new(Cuboid::new([0.5, 0.5, 0.5].into())),
1267      Isometry::translation(2.5, 0.5, 2.5),
1268    );
1269
1270    let obs_space = ObstacleSpace3df32::from(vec![ball, cube]);
1271
1272    let params = RrtxParams {
1273      min_cost: 0.0,
1274      portion: 0.1,
1275      delta: 1.0,
1276      gamma: 1067.0,
1277      eps: 0.01,
1278    };
1279
1280    let mut rrtx =
1281      Rrtx::new(init, goal, robot_specs, cspace, obs_space, params).unwrap();
1282
1283    let path = loop {
1284      rrtx.create_node();
1285      rrtx.update_pose(init, false);
1286      if let Some(path) = rrtx.get_path_to_goal() {
1287        break path;
1288      }
1289    };
1290
1291    let mut cost = 0.0;
1292    for i in 0..path.len() - 1 {
1293      cost += path[i].metric_distance(&path[i + 1]);
1294    }
1295    println!("{:?}", rrtx.count());
1296    println!("{:?}", rrtx.state.radius);
1297    println!("{:?}", path);
1298    println!("{:?}", cost);
1299  }
1300
1301  #[test]
1302  fn test_serialize_rrtx_state() {
1303    let init = [5.0, 0.5, 5.0].into();
1304    let goal = [-5.0, 0.5, -5.0].into();
1305
1306    let robot_specs = RobotSpecs {
1307      robot_radius: 0.1,
1308      sensor_radius: 2.0,
1309    };
1310
1311    let bounds = Bounds::new([-5.0, 0.0, -5.0].into(), [5.0, 1.0, 5.0].into());
1312    let cspace = EuclideanSpace::new(bounds, RNG::seed_from_u64(SEED)).unwrap();
1313
1314    let ball = Obstacle3df32::with_offset(
1315      SharedShape::new(Ball::new(0.5)),
1316      Isometry::translation(0.0, 0.5, 0.0),
1317    );
1318
1319    let cube = Obstacle3df32::with_offset(
1320      SharedShape::new(Cuboid::new([0.5, 0.5, 0.5].into())),
1321      Isometry::translation(2.5, 0.5, 2.5),
1322    );
1323
1324    let obs_space = ObstacleSpace3df32::from(vec![ball, cube]);
1325
1326    let params = RrtxParams {
1327      min_cost: 0.0,
1328      portion: 0.1,
1329      delta: 1.0,
1330      gamma: 1067.0,
1331      eps: 0.01,
1332    };
1333
1334    let mut rrtx =
1335      Rrtx::new(init, goal, robot_specs, cspace, obs_space, params).unwrap();
1336
1337    loop {
1338      rrtx.create_node();
1339      rrtx.update_pose(init, false);
1340      if let Some(_) = rrtx.get_path_to_goal() {
1341        break;
1342      }
1343    }
1344
1345    let state = rrtx.get_state();
1346    let v = bincode::serialize(&state).unwrap();
1347    let _: RrtxState<f32, EuclideanSpace<f32, 3>, ObstacleSpace3df32, 3> =
1348      bincode::deserialize(&v).unwrap();
1349  }
1350}