Exotica
time_indexed_rrt_connect.h
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018, University of Edinburgh
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without specific
15 // prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 
30 #ifndef TIME_INDEXED_RRT_CONNECT_SOLVER_TIME_INDEXED_RRT_CONNECT_H_
31 #define TIME_INDEXED_RRT_CONNECT_SOLVER_TIME_INDEXED_RRT_CONNECT_H_
32 
33 #include <memory>
34 
37 
38 #include <ompl/base/SpaceInformation.h>
39 #include <ompl/base/StateSpace.h>
40 #include <ompl/base/StateValidityChecker.h>
41 #include <ompl/base/goals/GoalSampleableRegion.h>
42 #include <ompl/base/spaces/RealVectorStateSpace.h>
43 #include <ompl/base/spaces/TimeStateSpace.h>
44 #include <ompl/geometric/SimpleSetup.h>
45 #include <ompl/tools/config/SelfConfig.h>
46 
47 #include <exotica_time_indexed_rrt_connect_solver/time_indexed_rrt_connect_initializer.h>
48 
49 namespace exotica
50 {
51 class OMPLTimeIndexedRNStateSpace : public ompl::base::CompoundStateSpace
52 {
53 public:
54  class StateType : public ompl::base::CompoundStateSpace::StateType
55  {
56  public:
57  StateType() : CompoundStateSpace::StateType()
58  {
59  }
60 
61  const ompl::base::RealVectorStateSpace::StateType &getRNSpace() const
62  {
63  return *as<ompl::base::RealVectorStateSpace::StateType>(0);
64  }
65 
66  ompl::base::RealVectorStateSpace::StateType &getRNSpace()
67  {
68  return *as<ompl::base::RealVectorStateSpace::StateType>(0);
69  }
70 
71  const ompl::base::TimeStateSpace::StateType &getTime() const
72  {
73  return *as<ompl::base::TimeStateSpace::StateType>(1);
74  }
75 
76  ompl::base::TimeStateSpace::StateType &getTime()
77  {
78  return *as<ompl::base::TimeStateSpace::StateType>(1);
79  }
80  };
81  OMPLTimeIndexedRNStateSpace(TimeIndexedSamplingProblemPtr &prob, TimeIndexedRRTConnectSolverInitializer init);
82 
83  ompl::base::StateSamplerPtr allocDefaultStateSampler() const override;
84  void ExoticaToOMPLState(const Eigen::VectorXd &q, const double &t, ompl::base::State *state) const;
85  void OMPLToExoticaState(const ompl::base::State *state, Eigen::VectorXd &q, double &t) const;
86  void StateDebug(const Eigen::VectorXd &q) const;
87 
89 };
90 
91 class OMPLTimeIndexedStateValidityChecker : public ompl::base::StateValidityChecker
92 {
93 public:
94  OMPLTimeIndexedStateValidityChecker(const ompl::base::SpaceInformationPtr &si, const TimeIndexedSamplingProblemPtr &prob);
95 
96  bool isValid(const ompl::base::State *state) const override;
97 
98  bool isValid(const ompl::base::State *state, double &dist) const override;
99 
100 protected:
102 };
103 
104 typedef boost::function<ompl::base::PlannerPtr(const ompl::base::SpaceInformationPtr &si, const std::string &name)> ConfiguredPlannerAllocator;
105 
106 class TimeIndexedRRTConnectSolver : public MotionSolver, Instantiable<TimeIndexedRRTConnectSolverInitializer>
107 {
108 public:
109  void Instantiate(const TimeIndexedRRTConnectSolverInitializer &init) override;
110  void Solve(Eigen::MatrixXd &solution) override;
111  void SpecifyProblem(PlanningProblemPtr pointer) override;
112  void SetPlannerTerminationCondition(const std::shared_ptr<ompl::base::PlannerTerminationCondition> &ptc);
113 
114 protected:
115  template <typename T>
116  static ompl::base::PlannerPtr allocatePlanner(const ompl::base::SpaceInformationPtr &si, const std::string &new_name)
117  {
118  ompl::base::PlannerPtr planner(new T(si));
119  if (!new_name.empty()) planner->setName(new_name);
120  return planner;
121  }
122 
123  void SetGoalState(const Eigen::VectorXd &qT, const double t, const double eps = 0);
124  void PreSolve();
125  void PostSolve();
126  void GetPath(Eigen::MatrixXd &traj, ompl::base::PlannerTerminationCondition &ptc);
127 
129  ompl::geometric::SimpleSetupPtr ompl_simple_setup_;
130  ompl::base::StateSpacePtr state_space_;
132  std::string algorithm_;
133  std::shared_ptr<ompl::base::PlannerTerminationCondition> ptc_;
134 };
135 
136 using namespace ompl;
137 class OMPLTimeIndexedRRTConnect : public base::Planner
138 {
139 public:
140  OMPLTimeIndexedRRTConnect(const base::SpaceInformationPtr &si);
141 
142  virtual ~OMPLTimeIndexedRRTConnect();
143 
144  void getPlannerData(base::PlannerData &data) const override;
145 
146  base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override;
147 
148  void clear() override;
149 
154  void setRange(double distance)
155  {
156  maxDistance_ = distance;
157  }
158 
160  double getRange() const
161  {
162  return maxDistance_;
163  }
164 
166  template <template <typename T> class NN>
168  {
169  tStart_.reset(new NN<Motion *>());
170  tGoal_.reset(new NN<Motion *>());
171  }
172 
173  void setup() override;
174 
175 protected:
177  class Motion
178  {
179  public:
180  Motion() = default;
181 
182  Motion(const base::SpaceInformationPtr &si) : state(si->allocState())
183  {
184  }
185 
186  ~Motion() = default;
187 
188  const base::State *root = nullptr;
189  base::State *state = nullptr;
190  Motion *parent = nullptr;
191  };
192 
194  typedef std::shared_ptr<NearestNeighbors<Motion *> > TreeData;
195 
198  {
199  base::State *xstate;
201  bool start;
203  };
204 
207  {
213  REACHED
214  };
215 
217  void freeMemory();
218 
220  double distanceFunction(const Motion *a, const Motion *b) const
221  {
222  return si_->distance(a->state, b->state);
223  }
224 
225  double forwardTimeDistance(const Motion *a, const Motion *b) const
226  {
227  static const Eigen::VectorXd max_vel = si_->getStateSpace()->as<OMPLTimeIndexedRNStateSpace>()->prob_->vel_limits;
228 
229  double ta, tb;
230  Eigen::VectorXd qa, qb;
231  si_->getStateSpace()->as<OMPLTimeIndexedRNStateSpace>()->OMPLToExoticaState(a->state, qa, ta);
232  si_->getStateSpace()->as<OMPLTimeIndexedRNStateSpace>()->OMPLToExoticaState(b->state, qb, tb);
233 
234  if (tb < ta) return 1e10;
235  Eigen::VectorXd diff = (qb - qa).cwiseAbs();
236  double min_dt = (diff.array() / max_vel.array()).maxCoeff();
237  if (fabs(tb - ta) < min_dt) return 1e10;
238  return si_->distance(a->state, b->state);
239  }
240 
241  double reverseTimeDistance(const Motion *a, const Motion *b) const
242  {
243  static const Eigen::VectorXd max_vel = si_->getStateSpace()->as<OMPLTimeIndexedRNStateSpace>()->prob_->vel_limits;
244 
245  double ta, tb;
246  Eigen::VectorXd qa, qb;
247  si_->getStateSpace()->as<OMPLTimeIndexedRNStateSpace>()->OMPLToExoticaState(a->state, qa, ta);
248  si_->getStateSpace()->as<OMPLTimeIndexedRNStateSpace>()->OMPLToExoticaState(b->state, qb, tb);
249 
250  if (tb > ta) return 1e10;
251  Eigen::VectorXd diff = (qb - qa).cwiseAbs();
252  double min_dt = (diff.array() / max_vel.array()).maxCoeff();
253  if (fabs(tb - ta) < min_dt) return 1e10;
254  return si_->distance(a->state, b->state);
255  }
256 
257  bool correctTime(const Motion *a, Motion *b, bool reverse, bool &changed) const
258  {
259  Eigen::VectorXd max_vel = si_->getStateSpace()->as<OMPLTimeIndexedRNStateSpace>()->prob_->vel_limits;
260  double ta, tb;
261  Eigen::VectorXd qa, qb;
262  si_->getStateSpace()->as<OMPLTimeIndexedRNStateSpace>()->OMPLToExoticaState(a->state, qa, ta);
263  si_->getStateSpace()->as<OMPLTimeIndexedRNStateSpace>()->OMPLToExoticaState(b->state, qb, tb);
264  Eigen::VectorXd diff = (qb - qa).cwiseAbs();
265  double min_dt = (diff.array() / max_vel.array()).maxCoeff();
266  if (fabs(tb - ta) < min_dt)
267  {
268  if (reverse_check_) return false;
269  tb = ta + (reverse ? -min_dt : min_dt);
270  changed = true;
271  }
272  else
273  changed = false;
274  if (tb < si_->getStateSpace()->as<OMPLTimeIndexedRNStateSpace>()->prob_->t_start || tb > si_->getStateSpace()->as<OMPLTimeIndexedRNStateSpace>()->prob_->GetGoalTime()) return false;
275  si_->getStateSpace()->as<OMPLTimeIndexedRNStateSpace>()->ExoticaToOMPLState(qb, tb, b->state);
276  return true;
277  }
278 
280  GrowState growTree(TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion);
281 
283  base::StateSamplerPtr sampler_;
284 
287 
290 
292  double maxDistance_;
293 
295  RNG rng_;
296 
298  std::pair<base::State *, base::State *> connectionPoint_;
299 
301 };
302 } // namespace exotica
303 
304 #endif // TIME_INDEXED_RRT_CONNECT_SOLVER_TIME_INDEXED_RRT_CONNECT_H_
exotica::OMPLTimeIndexedRNStateSpace::StateType::getRNSpace
ompl::base::RealVectorStateSpace::StateType & getRNSpace()
Definition: time_indexed_rrt_connect.h:66
exotica::OMPLTimeIndexedRRTConnect::Motion::state
base::State * state
Definition: time_indexed_rrt_connect.h:189
exotica::OMPLTimeIndexedRRTConnect::setNearestNeighbors
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Definition: time_indexed_rrt_connect.h:167
exotica::TimeIndexedRRTConnectSolver::prob_
TimeIndexedSamplingProblemPtr prob_
Definition: time_indexed_rrt_connect.h:128
exotica::OMPLTimeIndexedRRTConnect::ADVANCED
@ ADVANCED
progress has been made towards the randomly sampled state
Definition: time_indexed_rrt_connect.h:211
exotica::TimeIndexedRRTConnectSolver::PreSolve
void PreSolve()
exotica::OMPLTimeIndexedRNStateSpace::prob_
TimeIndexedSamplingProblemPtr prob_
Definition: time_indexed_rrt_connect.h:88
exotica::OMPLTimeIndexedRNStateSpace::StateType::getTime
ompl::base::TimeStateSpace::StateType & getTime()
Definition: time_indexed_rrt_connect.h:76
exotica::TimeIndexedRRTConnectSolver
Definition: time_indexed_rrt_connect.h:106
exotica::TimeIndexedRRTConnectSolver::SetGoalState
void SetGoalState(const Eigen::VectorXd &qT, const double t, const double eps=0)
exotica::OMPLTimeIndexedRRTConnect::Motion::Motion
Motion(const base::SpaceInformationPtr &si)
Definition: time_indexed_rrt_connect.h:182
exotica::OMPLTimeIndexedRRTConnect::TreeData
std::shared_ptr< NearestNeighbors< Motion * > > TreeData
A nearest-neighbor datastructure representing a tree of motions.
Definition: time_indexed_rrt_connect.h:194
exotica::TimeIndexedRRTConnectSolver::Instantiate
void Instantiate(const TimeIndexedRRTConnectSolverInitializer &init) override
exotica::OMPLTimeIndexedRNStateSpace
Definition: time_indexed_rrt_connect.h:51
exotica::OMPLTimeIndexedRNStateSpace::allocDefaultStateSampler
ompl::base::StateSamplerPtr allocDefaultStateSampler() const override
exotica::OMPLTimeIndexedRNStateSpace::StateType
Definition: time_indexed_rrt_connect.h:54
exotica::OMPLTimeIndexedStateValidityChecker
Definition: time_indexed_rrt_connect.h:91
exotica::TimeIndexedRRTConnectSolver::Solve
void Solve(Eigen::MatrixXd &solution) override
exotica::OMPLTimeIndexedRRTConnect::distanceFunction
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: time_indexed_rrt_connect.h:220
exotica::Instantiable
Definition: property.h:110
exotica
Definition: cartpole_dynamics_solver.h:38
exotica::OMPLTimeIndexedRRTConnect::GrowState
GrowState
The state of the tree after an attempt to extend it.
Definition: time_indexed_rrt_connect.h:206
exotica::TimeIndexedRRTConnectSolver::PostSolve
void PostSolve()
exotica::OMPLTimeIndexedRRTConnect::TreeGrowingInfo
Information attached to growing a tree of motions (used internally)
Definition: time_indexed_rrt_connect.h:197
exotica::OMPLTimeIndexedRRTConnect::setRange
void setRange(double distance)
Set the range the planner is supposed to use. This parameter greatly influences the runtime of the al...
Definition: time_indexed_rrt_connect.h:154
exotica::OMPLTimeIndexedRRTConnect::TreeGrowingInfo::xstate
base::State * xstate
Definition: time_indexed_rrt_connect.h:199
exotica::OMPLTimeIndexedRRTConnect::connectionPoint_
std::pair< base::State *, base::State * > connectionPoint_
The pair of states in each tree connected during planning. Used for PlannerData computation.
Definition: time_indexed_rrt_connect.h:298
exotica::OMPLTimeIndexedRNStateSpace::StateType::getRNSpace
const ompl::base::RealVectorStateSpace::StateType & getRNSpace() const
Definition: time_indexed_rrt_connect.h:61
exotica::OMPLTimeIndexedRRTConnect::correctTime
bool correctTime(const Motion *a, Motion *b, bool reverse, bool &changed) const
Definition: time_indexed_rrt_connect.h:257
time_indexed_sampling_problem.h
exotica::OMPLTimeIndexedRRTConnect::TRAPPED
@ TRAPPED
no progress has been made
Definition: time_indexed_rrt_connect.h:209
exotica::OMPLTimeIndexedRNStateSpace::StateType::getTime
const ompl::base::TimeStateSpace::StateType & getTime() const
Definition: time_indexed_rrt_connect.h:71
exotica::OMPLTimeIndexedRRTConnect::maxDistance_
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition: time_indexed_rrt_connect.h:292
exotica::TimeIndexedRRTConnectSolver::GetPath
void GetPath(Eigen::MatrixXd &traj, ompl::base::PlannerTerminationCondition &ptc)
exotica::OMPLTimeIndexedRNStateSpace::OMPLTimeIndexedRNStateSpace
OMPLTimeIndexedRNStateSpace(TimeIndexedSamplingProblemPtr &prob, TimeIndexedRRTConnectSolverInitializer init)
exotica::TimeIndexedRRTConnectSolver::algorithm_
std::string algorithm_
Definition: time_indexed_rrt_connect.h:132
exotica::OMPLTimeIndexedStateValidityChecker::prob_
TimeIndexedSamplingProblemPtr prob_
Definition: time_indexed_rrt_connect.h:101
exotica::ConfiguredPlannerAllocator
boost::function< ompl::base::PlannerPtr(const ompl::base::SpaceInformationPtr &si, const std::string &name)> ConfiguredPlannerAllocator
Definition: time_indexed_rrt_connect.h:104
exotica::OMPLTimeIndexedRRTConnect::rng_
RNG rng_
The random number generator.
Definition: time_indexed_rrt_connect.h:295
exotica::OMPLTimeIndexedRRTConnect::TreeGrowingInfo::start
bool start
Definition: time_indexed_rrt_connect.h:201
exotica::OMPLTimeIndexedRRTConnect::tStart_
TreeData tStart_
The start tree.
Definition: time_indexed_rrt_connect.h:286
exotica::TimeIndexedRRTConnectSolver::planner_allocator_
ConfiguredPlannerAllocator planner_allocator_
Definition: time_indexed_rrt_connect.h:131
exotica::TimeIndexedRRTConnectSolver::ompl_simple_setup_
ompl::geometric::SimpleSetupPtr ompl_simple_setup_
Definition: time_indexed_rrt_connect.h:129
exotica::TimeIndexedRRTConnectSolver::SetPlannerTerminationCondition
void SetPlannerTerminationCondition(const std::shared_ptr< ompl::base::PlannerTerminationCondition > &ptc)
motion_solver.h
exotica::TimeIndexedRRTConnectSolver::allocatePlanner
static ompl::base::PlannerPtr allocatePlanner(const ompl::base::SpaceInformationPtr &si, const std::string &new_name)
Definition: time_indexed_rrt_connect.h:116
exotica::OMPLTimeIndexedRRTConnect::reverse_check_
bool reverse_check_
Definition: time_indexed_rrt_connect.h:300
exotica::OMPLTimeIndexedRRTConnect::reverseTimeDistance
double reverseTimeDistance(const Motion *a, const Motion *b) const
Definition: time_indexed_rrt_connect.h:241
exotica::OMPLTimeIndexedRNStateSpace::StateType::StateType
StateType()
Definition: time_indexed_rrt_connect.h:57
exotica::MotionSolver
Definition: motion_solver.h:42
exotica::OMPLTimeIndexedRRTConnect::tGoal_
TreeData tGoal_
The goal tree.
Definition: time_indexed_rrt_connect.h:289
exotica::PlanningProblemPtr
std::shared_ptr< PlanningProblem > PlanningProblemPtr
Definition: planning_problem.h:116
exotica::TimeIndexedRRTConnectSolver::state_space_
ompl::base::StateSpacePtr state_space_
Definition: time_indexed_rrt_connect.h:130
exotica::OMPLTimeIndexedRNStateSpace::OMPLToExoticaState
void OMPLToExoticaState(const ompl::base::State *state, Eigen::VectorXd &q, double &t) const
exotica::TimeIndexedSamplingProblemPtr
std::shared_ptr< exotica::TimeIndexedSamplingProblem > TimeIndexedSamplingProblemPtr
Definition: time_indexed_sampling_problem.h:89
exotica::TimeIndexedRRTConnectSolver::SpecifyProblem
void SpecifyProblem(PlanningProblemPtr pointer) override
exotica::OMPLTimeIndexedRNStateSpace::StateDebug
void StateDebug(const Eigen::VectorXd &q) const
exotica::OMPLTimeIndexedRRTConnect::forwardTimeDistance
double forwardTimeDistance(const Motion *a, const Motion *b) const
Definition: time_indexed_rrt_connect.h:225
exotica::OMPLTimeIndexedStateValidityChecker::isValid
bool isValid(const ompl::base::State *state) const override
exotica::OMPLTimeIndexedRRTConnect::getRange
double getRange() const
Get the range the planner is using.
Definition: time_indexed_rrt_connect.h:160
exotica::OMPLTimeIndexedRRTConnect
Definition: time_indexed_rrt_connect.h:137
exotica::OMPLTimeIndexedRRTConnect::sampler_
base::StateSamplerPtr sampler_
State sampler.
Definition: time_indexed_rrt_connect.h:283
exotica::OMPLTimeIndexedStateValidityChecker::OMPLTimeIndexedStateValidityChecker
OMPLTimeIndexedStateValidityChecker(const ompl::base::SpaceInformationPtr &si, const TimeIndexedSamplingProblemPtr &prob)
exotica::OMPLTimeIndexedRNStateSpace::ExoticaToOMPLState
void ExoticaToOMPLState(const Eigen::VectorXd &q, const double &t, ompl::base::State *state) const
exotica::OMPLTimeIndexedRRTConnect::TreeGrowingInfo::correct_time
bool correct_time
Definition: time_indexed_rrt_connect.h:202
exotica::TimeIndexedRRTConnectSolver::ptc_
std::shared_ptr< ompl::base::PlannerTerminationCondition > ptc_
Definition: time_indexed_rrt_connect.h:133
exotica::OMPLTimeIndexedRRTConnect::TreeGrowingInfo::xmotion
Motion * xmotion
Definition: time_indexed_rrt_connect.h:200
exotica::OMPLTimeIndexedRRTConnect::Motion
Representation of a motion.
Definition: time_indexed_rrt_connect.h:177