Generic implementation of RRT algorithm.
More...
#include <hpp/rbprm/planner/parabola-planner.hh>
|
| 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) |
|
Generic implementation of RRT algorithm.
◆ ParabolaPlanner() [1/2]
hpp::rbprm::ParabolaPlanner::ParabolaPlanner |
( |
const core::Problem & |
problem, |
|
|
const core::RoadmapPtr_t & |
roadmap |
|
) |
| |
|
protected |
◆ ParabolaPlanner() [2/2]
hpp::rbprm::ParabolaPlanner::ParabolaPlanner |
( |
const core::Problem & |
problem | ) |
|
|
protected |
Constructor with roadmap.
◆ computeRandomParabola()
core::PathPtr_t hpp::rbprm::ParabolaPlanner::computeRandomParabola |
( |
core::NodePtr_t |
x_start, |
|
|
core::ConfigurationPtr_t |
q_target, |
|
|
DelayedEdges_t & |
delayedEdges |
|
) |
| |
computeRandomParabola
- Parameters
-
x_start | initial node |
q_target | target configuration (we shoot in this direction) |
delayedEdges | delayedEdges, 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()
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
-
near | node in the roadmap, |
target | target 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 |
◆ rbprmRoadmap()
◆ 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: