Go to the documentation of this file.    1 #ifndef AIKIDO_PLANNER_OMPL_CRRTCONNECT_HPP_ 
    2 #define AIKIDO_PLANNER_OMPL_CRRTCONNECT_HPP_ 
    4 #include <ompl/datastructures/NearestNeighbors.h> 
    5 #include <ompl/geometric/planners/PlannerIncludes.h> 
   20   explicit CRRTConnect(const ::ompl::base::SpaceInformationPtr& si);
 
   30   void getPlannerData(::ompl::base::PlannerData& _data) 
const override;
 
   42   ::ompl::base::PlannerStatus 
solve(
 
   43       const ::ompl::base::PlannerTerminationCondition& _ptc) 
override;
 
   47   ::ompl::base::PlannerStatus 
solve(
double _solveTime);
 
   51   void clear() 
override;
 
   61   template <
template <
typename T> 
class NN>
 
   67   void setup() 
override;
 
   90 #endif // AIKIDO_PLANNER_OMPL_CRRTCONNECT_HPP_ 
 
 
void setup() override
Perform extra configuration steps, if needed.
 
CRRTConnect(const ::ompl::base::SpaceInformationPtr &si)
Constructor.
 
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
 
void freeMemory() override
Free the memory allocated by this planner.
 
void clear() override
Clear all internal datastructures.
 
::ompl::base::PlannerStatus solve(const ::ompl::base::PlannerTerminationCondition &_ptc) override
Function that can solve the motion planning problem.
 
Implements a bi-direction constrained RRT planner.
Definition: CRRTConnect.hpp:15
 
std::pair<::ompl::base::State *, ::ompl::base::State * > mConnectionPoint
The pair of states in each tree connected during planning.
Definition: CRRTConnect.hpp:81
 
void setConnectionRadius(double _radius)
 
void getPlannerData(::ompl::base::PlannerData &_data) const override
Get information about the current run of the motion planner.
 
double mConnectionRadius
Max distance between two trees to consider them connected.
Definition: CRRTConnect.hpp:77
 
double getConnectionRadius() const
Get the connection radius the planner is using.
 
virtual ~CRRTConnect()
Destructor.
 
Implements a constrained RRT planner.
Definition: CRRT.hpp:16
 
void setNearestNeighbors()
Set a nearest neighbors data structure for both the start and goal trees.
Definition: CRRTConnect-impl.hpp:7
 
TreeData mGoalTree
The goal tree.
Definition: CRRTConnect.hpp:74
 
ompl_shared_ptr<::ompl::NearestNeighbors< Motion * > > TreeData
A nearest-neighbor datastructure representing a tree of motions */.
Definition: CRRT.hpp:159