Generic implementation of RRT algorithm. More...
#include <hpp/core/diffusing-planner.hh>
Public Member Functions | |
| virtual void | oneStep () |
| One step of extension. More... | |
| void | configurationShooter (const ConfigurationShooterPtr_t &shooter) |
| Set configuration shooter. More... | |
Public Member Functions inherited from hpp::core::PathPlanner | |
| virtual | ~PathPlanner () |
| virtual const RoadmapPtr_t & | roadmap () const |
| Get roadmap. More... | |
| const Problem & | problem () const |
| Get problem. More... | |
| virtual void | startSolve () |
| Initialize the problem resolution. More... | |
| virtual PathVectorPtr_t | solve () |
| Solve. More... | |
| virtual void | tryDirectPath () HPP_CORE_DEPRECATED |
| Try to make direct connection between init and goal configurations, in order to avoid a random shoot. More... | |
| virtual void | tryConnectInitAndGoals () |
| Try to connect initial and goal configurations to existing roadmap. More... | |
| virtual PathVectorPtr_t | finishSolve (const PathVectorPtr_t &path) |
| Post processing of the resulting path. More... | |
| void | interrupt () |
| Interrupt path planning. More... | |
| void | maxIterations (const unsigned long int &n) |
| Set maximal number of iterations. More... | |
| void | timeOut (const double &timeOut) |
| set time out (in seconds) More... | |
| PathVectorPtr_t | computePath () const |
| Find a path in the roadmap and transform it in trajectory. More... | |
Static Public Member Functions | |
| static DiffusingPlannerPtr_t | createWithRoadmap (const Problem &problem, const RoadmapPtr_t &roadmap) |
| Return shared pointer to new object. More... | |
| static DiffusingPlannerPtr_t | create (const Problem &problem) |
| Return shared pointer to new object. More... | |
Protected Member Functions | |
| DiffusingPlanner (const Problem &problem, const RoadmapPtr_t &roadmap) | |
| Constructor. More... | |
| DiffusingPlanner (const Problem &problem) | |
| Constructor with roadmap. More... | |
| void | init (const DiffusingPlannerWkPtr_t &weak) |
| Store weak pointer to itself. More... | |
| virtual PathPtr_t | extend (const NodePtr_t &near, const Configuration_t &target) |
| Extend a node in the direction of a configuration. More... | |
Protected Member Functions inherited from hpp::core::PathPlanner | |
| PathPlanner (const Problem &problem) | |
| Constructor. More... | |
| PathPlanner (const Problem &problem, const RoadmapPtr_t &roadmap) | |
| Constructor. More... | |
| void | init (const PathPlannerWkPtr_t &weak) |
| Store weak pointer to itself. More... | |
Generic implementation of RRT algorithm.
|
protected |
Constructor.
|
protected |
Constructor with roadmap.
| void hpp::core::DiffusingPlanner::configurationShooter | ( | const ConfigurationShooterPtr_t & | shooter | ) |
Set configuration shooter.
|
static |
Return shared pointer to new object.
|
static |
Return shared pointer to new object.
|
protectedvirtual |
Extend a node in the direction of a configuration.
| near | node in the roadmap, |
| target | target configuration |
|
protected |
Store weak pointer to itself.
|
virtual |
One step of extension.
Implements hpp::core::PathPlanner.