hpp-manipulation
6.0.0
Classes for manipulation planning.
|
#include <hpp/manipulation/path-planner/end-effector-trajectory.hh>
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 () |
Static Public Member Functions | |
static EndEffectorTrajectoryPtr_t | create (const core::ProblemConstPtr_t &problem) |
static EndEffectorTrajectoryPtr_t | createWithRoadmap (const core::ProblemConstPtr_t &problem, const core::RoadmapPtr_t &roadmap) |
Protected Member Functions | |
EndEffectorTrajectory (const core::ProblemConstPtr_t &problem) | |
EndEffectorTrajectory (const core::ProblemConstPtr_t &problem, const core::RoadmapPtr_t &roadmap) | |
void | init (const EndEffectorTrajectoryWkPtr_t &weak) |
Store weak pointer to itself. More... | |
Plan a path for a robot with constrained trajectory of an end effector
This path planner only works with a steering method of type steeringMethod::EndEffectorTrajectory. The steering method defines the desired end-effector trajectory using a time-varying constraint.
To plan a path between two configurations q_init
and q_goal
, the configurations must satisfy the constraint at the beginning and at the end of the definition interval respectively.
The interval of definition \([0,T]\) of the output path is defined by the time-varying constraint of the steering method. This interval is uniformly discretized in a number of samples that can be accessed using method nDiscreteSteps .
The path is planned by successively calling method oneStep that performs the following actions.
q_init
. The number of random configurations can be accessed by methods nRandomConfig .Note that continuity is not tested but enforced by projecting the configuration of the previous sample to compute the configuration at a given sample.