Go to the documentation of this file. 1 #ifndef AIKIDO_PLANNER_OMPL_CRRT_HPP_
2 #define AIKIDO_PLANNER_OMPL_CRRT_HPP_
4 #include <ompl/base/Planner.h>
5 #include <ompl/datastructures/NearestNeighbors.h>
6 #include <ompl/geometric/planners/PlannerIncludes.h>
16 class CRRT :
public ::ompl::base::Planner
21 explicit CRRT(const ::ompl::base::SpaceInformationPtr& _si);
26 CRRT(const ::ompl::base::SpaceInformationPtr& _si,
const std::string& _name);
36 void getPlannerData(::ompl::base::PlannerData& _data)
const override;
48 ::ompl::base::PlannerStatus
solve(
49 const ::ompl::base::PlannerTerminationCondition& _ptc)
override;
53 ::ompl::base::PlannerStatus
solve(
double _solveTime);
57 void clear()
override;
125 template <
template <
typename T>
class NN>
131 void setup()
override;
146 explicit Motion(const ::ompl::base::SpaceInformationPtr& _si)
193 const ::ompl::base::PlannerTerminationCondition& ptc,
196 ::ompl::base::State* gstate,
197 ::ompl::base::State* xstate,
198 ::ompl::base::Goal* goal,
242 #endif // AIKIDO_PLANNER_OMPL_CRRT_HPP_
~Motion()
Destructor.
Definition: CRRT.hpp:153
Motion(const ::ompl::base::SpaceInformationPtr &_si)
Constructor that allocates memory for the state.
Definition: CRRT.hpp:146
boost::shared_ptr< T > ompl_shared_ptr
Definition: BackwardCompatibility.hpp:83
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
constraint::ProjectablePtr mCons
The constraint that must be satisfied throughout the trajectory.
Definition: CRRT.hpp:221
std::shared_ptr< Projectable > ProjectablePtr
Definition: Projectable.hpp:33
void setMaxProjectedStepsizeSlackFactor(double _slackFactor)
Set the slack factor for the resolution of the final path after projection.
virtual void freeMemory()
Free the memory allocated by this planner.
CRRT(const ::ompl::base::SpaceInformationPtr &_si)
Constructor.
void setMinStateDifference(double _mindist)
Set the minimum distance between two states for them to be considered "equivalent".
double mMaxProjectedStepsizeSlackFactor
We multiply this with mMaxStepsize to get the maximum length of a step after projecting: in other wor...
Definition: CRRT.hpp:229
::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
void setProjectionResolution(double _resolution)
Set the resolution for the projection.
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
double getGoalBias() const
Get the goal bias the planner is using.
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.
double mMaxStepsize
The maximum length of a step before projecting.
Definition: CRRT.hpp:224
void setup() override
Perform extra configuration steps, if needed.
::ompl::base::State * state
The state contained in this node.
Definition: CRRT.hpp:159
void getPlannerData(::ompl::base::PlannerData &_data) const override
Get information about the current run of the motion planner.
double getMinStateDifference() const
Get the minimum distance between two states for them to be considered "equivalent".
void clear() override
Clear all internal datastructures.
void setPathConstraint(constraint::ProjectablePtr _projectable)
Set a projectable constraint to be applied throughout the trajectory.
double getRange() const
Get the range the planner is using.
Motion()
Constructor. Sets state and parent to null ptr.
Definition: CRRT.hpp:140
Representation of a node in the tree.
Definition: CRRT.hpp:136
void setRange(double _distance)
Set the range the planner is supposed to use.
Motion * mLastGoalMotion
The most recent goal motion. Used for PlannerData computation.
Definition: CRRT.hpp:218
TreeData mStartTree
A nearest-neighbors datastructure containing the tree of motions.
Definition: CRRT.hpp:176
double getProjectionResolution() const
Get the resolution for the projection.
double mMinStepsize
The minumum step size along the constraint.
Definition: CRRT.hpp:233
void setNearestNeighbors()
Set a nearest neighbors data structure.
Definition: CRRT-impl.hpp:7
::ompl::base::PlannerStatus solve(const ::ompl::base::PlannerTerminationCondition &_ptc) override
Function that can solve the motion planning problem.
Motion * parent
The parent of this node.
Definition: CRRT.hpp:162
::ompl::base::StateSamplerPtr mSampler
State sampler.
Definition: CRRT.hpp:204
double mMaxDistance
The maximum length of a motion to be added to a tree.
Definition: CRRT.hpp:211
Implements a constrained RRT planner.
Definition: CRRT.hpp:16
void setGoalBias(double _goalBias)
Set the goal bias.
ompl_shared_ptr<::ompl::NearestNeighbors< Motion * > > TreeData
A nearest-neighbor datastructure representing a tree of motions */.
Definition: CRRT.hpp:173
double getMaxProjectedStepsizeSlackFactor() const
Get the slack factor for the resolution of the final path after projection.
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states.
virtual ~CRRT()
Destructor.