path_planning/rrt/
rrt.rs

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