Aikido
CRRT.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_PLANNER_OMPL_CRRT_HPP_
2 #define AIKIDO_PLANNER_OMPL_CRRT_HPP_
3 
4 #include <ompl/base/Planner.h>
5 #include <ompl/datastructures/NearestNeighbors.h>
6 #include <ompl/geometric/planners/PlannerIncludes.h>
7 
10 
11 namespace aikido {
12 namespace planner {
13 namespace ompl {
14 
16 class CRRT : public ::ompl::base::Planner
17 {
18 public:
21  explicit CRRT(const ::ompl::base::SpaceInformationPtr& _si);
22 
26  CRRT(const ::ompl::base::SpaceInformationPtr& _si, const std::string& _name);
27 
29  virtual ~CRRT();
30 
36  void getPlannerData(::ompl::base::PlannerData& _data) const override;
37 
48  ::ompl::base::PlannerStatus solve(
49  const ::ompl::base::PlannerTerminationCondition& _ptc) override;
50 
53  ::ompl::base::PlannerStatus solve(double _solveTime);
54 
57  void clear() override;
58 
65  void setGoalBias(double _goalBias);
66 
68  double getGoalBias() const;
69 
75  void setRange(double _distance);
76 
78  double getRange() const;
79 
85 
91  void setProjectionResolution(double _resolution);
92 
96  double getProjectionResolution() const;
97 
104  void setMaxProjectedStepsizeSlackFactor(double _slackFactor);
105 
110  double getMaxProjectedStepsizeSlackFactor() const;
111 
116  void setMinStateDifference(double _mindist);
117 
122  double getMinStateDifference() const;
123 
125  template <template <typename T> class NN>
126  void setNearestNeighbors();
127 
131  void setup() override;
132 
133 protected:
136  class Motion
137  {
138  public:
140  Motion() : state(nullptr), parent(nullptr)
141  {
142  // Do nothing
143  }
144 
146  explicit Motion(const ::ompl::base::SpaceInformationPtr& _si)
147  : state(_si->allocState()), parent(nullptr)
148  {
149  // Do nothing
150  }
151 
154  {
155  // Do nothing
156  }
157 
159  ::ompl::base::State* state;
160 
163  };
164 
166  virtual void freeMemory();
167 
170  double distanceFunction(const Motion* a, const Motion* b) const;
171 
174 
177 
193  const ::ompl::base::PlannerTerminationCondition& ptc,
194  TreeData& tree,
195  Motion* nmotion,
196  ::ompl::base::State* gstate,
197  ::ompl::base::State* xstate,
198  ::ompl::base::Goal* goal,
199  bool returnlast,
200  double& dist,
201  bool& foundgoal);
202 
204  ::ompl::base::StateSamplerPtr mSampler;
205 
208  double mGoalBias;
209 
211  double mMaxDistance;
212 
215  ::ompl::RNG mRng;
216 
219 
222 
224  double mMaxStepsize;
225 
230 
233  double mMinStepsize;
234 };
235 
236 } // namespace ompl
237 } // namespace planner
238 } // namespace aikido
239 
240 #include "detail/CRRT-impl.hpp"
241 
242 #endif // AIKIDO_PLANNER_OMPL_CRRT_HPP_
aikido::planner::ompl::CRRT::Motion::~Motion
~Motion()
Destructor.
Definition: CRRT.hpp:153
aikido::planner::ompl::CRRT::Motion::Motion
Motion(const ::ompl::base::SpaceInformationPtr &_si)
Constructor that allocates memory for the state.
Definition: CRRT.hpp:146
aikido::planner::ompl::ompl_shared_ptr
boost::shared_ptr< T > ompl_shared_ptr
Definition: BackwardCompatibility.hpp:83
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::planner::ompl::CRRT::mCons
constraint::ProjectablePtr mCons
The constraint that must be satisfied throughout the trajectory.
Definition: CRRT.hpp:221
aikido::constraint::ProjectablePtr
std::shared_ptr< Projectable > ProjectablePtr
Definition: Projectable.hpp:33
aikido::planner::ompl::CRRT::setMaxProjectedStepsizeSlackFactor
void setMaxProjectedStepsizeSlackFactor(double _slackFactor)
Set the slack factor for the resolution of the final path after projection.
aikido::planner::ompl::CRRT::freeMemory
virtual void freeMemory()
Free the memory allocated by this planner.
aikido::planner::ompl::CRRT::CRRT
CRRT(const ::ompl::base::SpaceInformationPtr &_si)
Constructor.
aikido::planner::ompl::CRRT::setMinStateDifference
void setMinStateDifference(double _mindist)
Set the minimum distance between two states for them to be considered "equivalent".
aikido::planner::ompl::CRRT::mMaxProjectedStepsizeSlackFactor
double mMaxProjectedStepsizeSlackFactor
We multiply this with mMaxStepsize to get the maximum length of a step after projecting: in other wor...
Definition: CRRT.hpp:229
aikido::planner::ompl::CRRT::mRng
::ompl::RNG mRng
The random number generator used to determine whether to sample a goal state or a state uniformly fro...
Definition: CRRT.hpp:215
aikido::planner::ompl::CRRT::setProjectionResolution
void setProjectionResolution(double _resolution)
Set the resolution for the projection.
aikido::planner::ompl::CRRT::mGoalBias
double mGoalBias
The fraction of time the goal is picked as the state to expand towards (if such a state is available)
Definition: CRRT.hpp:208
aikido::planner::ompl::CRRT::getGoalBias
double getGoalBias() const
Get the goal bias the planner is using.
aikido::planner::ompl::CRRT::constrainedExtend
Motion * constrainedExtend(const ::ompl::base::PlannerTerminationCondition &ptc, TreeData &tree, Motion *nmotion, ::ompl::base::State *gstate, ::ompl::base::State *xstate, ::ompl::base::Goal *goal, bool returnlast, double &dist, bool &foundgoal)
Perform an extension that projects to a constraint.
aikido::planner::ompl::CRRT::mMaxStepsize
double mMaxStepsize
The maximum length of a step before projecting.
Definition: CRRT.hpp:224
aikido::planner::ompl::CRRT::setup
void setup() override
Perform extra configuration steps, if needed.
Projectable.hpp
aikido::planner::ompl::CRRT::Motion::state
::ompl::base::State * state
The state contained in this node.
Definition: CRRT.hpp:159
aikido::planner::ompl::CRRT::getPlannerData
void getPlannerData(::ompl::base::PlannerData &_data) const override
Get information about the current run of the motion planner.
aikido::planner::ompl::CRRT::getMinStateDifference
double getMinStateDifference() const
Get the minimum distance between two states for them to be considered "equivalent".
aikido::planner::ompl::CRRT::clear
void clear() override
Clear all internal datastructures.
CRRT-impl.hpp
aikido::planner::ompl::CRRT::setPathConstraint
void setPathConstraint(constraint::ProjectablePtr _projectable)
Set a projectable constraint to be applied throughout the trajectory.
aikido::planner::ompl::CRRT::getRange
double getRange() const
Get the range the planner is using.
aikido::planner::ompl::CRRT::Motion::Motion
Motion()
Constructor. Sets state and parent to null ptr.
Definition: CRRT.hpp:140
aikido::planner::ompl::CRRT::Motion
Representation of a node in the tree.
Definition: CRRT.hpp:136
aikido::planner::ompl::CRRT::setRange
void setRange(double _distance)
Set the range the planner is supposed to use.
aikido::planner::ompl::CRRT::mLastGoalMotion
Motion * mLastGoalMotion
The most recent goal motion. Used for PlannerData computation.
Definition: CRRT.hpp:218
aikido::planner::ompl::CRRT::mStartTree
TreeData mStartTree
A nearest-neighbors datastructure containing the tree of motions.
Definition: CRRT.hpp:176
aikido::planner::ompl::CRRT::getProjectionResolution
double getProjectionResolution() const
Get the resolution for the projection.
aikido::planner::ompl::CRRT::mMinStepsize
double mMinStepsize
The minumum step size along the constraint.
Definition: CRRT.hpp:233
aikido::planner::ompl::CRRT::setNearestNeighbors
void setNearestNeighbors()
Set a nearest neighbors data structure.
Definition: CRRT-impl.hpp:7
aikido::planner::ompl::CRRT::solve
::ompl::base::PlannerStatus solve(const ::ompl::base::PlannerTerminationCondition &_ptc) override
Function that can solve the motion planning problem.
BackwardCompatibility.hpp
aikido::planner::ompl::CRRT::Motion::parent
Motion * parent
The parent of this node.
Definition: CRRT.hpp:162
aikido::planner::ompl::CRRT::mSampler
::ompl::base::StateSamplerPtr mSampler
State sampler.
Definition: CRRT.hpp:204
aikido::planner::ompl::CRRT::mMaxDistance
double mMaxDistance
The maximum length of a motion to be added to a tree.
Definition: CRRT.hpp:211
aikido::planner::ompl::CRRT
Implements a constrained RRT planner.
Definition: CRRT.hpp:16
aikido::planner::ompl::CRRT::setGoalBias
void setGoalBias(double _goalBias)
Set the goal bias.
aikido::planner::ompl::CRRT::TreeData
ompl_shared_ptr<::ompl::NearestNeighbors< Motion * > > TreeData
A nearest-neighbor datastructure representing a tree of motions *‍/.
Definition: CRRT.hpp:173
aikido::planner::ompl::CRRT::getMaxProjectedStepsizeSlackFactor
double getMaxProjectedStepsizeSlackFactor() const
Get the slack factor for the resolution of the final path after projection.
aikido::planner::ompl::CRRT::distanceFunction
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states.
aikido::planner::ompl::CRRT::~CRRT
virtual ~CRRT()
Destructor.