hpp-rbprm
4.10.0
Implementation of RB-PRM planner using hpp.
|
Go to the documentation of this file.
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 (
const core::Problem& problem,
const core::RoadmapPtr_t&
roadmap);
78 virtual const core::RoadmapPtr_t&
roadmap ()
const{
92 void init (
const ParabolaPlannerWkPtr_t& weak);
96 virtual core::PathPtr_t
extend (
const core::NodePtr_t& near,
97 const core::ConfigurationPtr_t& target);
98 virtual core::PathPtr_t
extendParabola (
const core::NodePtr_t& near,
99 const core::ConfigurationPtr_t& target);
115 void computeGIWC(
const core::NodePtr_t x){
119 void computeGIWC(
const core::NodePtr_t node, core::ValidationReportPtr_t report){
124 core::ConfigurationShooterPtr_t configurationShooter_;
125 mutable core::Configuration_t qProj_;
126 ParabolaPlannerWkPtr_t weakPtr_;
129 const core::RoadmapPtr_t roadmap_;
134 #endif // HPP_CORE_DIFFUSING_PLANNER_HH
HPP_PREDEF_CLASS(RbPrmFullBody)
std::vector< DelayedEdge_t > DelayedEdges_t
Definition: parabola-planner.hh:38
Definition: rbprm-node.hh:23
void init(const ParabolaPlannerWkPtr_t &weak)
Store weak pointer to itself.
static ParabolaPlannerPtr_t create(const core::Problem &problem)
Return shared pointer to new object.
boost::tuple< core::NodePtr_t, core::ConfigurationPtr_t, core::PathPtr_t > DelayedEdge_t
Definition: parabola-planner.hh:37
ParabolaPlanner(const core::Problem &problem, const core::RoadmapPtr_t &roadmap)
Constructor.
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
boost::shared_ptr< SteeringMethodParabola > SteeringMethodParabolaPtr_t
Definition: steering-method-parabola.hh:37
const core::RbprmRoadmapPtr_t & rbprmRoadmap() const
Definition: parabola-planner.hh:82
virtual const core::RoadmapPtr_t & roadmap() const
Definition: parabola-planner.hh:78
Definition: algorithm.hh:27
virtual void startSolve()
virtual void tryDirectPath()
boost::shared_ptr< RbprmRoadmap > RbprmRoadmapPtr_t
Definition: rbprm-roadmap.hh:13
void configurationShooter(const core::ConfigurationShooterPtr_t &shooter)
Set configuration shooter.
virtual void oneStep()
One step of extension.
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.
boost::shared_ptr< ParabolaPlanner > ParabolaPlannerPtr_t
Definition: parabola-planner.hh:36
virtual core::PathPtr_t extendParabola(const core::NodePtr_t &near, const core::ConfigurationPtr_t &target)