Loading...
Searching...
No Matches
TSRRT.cpp
42ompl::geometric::TSRRT::TSRRT(const base::SpaceInformationPtr &si, const TaskSpaceConfigPtr &task_space)
48 Planner::declareParam<double>("range", this, &TSRRT::setRange, &TSRRT::getRange, "0.:1.:10000.");
49 Planner::declareParam<double>("goal_bias", this, &TSRRT::setGoalBias, &TSRRT::getGoalBias, "0.:.05:1.");
74 nn_->setDistanceFunction([this](const Motion *a, const Motion *b) { return distanceFunction(a, b); });
92ompl::base::PlannerStatus ompl::geometric::TSRRT::solve(const base::PlannerTerminationCondition &ptc)
116 OMPL_INFORM("%s: Starting with %u states already in datastructure. %d dimensional projection", getName().c_str(),
241 data.addEdge(base::PlannerDataVertex(motion->parent->state), base::PlannerDataVertex(motion->state));
Abstract definition of a goal region that can be sampled.
Definition GoalSampleableRegion.h:48
virtual bool isSatisfied(const State *st) const =0
Return true if the state satisfies the goal constraints.
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition PlannerData.h:59
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Definition PlannerData.h:175
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:413
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:422
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:432
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Definition PlannerTerminationCondition.h:64
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:106
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)
Definition TSRRT.h:193
TSRRT(const base::SpaceInformationPtr &si, const TaskSpaceConfigPtr &task_space)
Constructor.
Definition TSRRT.cpp:42
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition TSRRT.h:175
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 TSRRT.cpp:225
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition TSRRT.h:189
virtual base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc)
Function that can solve the motion planning problem. This function can be called multiple times on th...
Definition TSRRT.cpp:92
virtual void clear()
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition TSRRT.cpp:57
virtual void setup()
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition TSRRT.cpp:66
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition TSRRT.h:202
This class contains methods that automatically configure various parameters for motion planning....
Definition SelfConfig.h:60
static NearestNeighbors< _T > * getDefaultNearestNeighbors(const base::Planner *planner)
Select a default nearest neighbor datastructure for the given space.
Definition SelfConfig.h:106
void configurePlannerRange(double &range)
Compute what a good length for motion segments is.
Definition SelfConfig.cpp:225
This namespace contains sampling based planning routines shared by both planning under geometric cons...
Definition ConstrainedSpaceInformation.h:55
A class to store the exit status of Planner::solve()
Definition PlannerStatus.h:49