#include <hpp/manipulation/path-planner/end-effector-trajectory.hh>
◆ EndEffectorTrajectory() [1/2]
hpp::manipulation::pathPlanner::EndEffectorTrajectory::EndEffectorTrajectory |
( |
const core::Problem & |
problem | ) |
|
|
protected |
Protected constructor
- Parameters
-
problem | the path planning problem |
◆ EndEffectorTrajectory() [2/2]
Protected constructor
- Parameters
-
problem | the path planning problem |
roadmap | previously built roadmap |
◆ 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()
Return shared pointer to new instance
- Parameters
-
problem | the path planning problem |
◆ createWithRoadmap()
Return shared pointer to new instance
- Parameters
-
problem | the path planning problem |
roadmap | previously built roadmap |
◆ ikSolverInitialization()
◆ 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 |
◆ 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 |
The documentation for this class was generated from the following file: