hpp-rbprm  4.11.0
Implementation of RB-PRM planner using hpp.
hpp::rbprm::ParabolaPlanner Class Reference

Generic implementation of RRT algorithm. More...

#include <hpp/rbprm/planner/parabola-planner.hh>

Inheritance diagram for hpp::rbprm::ParabolaPlanner:
Collaboration diagram for hpp::rbprm::ParabolaPlanner:

Public Member Functions

virtual void oneStep ()
 One step of extension. More...
 
virtual void startSolve ()
 
virtual void tryDirectPath ()
 
core::PathPtr_t computeRandomParabola (core::NodePtr_t x_start, core::ConfigurationPtr_t q_target, DelayedEdges_t &delayedEdges)
 computeRandomParabola More...
 
void configurationShooter (const core::ConfigurationShooterPtr_t &shooter)
 Set configuration shooter. More...
 
virtual const core::RoadmapPtr_t & roadmap () const
 
const core::RbprmRoadmapPtr_trbprmRoadmap () const
 

Static Public Member Functions

static ParabolaPlannerPtr_t createWithRoadmap (const core::Problem &problem, const core::RoadmapPtr_t &roadmap)
 Return shared pointer to new object. More...
 
static ParabolaPlannerPtr_t create (const core::Problem &problem)
 Return shared pointer to new object. More...
 

Protected Member Functions

 ParabolaPlanner (const core::Problem &problem, const core::RoadmapPtr_t &roadmap)
 Constructor. More...
 
 ParabolaPlanner (const core::Problem &problem)
 Constructor with roadmap. More...
 
void init (const ParabolaPlannerWkPtr_t &weak)
 Store weak pointer to itself. More...
 
virtual core::PathPtr_t extend (const core::NodePtr_t &near, const core::ConfigurationPtr_t &target)
 
virtual core::PathPtr_t extendParabola (const core::NodePtr_t &near, const core::ConfigurationPtr_t &target)
 

Detailed Description

Generic implementation of RRT algorithm.

Constructor & Destructor Documentation

◆ ParabolaPlanner() [1/2]

hpp::rbprm::ParabolaPlanner::ParabolaPlanner ( const core::Problem &  problem,
const core::RoadmapPtr_t &  roadmap 
)
protected

Constructor.

◆ ParabolaPlanner() [2/2]

hpp::rbprm::ParabolaPlanner::ParabolaPlanner ( const core::Problem &  problem)
protected

Constructor with roadmap.

Member Function Documentation

◆ computeRandomParabola()

core::PathPtr_t hpp::rbprm::ParabolaPlanner::computeRandomParabola ( core::NodePtr_t  x_start,
core::ConfigurationPtr_t  q_target,
DelayedEdges_t delayedEdges 
)

computeRandomParabola

Parameters
x_startinitial node
q_targettarget configuration (we shoot in this direction)
delayedEdgesdelayedEdges, node and edges waiting to be added in roadmap at each iteration
Returns
the path computed (valid or not)

◆ configurationShooter()

void hpp::rbprm::ParabolaPlanner::configurationShooter ( const core::ConfigurationShooterPtr_t &  shooter)

Set configuration shooter.

◆ create()

static ParabolaPlannerPtr_t hpp::rbprm::ParabolaPlanner::create ( const core::Problem &  problem)
static

Return shared pointer to new object.

◆ createWithRoadmap()

static ParabolaPlannerPtr_t hpp::rbprm::ParabolaPlanner::createWithRoadmap ( const core::Problem &  problem,
const core::RoadmapPtr_t &  roadmap 
)
static

Return shared pointer to new object.

◆ extend()

virtual core::PathPtr_t hpp::rbprm::ParabolaPlanner::extend ( const core::NodePtr_t &  near,
const core::ConfigurationPtr_t &  target 
)
protectedvirtual

Extend a node in the direction of a configuration

Parameters
nearnode in the roadmap,
targettarget configuration

◆ extendParabola()

virtual core::PathPtr_t hpp::rbprm::ParabolaPlanner::extendParabola ( const core::NodePtr_t &  near,
const core::ConfigurationPtr_t &  target 
)
protectedvirtual

◆ init()

void hpp::rbprm::ParabolaPlanner::init ( const ParabolaPlannerWkPtr_t &  weak)
protected

Store weak pointer to itself.

◆ oneStep()

virtual void hpp::rbprm::ParabolaPlanner::oneStep ( )
virtual

One step of extension.

◆ rbprmRoadmap()

const core::RbprmRoadmapPtr_t& hpp::rbprm::ParabolaPlanner::rbprmRoadmap ( ) const
inline

◆ roadmap()

virtual const core::RoadmapPtr_t& hpp::rbprm::ParabolaPlanner::roadmap ( ) const
inlinevirtual

◆ startSolve()

virtual void hpp::rbprm::ParabolaPlanner::startSolve ( )
virtual

◆ tryDirectPath()

virtual void hpp::rbprm::ParabolaPlanner::tryDirectPath ( )
virtual

The documentation for this class was generated from the following file: