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 {
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);
95 core_idl::PathVector
optimizePath(in core_idl::Path path) raises(Error);
111 void addPathOptimizer(in
string pathOptimizerType) raises(Error);
119 void setParameter (in
string name, in any value) raises (Error);
Definition _path_planners.idl:45
void constraintGraph(in graph_idl::Graph graph)
Definition _path_planners.idl:55
Definition _path_planners.idl:51
Definition _path_planners.idl:76
void clearPathOptimizers()
core_idl::PathVector optimizePath(in core_idl::Path path)
void setPathProjector(in string pathProjectorType, in double tolerance)
core_idl::PathVector timeParameterization(in core_idl::PathVector path)
void setReedsAndSheppSteeringMethod(in double turningRadius)
core_idl::PathVector planPath(in floatSeq qInit, in floatSeqSeq qGoals, in boolean resetRoadmap)
core_idl::Path directPath(in floatSeq q1, in floatSeq q2, in boolean validate, out boolean success, out string status)
boolean validateConfiguration(in floatSeq config, in size_t id, out ValidationReport report)
unsigned long long size_t
Definition _path_planners.idl:44
string ValidationReport
Definition _path_planners.idl:43