Aikido
CRRTConnect.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_PLANNER_OMPL_CRRTCONNECT_HPP_
2 #define AIKIDO_PLANNER_OMPL_CRRTCONNECT_HPP_
3 
4 #include <ompl/datastructures/NearestNeighbors.h>
5 #include <ompl/geometric/planners/PlannerIncludes.h>
6 
9 
10 namespace aikido {
11 namespace planner {
12 namespace ompl {
13 
15 class CRRTConnect : public CRRT
16 {
17 public:
20  explicit CRRTConnect(const ::ompl::base::SpaceInformationPtr& si);
21 
23  virtual ~CRRTConnect();
24 
30  void getPlannerData(::ompl::base::PlannerData& _data) const override;
31 
42  ::ompl::base::PlannerStatus solve(
43  const ::ompl::base::PlannerTerminationCondition& _ptc) override;
44 
47  ::ompl::base::PlannerStatus solve(double _solveTime);
48 
51  void clear() override;
52 
55  void setConnectionRadius(double _radius);
56 
58  double getConnectionRadius() const;
59 
61  template <template <typename T> class NN>
62  void setNearestNeighbors();
63 
67  void setup() override;
68 
69 protected:
71  void freeMemory() override;
72 
75 
78 
81  std::pair<::ompl::base::State*, ::ompl::base::State*> mConnectionPoint;
82 };
83 
84 } // namespace ompl
85 } // namespace planner
86 } // namespace aikido
87 
89 
90 #endif // AIKIDO_PLANNER_OMPL_CRRTCONNECT_HPP_
aikido::planner::ompl::CRRTConnect::setup
void setup() override
Perform extra configuration steps, if needed.
aikido::planner::ompl::CRRTConnect::CRRTConnect
CRRTConnect(const ::ompl::base::SpaceInformationPtr &si)
Constructor.
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
CRRT.hpp
aikido::planner::ompl::CRRTConnect::freeMemory
void freeMemory() override
Free the memory allocated by this planner.
aikido::planner::ompl::CRRTConnect::clear
void clear() override
Clear all internal datastructures.
aikido::planner::ompl::CRRTConnect::solve
::ompl::base::PlannerStatus solve(const ::ompl::base::PlannerTerminationCondition &_ptc) override
Function that can solve the motion planning problem.
CRRTConnect-impl.hpp
aikido::planner::ompl::CRRTConnect
Implements a bi-direction constrained RRT planner.
Definition: CRRTConnect.hpp:15
Projectable.hpp
aikido::planner::ompl::CRRTConnect::mConnectionPoint
std::pair<::ompl::base::State *, ::ompl::base::State * > mConnectionPoint
The pair of states in each tree connected during planning.
Definition: CRRTConnect.hpp:81
aikido::planner::ompl::CRRTConnect::setConnectionRadius
void setConnectionRadius(double _radius)
aikido::planner::ompl::CRRTConnect::getPlannerData
void getPlannerData(::ompl::base::PlannerData &_data) const override
Get information about the current run of the motion planner.
aikido::planner::ompl::CRRTConnect::mConnectionRadius
double mConnectionRadius
Max distance between two trees to consider them connected.
Definition: CRRTConnect.hpp:77
aikido::planner::ompl::CRRTConnect::getConnectionRadius
double getConnectionRadius() const
Get the connection radius the planner is using.
aikido::planner::ompl::CRRTConnect::~CRRTConnect
virtual ~CRRTConnect()
Destructor.
aikido::planner::ompl::CRRT
Implements a constrained RRT planner.
Definition: CRRT.hpp:16
aikido::planner::ompl::CRRTConnect::setNearestNeighbors
void setNearestNeighbors()
Set a nearest neighbors data structure for both the start and goal trees.
Definition: CRRTConnect-impl.hpp:7
aikido::planner::ompl::CRRTConnect::mGoalTree
TreeData mGoalTree
The goal tree.
Definition: CRRTConnect.hpp:74
aikido::planner::ompl::CRRT::TreeData
ompl_shared_ptr<::ompl::NearestNeighbors< Motion * > > TreeData
A nearest-neighbor datastructure representing a tree of motions *‍/.
Definition: CRRT.hpp:159