RRT.cpp
51 Planner::declareParam<double>("goal_bias", this, &RRT::setGoalBias, &RRT::getGoalBias, "0.:.05:1.");
52 Planner::declareParam<bool>("intermediate_states", this, &RRT::setIntermediateStates, &RRT::getIntermediateStates);
96 ompl::base::PlannerStatus ompl::control::RRT::solve(const base::PlannerTerminationCondition &ptc)
121 OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), nn_->size());
143 /* sample a random control that attempts to go towards the random state, and also sample a control duration */
144 unsigned int cd = controlSampler_->sampleTo(rctrl, nmotion->control, nmotion->state, rmotion->state);
247 path->append(mpath[i]->state, mpath[i]->control, mpath[i]->steps * siC_->getPropagationStepSize());
bool approximateSolutions
Flag indicating whether the planner is able to compute approximate solutions.
Definition: Planner.h:214
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:164
unsigned int getMinControlDuration() const
Get the minimum number of steps a control is propagated for.
Definition: SpaceInformation.h:161
bool getIntermediateStates() const
Return true if the intermediate states generated along motions are to be added to the tree itself...
Definition: RRT.h:102
unsigned int propagateWhileValid(const base::State *state, const Control *control, int steps, base::State *result) const
Propagate the model of the system forward, starting at a given state, with a given control...
Definition: SpaceInformation.cpp:147
void append(const base::State *state)
Append state to the end of the path; it is assumed state is the first state, so no control is applied...
Definition: PathControl.cpp:266
virtual bool hasControls() const
Indicate whether any information about controls (ompl::control::Control) is stored in this instance...
Definition: PlannerData.cpp:800
virtual void clear()
Clear datastructures. Call this function if the input data to the planner has changed and you do not ...
Definition: RRT.cpp:68
boost::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition: RRT.h:180
unsigned int addGoalVertex(const PlannerDataVertex &v)
Adds the given vertex to the graph data, and marks it as a start vertex. The vertex index is returned...
Definition: PlannerData.cpp:434
virtual base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc)
Continue solving for some amount of time. Return true if solution was found.
Definition: RRT.cpp:96
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Definition: PlannerTerminationCondition.h:64
Representation of an edge in PlannerData for planning with controls. This structure encodes a specifi...
Definition: PlannerData.h:60
void freeControl(Control *control) const
Free the memory of a control.
Definition: SpaceInformation.h:100
bool addIntermediateStates_
Flag indicating whether intermediate states are added to the built tree of motions.
Definition: RRT.h:186
void setIntermediateStates(bool addIntermediateStates)
Specify whether the intermediate states generated along motions are to be added to the tree itself...
Definition: RRT.h:108
virtual void setup()
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: RRT.cpp:60
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition: PlannerData.h:60
DirectedControlSamplerPtr allocDirectedControlSampler() const
Allocate an instance of the DirectedControlSampler to use. This will be the default (SimpleDirectedCo...
Definition: SpaceInformation.cpp:74
Invalid start state or no start state specified.
Definition: PlannerStatus.h:56
double getPropagationStepSize() const
Propagation is performed at integer multiples of a specified step size. This function returns the val...
Definition: SpaceInformation.h:207
Abstract definition of a goal region that can be sampled.
Definition: GoalSampleableRegion.h:49
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition: RRT.h:192
virtual void setup()
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: Planner.cpp:86
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
virtual bool addEdge(unsigned int v1, unsigned int v2, const PlannerDataEdge &edge=PlannerDataEdge(), Cost weight=Cost(1.0))
Adds a directed edge between the given vertex indexes. An optional edge structure and weight can be s...
Definition: PlannerData.cpp:444
bool canSample() const
Return true if maxSampleCount() > 0, since in this case samples can certainly be produced.
Definition: GoalSampleableRegion.h:70
unsigned int addStartVertex(const PlannerDataVertex &v)
Adds the given vertex to the graph data, and marks it as a start vertex. The vertex index is returned...
Definition: PlannerData.cpp:425
virtual void checkValidity()
Check to see if the planner is in a working state (setup has been called, a goal was set...
Definition: Planner.cpp:100
A boost shared pointer wrapper for ompl::control::SpaceInformation.
const State * nextStart()
Return the next valid start state or NULL if no more valid start states are available.
Definition: Planner.cpp:230
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: RRT.h:165
void nullControl(Control *control) const
Make the control have no effect if it were to be applied to a state for any amount of time...
Definition: SpaceInformation.h:137
const SpaceInformation * siC_
The base::SpaceInformation cast as control::SpaceInformation, for convenience.
Definition: RRT.h:177
virtual void getPlannerData(base::PlannerData &data) const
Get information about the current run of the motion planner. Repeated calls to this function will upd...
Definition: RRT.cpp:266
virtual bool isSatisfied(const State *st) const =0
Return true if the state satisfies the goal constraints.
virtual void sampleGoal(State *st) const =0
Sample a state in the goal region.
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
Definition: RRT.h:183
A boost shared pointer wrapper for ompl::base::Path.
void copyControl(Control *destination, const Control *source) const
Copy a control to another.
Definition: SpaceInformation.h:106