28 #ifndef HPP_MANIPULATION_CORBA_PATH_PLANNERS_IDL 29 #define HPP_MANIPULATION_CORBA_PATH_PLANNERS_IDL 30 #include <hpp/common.idl> 32 #include <hpp/core_idl/path_planners.idl> 38 interface PathPlanner;
39 interface PathProjector;
42 module manipulation_idl {
47 module pathPlanner_idl {
54 long getNRandomConfig ( ) raises (Error);
56 void setNRandomConfig (in
long n) raises (Error);
59 long getNDiscreteSteps ( ) raises (Error);
61 void setNDiscreteSteps (in
long n) raises (Error);
64 boolean getCheckFeasibilityOnly ( ) raises (Error);
66 void setCheckFeasibilityOnly (in
boolean n) raises (Error);
75 core_idl::PathVector planPath(in floatSeq qInit,
76 in floatSeqSeq qGoals, in
boolean resetRoadmap) raises(Error);
77 core_idl::Path directPath(in floatSeq q1, in floatSeq q2, in
boolean 78 validate, out
boolean success, out
string status) raises(Error);
79 core_idl::PathVector optimizePath(in core_idl::Path path) raises(Error);
80 core_idl::PathVector timeParameterization(in core_idl::PathVector path)
82 void setReedsAndSheppSteeringMethod(in
double turningRadius)
84 void setEdge(in
long id) raises(Error);
85 void setPathProjector(in
string pathProjectorType,in
double tolerance)
94 void clearPathOptimizers() raises(Error);
95 void addPathOptimizer(in
string pathOptimizerType) raises(Error);
103 void setParameter (in
string name, in any value) raises (Error);
124 #endif // HPP_MANIPULATION_CORBA_PATH_PLANNERS_IDL Definition: _path_planners.idl:48
Definition: _graph.idl:87
Definition: _path_planners.idl:52
Definition: _path_planners.idl:73
Definition: _path_planners.idl:43