hpp-manipulation-corba 5.2.0
Corba server for manipulation planning
Loading...
Searching...
No Matches
_path_planners.idl
Go to the documentation of this file.
1// Copyright (C) 2020 by Joseph Mirabel, LAAS-CNRS.
2//
3// Redistribution and use in source and binary forms, with or without
4// modification, are permitted provided that the following conditions are
5// met:
6//
7// 1. Redistributions of source code must retain the above copyright
8// notice, this list of conditions and the following disclaimer.
9//
10// 2. Redistributions in binary form must reproduce the above copyright
11// notice, this list of conditions and the following disclaimer in the
12// documentation and/or other materials provided with the distribution.
13//
14// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
15// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
16// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
17// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
18// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
19// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
20// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
21// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
22// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
23// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
24// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
25// DAMAGE.
26
27
28#ifndef HPP_MANIPULATION_CORBA_PATH_PLANNERS_IDL
29#define HPP_MANIPULATION_CORBA_PATH_PLANNERS_IDL
30#include <hpp/common.idl>
31
32#include <hpp/core_idl/path_planners.idl>
34
35module hpp
36{
37 module core_idl {
38 interface PathPlanner;
39 interface PathProjector;
40 }; // module core
41
42 module manipulation_idl {
43 typedef string ValidationReport;
44 typedef unsigned long long size_t;
45 interface Roadmap : core_idl::Roadmap {
46 void constraintGraph (in graph_idl::Graph graph) raises (Error);
47 }; // interface Roadmap
48
49 module pathPlanner_idl {
51 {
52 }; // interface IkSolverInitialization
53
54 interface EndEffectorTrajectory : core_idl::PathPlanner
55 {
56 long getNRandomConfig ( ) raises (Error);
57 //-> nRandomConfig
58 void setNRandomConfig (in long n) raises (Error);
59 //-> nRandomConfig
60
61 long getNDiscreteSteps ( ) raises (Error);
62 //-> nDiscreteSteps
63 void setNDiscreteSteps (in long n) raises (Error);
64 //-> nDiscreteSteps
65
66 boolean getCheckFeasibilityOnly ( ) raises (Error);
67 //-> checkFeasibilityOnly
68 void setCheckFeasibilityOnly (in boolean n) raises (Error);
69 //-> checkFeasibilityOnly
70
71 void setIkSolverInitialization (in IkSolverInitialization solver);
72 //-> ikSolverInitialization
73 }; // interface EndEffectorTrajectory
74
75 interface TransitionPlanner : core_idl::PathPlanner
76 {
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)
82 raises(Error);
83 //* using namespace hpp::core;
84 //* Configuration_t q(corbaServer::floatSeqToVector(config));
85 //* ValidationReportPtr_t vr;
86 //* bool res = getT()->validateConfiguration(q, id, vr);
87 //* if (vr) {
88 //* std::ostringstream oss; oss << *vr;
89 //* std::string res = oss.str();
90 //* report = CORBA::string_dup(res.c_str());
91 //* } else {
92 //* report = CORBA::string_dup("");
93 //* }
94 //* return res;
95 core_idl::PathVector optimizePath(in core_idl::Path path) raises(Error);
96 core_idl::PathVector timeParameterization(in core_idl::PathVector path)
97 raises(Error);
98 void setReedsAndSheppSteeringMethod(in double turningRadius)
99 raises(Error);
100 void setEdge(in long id) raises(Error);
101 void setPathProjector(in string pathProjectorType,in double tolerance)
102 raises(Error);
103 //* std::string _pathProjectorType (pathProjectorType);
104 //* core::ProblemSolverPtr_t ps = server_->problemSolver();
105 //* core::PathProjectorBuilder_t factory(ps->pathProjectors.get
106 //* (_pathProjectorType));
107 //* core::PathProjectorPtr_t pathProjector(factory(getT()->
108 //* innerProblem(), tolerance));
109 //* (getT()->pathProjector (pathProjector));
110 void clearPathOptimizers() raises(Error);
111 void addPathOptimizer(in string pathOptimizerType) raises(Error);
112 //* std::string _pathOptimizerType (pathOptimizerType);
113 //* core::ProblemSolverPtr_t ps = server_->problemSolver();
114 //* core::PathOptimizerBuilder_t factory(ps->pathOptimizers.get
115 //* (_pathOptimizerType));
116 //* core::PathOptimizerPtr_t pathOptimizer(factory(getT()->
117 //* problem()));
118 //* (getT()->addPathOptimizer (pathOptimizer));
119 void setParameter (in string name, in any value) raises (Error);
120 //* getT()->innerProblem()->setParameter(name,
121 //* hpp::corbaServer::toParameter(value));
122
123 }; // interface TransitionPlanner
124
125 }; // module pathPlanner_idl
126 }; // module manipulation_idl
127}; // module hpp
128
129//* #include <hpp/manipulation/path-planner/end-effector-trajectory.hh>
130//* #include <hpp/manipulation/path-planner/transition-planner.hh>
131//* #include <hpp/core/parameter.hh>
132//* #include <hpp/core/problem.hh>
133//* #include <hpp/core_idl/paths.hh>
134//* #include <hpp/core_idl/path_planners.hh>
135//* #include <hpp/core_idl/path_projectors.hh>
136//* #include <hpp/manipulation_idl/_graph-fwd.hh>
137//* #include <hpp/manipulation/roadmap.hh>
138//* #include <hpp/manipulation/problem-solver.hh>
139
140#endif // HPP_MANIPULATION_CORBA_PATH_PLANNERS_IDL
Definition _path_planners.idl:45
void constraintGraph(in graph_idl::Graph graph)
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
Definition client.hh:46