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 {
49 module pathPlanner_idl {
56 long getNRandomConfig ( ) raises (Error);
58 void setNRandomConfig (in
long n) raises (Error);
61 long getNDiscreteSteps ( ) raises (Error);
63 void setNDiscreteSteps (in
long n) raises (Error);
66 boolean getCheckFeasibilityOnly ( ) raises (Error);
68 void setCheckFeasibilityOnly (in
boolean n) raises (Error);
77 core_idl::PathVector planPath(in floatSeq qInit,
78 in floatSeqSeq qGoals, in
boolean resetRoadmap) raises(Error);
79 core_idl::Path directPath(in floatSeq q1, in floatSeq q2, in
boolean
80 validate, out
boolean success, out
string status) raises(Error);
81 boolean validateConfiguration(in floatSeq config, in
size_t id, out
ValidationReport report)
95 core_idl::PathVector optimizePath(in core_idl::Path path) raises(Error);
96 core_idl::PathVector timeParameterization(in core_idl::PathVector path)
98 void setReedsAndSheppSteeringMethod(in
double turningRadius)
100 void setEdge(in
long id) raises(Error);
101 void setPathProjector(in
string pathProjectorType,in
double tolerance)
110 void clearPathOptimizers() raises(Error);
111 void addPathOptimizer(in
string pathOptimizerType) raises(Error);
119 void setParameter (in
string name, in any value) raises (Error);
140 #endif // HPP_MANIPULATION_CORBA_PATH_PLANNERS_IDL