import </local/robotpkg/var/tmp/robotpkg/path/py-hpp-manipulation-corba/work/hpp-manipulation-corba-5.2.0/idl/hpp/manipulation_idl/_path_planners.idl;
|
core_idl::PathVector | planPath (in floatSeq qInit, in floatSeqSeq qGoals, in boolean resetRoadmap) raises (Error) |
|
core_idl::Path | directPath (in floatSeq q1, in floatSeq q2, in boolean validate, out boolean success, out string status) raises (Error) |
|
boolean | validateConfiguration (in floatSeq config, in size_t id, out ValidationReport report) raises (Error) |
|
core_idl::PathVector | optimizePath (in core_idl::Path path) raises (Error) |
|
core_idl::PathVector | timeParameterization (in core_idl::PathVector path) raises (Error) |
|
void | setReedsAndSheppSteeringMethod (in double turningRadius) raises (Error) |
|
void | setEdge (in long id) raises (Error) |
|
void | setPathProjector (in string pathProjectorType, in double tolerance) raises (Error) |
|
void | clearPathOptimizers () raises (Error) |
|
void | addPathOptimizer (in string pathOptimizerType) raises (Error) |
|
void | setParameter (in string name, in any value) raises (Error) |
|
◆ addPathOptimizer()
void hpp::manipulation_idl::pathPlanner_idl::TransitionPlanner::addPathOptimizer |
( |
in string | pathOptimizerType | ) |
|
raises | ( | Error ) | | | |
◆ clearPathOptimizers()
void hpp::manipulation_idl::pathPlanner_idl::TransitionPlanner::clearPathOptimizers |
( |
| ) |
|
raises | ( | Error ) | | | |
◆ directPath()
core_idl::Path hpp::manipulation_idl::pathPlanner_idl::TransitionPlanner::directPath |
( |
in floatSeq | q1, |
|
|
in floatSeq | q2, |
|
|
in boolean | validate, |
|
|
out boolean | success, |
|
|
out string | status ) |
raises | ( | Error ) | | | |
◆ optimizePath()
core_idl::PathVector hpp::manipulation_idl::pathPlanner_idl::TransitionPlanner::optimizePath |
( |
in core_idl::Path | path | ) |
|
raises | ( | Error ) | | | |
◆ planPath()
core_idl::PathVector hpp::manipulation_idl::pathPlanner_idl::TransitionPlanner::planPath |
( |
in floatSeq | qInit, |
|
|
in floatSeqSeq | qGoals, |
|
|
in boolean | resetRoadmap ) |
raises | ( | Error ) | | | |
◆ setEdge()
void hpp::manipulation_idl::pathPlanner_idl::TransitionPlanner::setEdge |
( |
in long | id | ) |
|
raises | ( | Error ) | | | |
◆ setParameter()
void hpp::manipulation_idl::pathPlanner_idl::TransitionPlanner::setParameter |
( |
in string | name, |
|
|
in any | value ) |
raises | ( | Error ) | | | |
◆ setPathProjector()
void hpp::manipulation_idl::pathPlanner_idl::TransitionPlanner::setPathProjector |
( |
in string | pathProjectorType, |
|
|
in double | tolerance ) |
raises | ( | Error ) | | | |
◆ setReedsAndSheppSteeringMethod()
void hpp::manipulation_idl::pathPlanner_idl::TransitionPlanner::setReedsAndSheppSteeringMethod |
( |
in double | turningRadius | ) |
|
raises | ( | Error ) | | | |
◆ timeParameterization()
core_idl::PathVector hpp::manipulation_idl::pathPlanner_idl::TransitionPlanner::timeParameterization |
( |
in core_idl::PathVector | path | ) |
|
raises | ( | Error ) | | | |
◆ validateConfiguration()
boolean hpp::manipulation_idl::pathPlanner_idl::TransitionPlanner::validateConfiguration |
( |
in floatSeq | config, |
|
|
in size_t | id, |
|
|
out ValidationReport | report ) |
raises | ( | Error ) | | | |
The documentation for this interface was generated from the following file: