Loading...
Searching...
No Matches
AORRTC.h
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition RandomNumbers.h:57
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition Cost.h:48
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Definition PlannerData.h:175
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Definition PlannerTerminationCondition.h:64
ompl::base::Cost bestCost() const
Retrieve the best exact-solution cost found.
Definition AORRTC.cpp:60
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition AORRTC.cpp:53
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition AORRTC.cpp:65
void getPlannerData(base::PlannerData &data) const override
Get information about the current run of the motion planner. Repeated calls to this function will upd...
Definition AORRTC.cpp:226
void simplifySolution(const base::PathPtr &p, const base::PlannerTerminationCondition &ptc)
Attempt to simplify the current solution path. Stop computation when ptc becomes true at the latest.
Definition AORRTC.cpp:105
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Function that can solve the motion planning problem. This function can be called multiple times on th...
Definition AORRTC.cpp:119
A shared pointer wrapper for ompl::geometric::PathSimplifier.
This namespace contains code that is specific to planning under geometric constraints.
Definition GeneticSearch.h:48
Main namespace. Contains everything in this library.
Definition MultiLevelPlanarManipulatorDemo.cpp:66
A class to store the exit status of Planner::solve().
Definition PlannerStatus.h:49