19 #ifndef HPP_RBPRM_PARABOLA_PLANNER_HH 20 #define HPP_RBPRM_PARABOLA_PLANNER_HH 22 #include <hpp/core/path-planner.hh> 23 #include <hpp/core/steering-method.hh> 24 #include <boost/tuple/tuple.hpp> 37 typedef boost::tuple<core::NodePtr_t, core::ConfigurationPtr_t, core::PathPtr_t>
DelayedEdge_t;
46 static ParabolaPlannerPtr_t
create(
const core::Problem& problem);
73 DelayedEdges_t& delayedEdges);
80 virtual const core::RoadmapPtr_t&
roadmap()
const {
return roadmap_; }
86 ParabolaPlanner(
const core::Problem& problem,
const core::RoadmapPtr_t& roadmap);
90 void init(
const ParabolaPlannerWkPtr_t& weak);
94 virtual core::PathPtr_t
extend(
const core::NodePtr_t& near,
const core::ConfigurationPtr_t& target);
95 virtual core::PathPtr_t
extendParabola(
const core::NodePtr_t& near,
const core::ConfigurationPtr_t& target);
112 void computeGIWC(
const core::NodePtr_t x) { computeGIWC(static_cast<core::RbprmNodePtr_t>(x)); }
114 void computeGIWC(
const core::NodePtr_t node, core::ValidationReportPtr_t report) {
115 computeGIWC(static_cast<core::RbprmNodePtr_t>(node), report);
118 core::ConfigurationShooterPtr_t configurationShooter_;
119 mutable core::Configuration_t qProj_;
120 ParabolaPlannerWkPtr_t weakPtr_;
123 const core::RoadmapPtr_t roadmap_;
128 #endif // HPP_CORE_DIFFUSING_PLANNER_HH Definition: algorithm.hh:27
ParabolaPlanner(const core::Problem &problem, const core::RoadmapPtr_t &roadmap)
Constructor.
std::vector< DelayedEdge_t > DelayedEdges_t
Definition: parabola-planner.hh:38
Definition: rbprm-node.hh:22
virtual core::PathPtr_t extend(const core::NodePtr_t &near, const core::ConfigurationPtr_t &target)
static ParabolaPlannerPtr_t createWithRoadmap(const core::Problem &problem, const core::RoadmapPtr_t &roadmap)
Return shared pointer to new object.
std::shared_ptr< RbprmRoadmap > RbprmRoadmapPtr_t
Definition: rbprm-roadmap.hh:13
std::shared_ptr< ParabolaPlanner > ParabolaPlannerPtr_t
Definition: parabola-planner.hh:36
boost::tuple< core::NodePtr_t, core::ConfigurationPtr_t, core::PathPtr_t > DelayedEdge_t
Definition: parabola-planner.hh:37
virtual void oneStep()
One step of extension.
HPP_PREDEF_CLASS(RbPrmFullBody)
virtual core::PathPtr_t extendParabola(const core::NodePtr_t &near, const core::ConfigurationPtr_t &target)
void init(const ParabolaPlannerWkPtr_t &weak)
Store weak pointer to itself.
void configurationShooter(const core::ConfigurationShooterPtr_t &shooter)
Set configuration shooter.
virtual const core::RoadmapPtr_t & roadmap() const
Definition: parabola-planner.hh:80
std::shared_ptr< SteeringMethodParabola > SteeringMethodParabolaPtr_t
Definition: steering-method-parabola.hh:37
core::PathPtr_t computeRandomParabola(core::NodePtr_t x_start, core::ConfigurationPtr_t q_target, DelayedEdges_t &delayedEdges)
computeRandomParabola
Generic implementation of RRT algorithm.
Definition: parabola-planner.hh:41
virtual void tryDirectPath()
virtual void startSolve()
const core::RbprmRoadmapPtr_t & rbprmRoadmap() const
Definition: parabola-planner.hh:82
static ParabolaPlannerPtr_t create(const core::Problem &problem)
Return shared pointer to new object.