hpp-manipulation  4.9.0
Classes for manipulation planning.
hpp::manipulation::pathPlanner::EndEffectorTrajectory Class Reference

#include <hpp/manipulation/path-planner/end-effector-trajectory.hh>

Inheritance diagram for hpp::manipulation::pathPlanner::EndEffectorTrajectory:
Collaboration diagram for hpp::manipulation::pathPlanner::EndEffectorTrajectory:

Public Member Functions

virtual void startSolve ()
 
virtual void oneStep ()
 One step of the algorithm. More...
 
int nRandomConfig () const
 
void nRandomConfig (int n)
 
int nDiscreteSteps () const
 Number of steps to generate goal config (successive projections). More...
 
void nDiscreteSteps (int n)
 
void checkFeasibilityOnly (bool enable)
 
bool checkFeasibilityOnly () const
 
void ikSolverInitialization (IkSolverInitializationPtr_t solver)
 
void tryConnectInitAndGoals ()
 
- Public Member Functions inherited from hpp::core::PathPlanner
virtual ~PathPlanner ()
 
virtual const RoadmapPtr_troadmap () const
 
const Problemproblem () const
 
virtual PathVectorPtr_t solve ()
 
virtual void tryDirectPath () HPP_CORE_DEPRECATED
 
virtual PathVectorPtr_t finishSolve (const PathVectorPtr_t &path)
 
void interrupt ()
 
void maxIterations (const unsigned long int &n)
 
void timeOut (const double &timeOut)
 
PathVectorPtr_t computePath () const
 
virtual ~PathPlanner ()
 
virtual const RoadmapPtr_troadmap () const
 
const Problemproblem () const
 
virtual PathVectorPtr_t solve ()
 
virtual void tryDirectPath () HPP_CORE_DEPRECATED
 
virtual PathVectorPtr_t finishSolve (const PathVectorPtr_t &path)
 
void interrupt ()
 
void maxIterations (const unsigned long int &n)
 
void timeOut (const double &timeOut)
 
PathVectorPtr_t computePath () const
 

Static Public Member Functions

static EndEffectorTrajectoryPtr_t create (const core::Problem &problem)
 
static EndEffectorTrajectoryPtr_t createWithRoadmap (const core::Problem &problem, const core::RoadmapPtr_t &roadmap)
 

Protected Member Functions

 EndEffectorTrajectory (const core::Problem &problem)
 
 EndEffectorTrajectory (const core::Problem &problem, const core::RoadmapPtr_t &roadmap)
 
void init (const EndEffectorTrajectoryWkPtr_t &weak)
 Store weak pointer to itself. More...
 
- Protected Member Functions inherited from hpp::core::PathPlanner
 PathPlanner (const Problem &problem)
 
 PathPlanner (const Problem &problem, const RoadmapPtr_t &roadmap)
 
void init (const PathPlannerWkPtr_t &weak)
 
 PathPlanner (const Problem &problem)
 
 PathPlanner (const Problem &problem, const RoadmapPtr_t &roadmap)
 
void init (const PathPlannerWkPtr_t &weak)
 

Constructor & Destructor Documentation

◆ EndEffectorTrajectory() [1/2]

hpp::manipulation::pathPlanner::EndEffectorTrajectory::EndEffectorTrajectory ( const core::Problem problem)
protected

Protected constructor

Parameters
problemthe path planning problem

◆ EndEffectorTrajectory() [2/2]

hpp::manipulation::pathPlanner::EndEffectorTrajectory::EndEffectorTrajectory ( const core::Problem problem,
const core::RoadmapPtr_t roadmap 
)
protected

Protected constructor

Parameters
problemthe path planning problem
roadmappreviously built roadmap

Member Function Documentation

◆ checkFeasibilityOnly() [1/2]

void hpp::manipulation::pathPlanner::EndEffectorTrajectory::checkFeasibilityOnly ( bool  enable)

If enabled, only add one solution to the roadmap. Otherwise add all solution.

◆ checkFeasibilityOnly() [2/2]

bool hpp::manipulation::pathPlanner::EndEffectorTrajectory::checkFeasibilityOnly ( ) const
inline

◆ create()

static EndEffectorTrajectoryPtr_t hpp::manipulation::pathPlanner::EndEffectorTrajectory::create ( const core::Problem problem)
static

Return shared pointer to new instance

Parameters
problemthe path planning problem

◆ createWithRoadmap()

static EndEffectorTrajectoryPtr_t hpp::manipulation::pathPlanner::EndEffectorTrajectory::createWithRoadmap ( const core::Problem problem,
const core::RoadmapPtr_t roadmap 
)
static

Return shared pointer to new instance

Parameters
problemthe path planning problem
roadmappreviously built roadmap

◆ ikSolverInitialization()

void hpp::manipulation::pathPlanner::EndEffectorTrajectory::ikSolverInitialization ( IkSolverInitializationPtr_t  solver)
inline

◆ init()

void hpp::manipulation::pathPlanner::EndEffectorTrajectory::init ( const EndEffectorTrajectoryWkPtr_t &  weak)
protected

Store weak pointer to itself.

◆ nDiscreteSteps() [1/2]

int hpp::manipulation::pathPlanner::EndEffectorTrajectory::nDiscreteSteps ( ) const
inline

Number of steps to generate goal config (successive projections).

◆ nDiscreteSteps() [2/2]

void hpp::manipulation::pathPlanner::EndEffectorTrajectory::nDiscreteSteps ( int  n)
inline

◆ nRandomConfig() [1/2]

int hpp::manipulation::pathPlanner::EndEffectorTrajectory::nRandomConfig ( ) const
inline

Get the number of random configurations shoot (after using init config) in order to generate the initial config of the final path.

◆ nRandomConfig() [2/2]

void hpp::manipulation::pathPlanner::EndEffectorTrajectory::nRandomConfig ( int  n)
inline

◆ oneStep()

virtual void hpp::manipulation::pathPlanner::EndEffectorTrajectory::oneStep ( )
virtual

One step of the algorithm.

Implements hpp::core::PathPlanner.

◆ startSolve()

virtual void hpp::manipulation::pathPlanner::EndEffectorTrajectory::startSolve ( )
virtual

Initialize the problem resolution

  • call parent implementation
  • get number nodes in problem parameter map

Reimplemented from hpp::core::PathPlanner.

◆ tryConnectInitAndGoals()

void hpp::manipulation::pathPlanner::EndEffectorTrajectory::tryConnectInitAndGoals ( )
virtual

Reimplemented from hpp::core::PathPlanner.


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