Line |
Branch |
Exec |
Source |
1 |
|
|
// |
2 |
|
|
// Copyright (c) 2005, 2006, 2007, 2008, 2009, 2010, 2011 CNRS |
3 |
|
|
// Authors: Florent Lamiraux |
4 |
|
|
// |
5 |
|
|
|
6 |
|
|
// Redistribution and use in source and binary forms, with or without |
7 |
|
|
// modification, are permitted provided that the following conditions are |
8 |
|
|
// met: |
9 |
|
|
// |
10 |
|
|
// 1. Redistributions of source code must retain the above copyright |
11 |
|
|
// notice, this list of conditions and the following disclaimer. |
12 |
|
|
// |
13 |
|
|
// 2. Redistributions in binary form must reproduce the above copyright |
14 |
|
|
// notice, this list of conditions and the following disclaimer in the |
15 |
|
|
// documentation and/or other materials provided with the distribution. |
16 |
|
|
// |
17 |
|
|
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
18 |
|
|
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
19 |
|
|
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR |
20 |
|
|
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT |
21 |
|
|
// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, |
22 |
|
|
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT |
23 |
|
|
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, |
24 |
|
|
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY |
25 |
|
|
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT |
26 |
|
|
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE |
27 |
|
|
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH |
28 |
|
|
// DAMAGE. |
29 |
|
|
|
30 |
|
|
#ifndef HPP_CORE_PROBLEM_SOLVER_HH |
31 |
|
|
#define HPP_CORE_PROBLEM_SOLVER_HH |
32 |
|
|
|
33 |
|
|
#include <functional> |
34 |
|
|
#include <hpp/core/config.hh> |
35 |
|
|
#include <hpp/core/container.hh> |
36 |
|
|
#include <hpp/core/deprecated.hh> |
37 |
|
|
#include <hpp/core/fwd.hh> |
38 |
|
|
#include <hpp/pinocchio/fwd.hh> |
39 |
|
|
#include <stdexcept> |
40 |
|
|
|
41 |
|
|
namespace hpp { |
42 |
|
|
namespace core { |
43 |
|
|
/// member ProblemSolver::lockedJoints has been removed. LockedJointPtr_t |
44 |
|
|
/// instances are now stored with constraints::ImplicitPtr_t in |
45 |
|
|
/// member numericalConstraints. |
46 |
|
|
class |
47 |
|
|
Member_lockedJoints_in_class_ProblemSolver_has_been_removed_use_member_numericalConstraints_instead { |
48 |
|
|
}; |
49 |
|
|
typedef std::function<DevicePtr_t(const std::string&)> RobotBuilder_t; |
50 |
|
|
typedef std::function<PathOptimizerPtr_t(const ProblemConstPtr_t&)> |
51 |
|
|
PathOptimizerBuilder_t; |
52 |
|
|
typedef std::function<PathPlannerPtr_t(const ProblemConstPtr_t&, |
53 |
|
|
const RoadmapPtr_t&)> |
54 |
|
|
PathPlannerBuilder_t; |
55 |
|
|
typedef std::function<PathValidationPtr_t(const DevicePtr_t&, |
56 |
|
|
const value_type&)> |
57 |
|
|
PathValidationBuilder_t; |
58 |
|
|
typedef std::function<ConfigValidationPtr_t(const DevicePtr_t&)> |
59 |
|
|
ConfigValidationBuilder_t; |
60 |
|
|
typedef std::function<PathProjectorPtr_t(const ProblemConstPtr_t&, |
61 |
|
|
const value_type&)> |
62 |
|
|
PathProjectorBuilder_t; |
63 |
|
|
typedef std::function<ConfigurationShooterPtr_t(const ProblemConstPtr_t&)> |
64 |
|
|
ConfigurationShooterBuilder_t; |
65 |
|
|
typedef std::function<DistancePtr_t(const ProblemConstPtr_t&)> |
66 |
|
|
DistanceBuilder_t; |
67 |
|
|
typedef std::function<SteeringMethodPtr_t(const ProblemConstPtr_t&)> |
68 |
|
|
SteeringMethodBuilder_t; |
69 |
|
|
typedef std::vector<std::pair<std::string, CollisionObjectPtr_t> > |
70 |
|
|
AffordanceObjects_t; |
71 |
|
|
typedef vector3_t AffordanceConfig_t; |
72 |
|
|
|
73 |
|
|
/// Set and solve a path planning problem |
74 |
|
|
/// |
75 |
|
|
/// This class is a container that does the interface between |
76 |
|
|
/// hpp-core library and component to be running in a middleware |
77 |
|
|
/// like CORBA or ROS. |
78 |
|
|
class HPP_CORE_DLLAPI ProblemSolver { |
79 |
|
|
public: |
80 |
|
|
typedef std::vector<PathOptimizerPtr_t> PathOptimizers_t; |
81 |
|
|
typedef std::vector<std::string> PathOptimizerTypes_t; |
82 |
|
|
typedef std::vector<std::string> ConfigValidationTypes_t; |
83 |
|
|
|
84 |
|
|
/// Create instance and return pointer |
85 |
|
|
static ProblemSolverPtr_t create(); |
86 |
|
|
|
87 |
|
|
/// Destructor |
88 |
|
|
virtual ~ProblemSolver(); |
89 |
|
|
|
90 |
|
|
/// Set robot type |
91 |
|
|
/// \param type type of the robots that will be created later |
92 |
|
|
void robotType(const std::string& type); |
93 |
|
|
|
94 |
|
|
/// Get robot type |
95 |
|
|
const std::string& robotType() const; |
96 |
|
|
|
97 |
|
|
/// Create a robot of a type defined by method setRobotType |
98 |
|
|
/// |
99 |
|
|
/// \param name name of the robot |
100 |
|
|
/// |
101 |
|
|
/// Robot is stored in problemSolver. |
102 |
|
|
DevicePtr_t createRobot(const std::string& name); |
103 |
|
|
|
104 |
|
|
/// Set robot |
105 |
|
|
virtual void robot(const DevicePtr_t& robot); |
106 |
|
|
|
107 |
|
|
/// Get robot |
108 |
|
|
const DevicePtr_t& robot() const; |
109 |
|
|
|
110 |
|
|
/// Get pointer to problem |
111 |
|
17 |
ProblemPtr_t problem() { return problem_; } |
112 |
|
|
/// Get shared pointer to initial configuration. |
113 |
|
|
const Configuration_t& initConfig() const { return initConf_; } |
114 |
|
|
/// Set initial configuration. |
115 |
|
|
virtual void initConfig(ConfigurationIn_t config); |
116 |
|
|
/// Get number of goal configuration. |
117 |
|
|
const Configurations_t& goalConfigs() const; |
118 |
|
|
/// Add goal configuration. |
119 |
|
|
virtual void addGoalConfig(ConfigurationIn_t config); |
120 |
|
|
/// Reset the set of goal configurations |
121 |
|
|
void resetGoalConfigs(); |
122 |
|
|
/// Set goal of path planning as a set of constraints |
123 |
|
|
void setGoalConstraints(const NumericalConstraints_t& constraints); |
124 |
|
|
/// Stop defining the goal of path planning as a set of constraints |
125 |
|
|
void resetGoalConstraints(); |
126 |
|
|
/* |
127 |
|
|
/// Add goal constraints |
128 |
|
|
void addGoalConstraint (const ConstraintPtr_t& constraint); |
129 |
|
|
/// Add goal LockedJoint |
130 |
|
|
void addGoalConstraint (const LockedJointPtr_t& lj); |
131 |
|
|
/// Add goal numerical constraints |
132 |
|
|
void addGoalConstraint (const std::string& constraintName, |
133 |
|
|
const std::string& functionName, const std::size_t priority); |
134 |
|
|
/// Reset goal constraints |
135 |
|
|
void resetGoalConstraint (); |
136 |
|
|
*/ |
137 |
|
|
/// Set path planner type |
138 |
|
|
virtual void pathPlannerType(const std::string& type); |
139 |
|
|
const std::string& pathPlannerType() const { return pathPlannerType_; } |
140 |
|
|
/// Set distance type |
141 |
|
|
void distanceType(const std::string& type); |
142 |
|
|
const std::string& distanceType() const { return distanceType_; } |
143 |
|
|
/// Set steering method type |
144 |
|
|
void steeringMethodType(const std::string& type); |
145 |
|
|
const std::string& steeringMethodType() const { return steeringMethodType_; } |
146 |
|
|
/// Set configuration shooter type |
147 |
|
|
void configurationShooterType(const std::string& type); |
148 |
|
|
const std::string& configurationShooterType() const { |
149 |
|
|
return configurationShooterType_; |
150 |
|
|
} |
151 |
|
|
/// Get path planner |
152 |
|
✗ |
const PathPlannerPtr_t& pathPlanner() const { return pathPlanner_; } |
153 |
|
|
|
154 |
|
|
/// Add a path optimizer in the vector |
155 |
|
|
/// |
156 |
|
|
/// \param name of the type of path optimizer that should be added |
157 |
|
|
void addPathOptimizer(const std::string& type); |
158 |
|
|
const PathOptimizerTypes_t& pathOptimizerTypes() const { |
159 |
|
|
return pathOptimizerTypes_; |
160 |
|
|
} |
161 |
|
|
/// Clear the vector of path optimizers |
162 |
|
|
void clearPathOptimizers(); |
163 |
|
|
/// Get path optimizer at given rank |
164 |
|
|
const PathOptimizerPtr_t& pathOptimizer(std::size_t rank) const { |
165 |
|
|
return pathOptimizers_[rank]; |
166 |
|
|
} |
167 |
|
|
|
168 |
|
|
/// Optimize path |
169 |
|
|
/// |
170 |
|
|
/// \param path path to optimize |
171 |
|
|
/// Build vector of path optimizers if needed |
172 |
|
|
/// \note each intermediate optimization output is stored in this object. |
173 |
|
|
void optimizePath(PathVectorPtr_t path); |
174 |
|
|
|
175 |
|
|
/// Set path validation method |
176 |
|
|
/// \param type name of new path validation method |
177 |
|
|
/// \param tolerance acceptable penetration for path validation |
178 |
|
|
/// Path validation methods are used to validate edges in path planning |
179 |
|
|
/// path optimization methods. |
180 |
|
|
virtual void pathValidationType(const std::string& type, |
181 |
|
|
const value_type& tolerance); |
182 |
|
|
const std::string& pathValidationType(value_type& tolerance) const { |
183 |
|
|
tolerance = pathValidationTolerance_; |
184 |
|
|
return pathValidationType_; |
185 |
|
|
} |
186 |
|
|
|
187 |
|
|
/// Set path projector method |
188 |
|
|
/// \param type name of new path validation method |
189 |
|
|
/// \param step discontinuity tolerance |
190 |
|
|
void pathProjectorType(const std::string& type, const value_type& step); |
191 |
|
|
|
192 |
|
|
/// Get path projector current type and get tolerance |
193 |
|
|
const std::string& pathProjectorType(value_type& tolerance) const { |
194 |
|
|
tolerance = pathProjectorTolerance_; |
195 |
|
|
return pathProjectorType_; |
196 |
|
|
} |
197 |
|
|
|
198 |
|
|
/// Add a config validation method |
199 |
|
|
/// \param type name of new config validation method |
200 |
|
|
/// Config validation methods are used to validate individual |
201 |
|
|
/// configurations of the robot. |
202 |
|
|
virtual void addConfigValidation(const std::string& type); |
203 |
|
|
|
204 |
|
|
/// Get config validation current types |
205 |
|
1 |
const ConfigValidationTypes_t configValidationTypes() { |
206 |
|
1 |
return configValidationTypes_; |
207 |
|
|
} |
208 |
|
|
|
209 |
|
|
// Clear the vector of config validations |
210 |
|
|
void clearConfigValidations(); |
211 |
|
|
|
212 |
|
|
/// Add a new available config validation method |
213 |
|
|
void addConfigValidationBuilder(const std::string& type, |
214 |
|
|
const ConfigValidationBuilder_t& builder); |
215 |
|
|
|
216 |
|
15 |
const RoadmapPtr_t& roadmap() const { return roadmap_; } |
217 |
|
|
|
218 |
|
|
/// \name Constraints |
219 |
|
|
/// \{ |
220 |
|
|
|
221 |
|
|
/// Add a constraint |
222 |
|
|
void addConstraint(const ConstraintPtr_t& constraint); |
223 |
|
|
|
224 |
|
|
/// Get constraint set |
225 |
|
✗ |
const ConstraintSetPtr_t& constraints() const { return constraints_; } |
226 |
|
|
|
227 |
|
|
/// Reset constraint set |
228 |
|
|
virtual void resetConstraints(); |
229 |
|
|
|
230 |
|
|
/// Add numerical constraint to the config projector |
231 |
|
|
/// \param configProjName Name given to config projector if created by |
232 |
|
|
/// this method. |
233 |
|
|
/// \param constraintName name of the function as stored in internal map. |
234 |
|
|
/// Build the config projector if not yet constructed. |
235 |
|
|
virtual void addNumericalConstraintToConfigProjector( |
236 |
|
|
const std::string& configProjName, const std::string& constraintName, |
237 |
|
|
const std::size_t priority = 0); |
238 |
|
|
|
239 |
|
|
/// Add a a numerical constraint in local map. |
240 |
|
|
/// \param name name of the numerical constraint as stored in local map, |
241 |
|
|
/// \param constraint numerical constraint |
242 |
|
|
/// |
243 |
|
|
/// Numerical constraints are to be inserted in the ConfigProjector of |
244 |
|
|
/// the constraint set. |
245 |
|
|
void addNumericalConstraint(const std::string& name, |
246 |
|
|
const constraints::ImplicitPtr_t& constraint) { |
247 |
|
|
numericalConstraints.add(name, constraint); |
248 |
|
|
} |
249 |
|
|
|
250 |
|
|
/// Set the comparison types of a constraint. |
251 |
|
|
/// \param name name of the differentiable function. |
252 |
|
|
void comparisonType(const std::string& name, const ComparisonTypes_t types); |
253 |
|
|
|
254 |
|
|
void comparisonType(const std::string& name, const ComparisonType& type); |
255 |
|
|
|
256 |
|
|
ComparisonTypes_t comparisonType(const std::string& name) const; |
257 |
|
|
|
258 |
|
|
/// Get constraint with given name |
259 |
|
|
constraints::ImplicitPtr_t numericalConstraint(const std::string& name) { |
260 |
|
|
return numericalConstraints.get(name, constraints::ImplicitPtr_t()); |
261 |
|
|
} |
262 |
|
|
|
263 |
|
|
/// Compute value and Jacobian of numerical constraints |
264 |
|
|
/// |
265 |
|
|
/// \param configuration input configuration |
266 |
|
|
/// \retval value values of the numerical constraints stacked in a unique |
267 |
|
|
/// vector, |
268 |
|
|
/// \retval jacobian Jacobian of the numerical constraints stacked in a |
269 |
|
|
/// unique matrix. |
270 |
|
|
/// |
271 |
|
|
/// Columns of the Jacobian corresponding to locked joints are omitted, |
272 |
|
|
/// columns corresponding to passive dofs are set to 0. |
273 |
|
|
void computeValueAndJacobian(const Configuration_t& configuration, |
274 |
|
|
vector_t& value, matrix_t& jacobian) const; |
275 |
|
|
|
276 |
|
|
/// Set maximal number of iterations in config projector |
277 |
|
|
void maxIterProjection(size_type iterations); |
278 |
|
|
/// Get maximal number of iterations in config projector |
279 |
|
|
size_type maxIterProjection() const { return maxIterProjection_; } |
280 |
|
|
|
281 |
|
|
/// Set maximal number of iterations in config projector |
282 |
|
|
void maxIterPathPlanning(size_type iterations); |
283 |
|
|
/// Get maximal number of iterations in config projector |
284 |
|
|
size_type maxIterPathPlanning() const { return maxIterPathPlanning_; } |
285 |
|
|
|
286 |
|
|
/// set time out for the path planning ( in seconds) |
287 |
|
|
void setTimeOutPathPlanning(double timeOut) { |
288 |
|
|
timeOutPathPlanning_ = timeOut; |
289 |
|
|
} |
290 |
|
|
|
291 |
|
|
/// set time out for the path planning ( in seconds) |
292 |
|
|
double getTimeOutPathPlanning() { return timeOutPathPlanning_; } |
293 |
|
|
|
294 |
|
|
/// Set error threshold in config projector |
295 |
|
|
void errorThreshold(const value_type& threshold); |
296 |
|
|
/// Get errorimal number of threshold in config projector |
297 |
|
|
value_type errorThreshold() const { return errorThreshold_; } |
298 |
|
|
/// \} |
299 |
|
|
|
300 |
|
|
/// Create new problem. |
301 |
|
|
virtual void resetProblem(); |
302 |
|
|
|
303 |
|
|
/// Reset the roadmap. |
304 |
|
|
/// \note When joints bounds are changed, the roadmap must be reset |
305 |
|
|
/// because the kd tree must be resized. |
306 |
|
|
virtual void resetRoadmap(); |
307 |
|
|
|
308 |
|
|
/// \name Solve problem and get paths |
309 |
|
|
/// \{ |
310 |
|
|
|
311 |
|
|
/// Create Path optimizer if needed |
312 |
|
|
/// |
313 |
|
|
/// If a path optimizer is already set, do nothing. |
314 |
|
|
/// Type of optimizer is determined by method selectPathOptimizer. |
315 |
|
|
void createPathOptimizers(); |
316 |
|
|
|
317 |
|
|
/// Prepare the solver for a step by step planning. |
318 |
|
|
/// and try to make direct connections (call PathPlanner::tryDirectPath) |
319 |
|
|
/// \return the return value of PathPlanner::pathExists |
320 |
|
|
virtual bool prepareSolveStepByStep(); |
321 |
|
|
|
322 |
|
|
/// Execute one step of the planner. |
323 |
|
|
/// \return the return value of PathPlanner::pathExists of the selected |
324 |
|
|
/// planner. \note This won't check if a solution has been found before doing |
325 |
|
|
/// one step. The decision to stop planning is let to the user. |
326 |
|
|
virtual bool executeOneStep(); |
327 |
|
|
|
328 |
|
|
/// Finish the solving procedure |
329 |
|
|
/// The path optimizer is not called |
330 |
|
|
virtual void finishSolveStepByStep(); |
331 |
|
|
|
332 |
|
|
/// Set and solve the problem |
333 |
|
|
virtual void solve(); |
334 |
|
|
|
335 |
|
|
/// Make direct connection between two configurations |
336 |
|
|
/// \param start, end: the configurations to link. |
337 |
|
|
/// \param validate whether path should be validated. If true, path |
338 |
|
|
/// validation is called and only valid part of path is inserted |
339 |
|
|
/// in the path vector. |
340 |
|
|
/// \retval pathId Id of the path that is inserted in the path vector, |
341 |
|
|
/// \retval report Reason for non validation if relevant. |
342 |
|
|
/// return false if direct path is not fully valid |
343 |
|
|
/// |
344 |
|
|
/// \note If path is only partly valid, valid part starting at start |
345 |
|
|
/// configuration is inserted in path vector. |
346 |
|
|
bool directPath(ConfigurationIn_t start, ConfigurationIn_t end, bool validate, |
347 |
|
|
std::size_t& pathId, std::string& report); |
348 |
|
|
|
349 |
|
|
/// Add random configuration into roadmap as new node. |
350 |
|
|
void addConfigToRoadmap(ConfigurationIn_t config); |
351 |
|
|
|
352 |
|
|
/// Add an edge between two roadmap nodes. |
353 |
|
|
/// |
354 |
|
|
/// \param config1 configuration of start node, |
355 |
|
|
/// \param config2 configuration of destination node, |
356 |
|
|
/// \param path path to store in the edge. |
357 |
|
|
/// |
358 |
|
|
/// Check that nodes containing config1 and config2 exist in the roadmap. |
359 |
|
|
void addEdgeToRoadmap(ConfigurationIn_t config1, ConfigurationIn_t config2, |
360 |
|
|
const PathPtr_t& path); |
361 |
|
|
|
362 |
|
|
/// Interrupt path planning and path optimization |
363 |
|
|
void interrupt(); |
364 |
|
|
|
365 |
|
|
/// Add a path |
366 |
|
✗ |
std::size_t addPath(const PathVectorPtr_t& path) { |
367 |
|
✗ |
std::size_t s = paths_.size(); |
368 |
|
✗ |
paths_.push_back(path); |
369 |
|
✗ |
return s; |
370 |
|
|
} |
371 |
|
|
|
372 |
|
|
/// Erase a path. |
373 |
|
|
void erasePath(std::size_t pathId) { |
374 |
|
|
PathVectors_t::iterator it = paths_.begin(); |
375 |
|
|
std::advance(it, pathId); |
376 |
|
|
|
377 |
|
|
paths_.erase(it); |
378 |
|
|
} |
379 |
|
|
|
380 |
|
|
/// Return vector of paths |
381 |
|
|
const PathVectors_t& paths() const { return paths_; } |
382 |
|
|
/// \} |
383 |
|
|
|
384 |
|
|
/// \name Obstacles |
385 |
|
|
/// \{ |
386 |
|
|
|
387 |
|
|
/// Add collision objects of a device as obstacles to the list. |
388 |
|
|
/// \param device the Device to be added. |
389 |
|
|
/// \param collision whether collision checking should be performed |
390 |
|
|
/// for this object. |
391 |
|
|
/// \param distance whether distance computation should be performed |
392 |
|
|
/// for this object. |
393 |
|
|
virtual void addObstacle(const DevicePtr_t& device, bool collision, |
394 |
|
|
bool distance); |
395 |
|
|
|
396 |
|
|
/// Add obstacle to the list. |
397 |
|
|
/// \param inObject a new object. |
398 |
|
|
/// \param collision whether collision checking should be performed |
399 |
|
|
/// for this object. |
400 |
|
|
/// \param distance whether distance computation should be performed |
401 |
|
|
/// for this object. |
402 |
|
|
virtual void addObstacle(const CollisionObjectPtr_t& inObject, bool collision, |
403 |
|
|
bool distance); |
404 |
|
|
|
405 |
|
|
/// Remove obstacle from the list. |
406 |
|
|
/// \param name name of the obstacle |
407 |
|
|
virtual void removeObstacle(const std::string& name); |
408 |
|
|
|
409 |
|
|
/// Add obstacle to the list. |
410 |
|
|
/// \param inObject a new object. |
411 |
|
|
/// \param pose the object pose. |
412 |
|
|
/// \param collision whether collision checking should be performed |
413 |
|
|
/// for this object. |
414 |
|
|
/// \param distance whether distance computation should be performed |
415 |
|
|
/// for this object. |
416 |
|
|
virtual void addObstacle(const std::string& name, |
417 |
|
|
const CollisionGeometryPtr_t& inObject, |
418 |
|
|
const Transform3s& pose, bool collision, |
419 |
|
|
bool distance); |
420 |
|
|
|
421 |
|
|
/// Add obstacle to the list. |
422 |
|
|
/// \param inObject a new object. |
423 |
|
|
/// \param collision whether collision checking should be performed |
424 |
|
|
/// for this object. |
425 |
|
|
/// \param distance whether distance computation should be performed |
426 |
|
|
/// for this object. |
427 |
|
|
virtual void addObstacle(const std::string& name, |
428 |
|
|
/*const*/ FclCollisionObject& inObject, |
429 |
|
|
bool collision, bool distance); |
430 |
|
|
|
431 |
|
|
/// Remove collision pair between a joint and an obstacle |
432 |
|
|
/// \param jointName name of the joint, |
433 |
|
|
/// \param obstacleName name of the obstacle |
434 |
|
|
void removeObstacleFromJoint(const std::string& jointName, |
435 |
|
|
const std::string& obstacleName); |
436 |
|
|
|
437 |
|
|
/// Extract from the obstacle the part that can collide with aabb |
438 |
|
|
/// \warning the obstacle is removed if there are not possible collision. |
439 |
|
|
void cutObstacle(const std::string& name, const coal::AABB& aabb); |
440 |
|
|
|
441 |
|
|
/// Build matrix of relative motions between joints |
442 |
|
|
/// |
443 |
|
|
/// Call Problem::filterCollisionPairs. |
444 |
|
|
void filterCollisionPairs(); |
445 |
|
|
|
446 |
|
|
/// Get obstacle by name |
447 |
|
|
/// Throws if obstacle does not exists. |
448 |
|
|
CollisionObjectPtr_t obstacle(const std::string& name) const; |
449 |
|
|
|
450 |
|
|
/// Get obstacle frame position by name |
451 |
|
|
/// Throws if obstacle frame does not exists. |
452 |
|
|
const Transform3s& obstacleFramePosition(const std::string& name) const; |
453 |
|
|
|
454 |
|
|
/// Get list of obstacle names |
455 |
|
|
/// |
456 |
|
|
/// \param collision whether to return collision obstacle names |
457 |
|
|
/// \param distance whether to return distance obstacle names |
458 |
|
|
/// \return list of obstacle names |
459 |
|
|
std::list<std::string> obstacleNames(bool collision, bool distance) const; |
460 |
|
|
|
461 |
|
|
/// Return list of pair of distance computations |
462 |
|
|
const DistanceBetweenObjectsPtr_t& distanceBetweenObjects() const { |
463 |
|
|
return distanceBetweenObjects_; |
464 |
|
|
} |
465 |
|
|
|
466 |
|
|
pinocchio::GeomModelPtr_t obstacleGeomModel() const { return obstacleModel_; } |
467 |
|
|
pinocchio::GeomDataPtr_t obstacleGeomData() const { return obstacleData_; } |
468 |
|
|
/// \} |
469 |
|
|
|
470 |
|
|
/// Local vector of objects considered for collision detection |
471 |
|
|
const ObjectStdVector_t& collisionObstacles() const; |
472 |
|
|
/// Local vector of objects considered for distance computation |
473 |
|
|
const ObjectStdVector_t& distanceObstacles() const; |
474 |
|
|
|
475 |
|
|
/// Set the roadmap |
476 |
|
|
void roadmap(const RoadmapPtr_t& roadmap) { roadmap_ = roadmap; } |
477 |
|
|
|
478 |
|
|
/// Initialize distance |
479 |
|
|
/// |
480 |
|
|
/// Set distance by calling the distance factory |
481 |
|
|
void initDistance(); |
482 |
|
|
|
483 |
|
|
/// Initialize steering method |
484 |
|
|
/// |
485 |
|
|
/// Set steering method by calling the steering method factory |
486 |
|
|
void initSteeringMethod(); |
487 |
|
|
|
488 |
|
|
/// Initialize path projector |
489 |
|
|
/// |
490 |
|
|
/// Set path projector by calling path projector factory |
491 |
|
|
void initPathProjector(); |
492 |
|
|
|
493 |
|
|
/// Set path validation by calling path validation factory |
494 |
|
|
void initPathValidation(); |
495 |
|
|
|
496 |
|
|
/// Set config validation by calling config validation factories |
497 |
|
|
void initConfigValidation(); |
498 |
|
|
|
499 |
|
|
/// Initialize the config and path validations and add the obstacles. |
500 |
|
|
void initValidations(); |
501 |
|
|
|
502 |
|
|
/// Initialize the problem target by calling the path validation factory |
503 |
|
|
virtual void initProblemTarget(); |
504 |
|
|
|
505 |
|
|
/// Container of static method that creates a Robot |
506 |
|
|
/// with string as input |
507 |
|
|
Container<RobotBuilder_t> robots; |
508 |
|
|
/// Container of static method that creates a ConfigurationShooter |
509 |
|
|
/// with a robot as input |
510 |
|
|
Container<ConfigurationShooterBuilder_t> configurationShooters; |
511 |
|
|
/// Container of static method that creates a SteeringMethod |
512 |
|
|
/// with a problem as input |
513 |
|
|
Container<SteeringMethodBuilder_t> steeringMethods; |
514 |
|
|
/// Container of static method that creates a Distance |
515 |
|
|
/// with problem as input |
516 |
|
|
Container<DistanceBuilder_t> distances; |
517 |
|
|
/// Container of static method that creates a PathValidation |
518 |
|
|
/// with a robot and a tolerance as input. |
519 |
|
|
Container<PathValidationBuilder_t> pathValidations; |
520 |
|
|
/// Container of static method that creates a ConfigValidation |
521 |
|
|
/// with a robot as input. |
522 |
|
|
Container<ConfigValidationBuilder_t> configValidations; |
523 |
|
|
/// Container of static method that creates a PathProjection |
524 |
|
|
/// with a problem and a tolerance as input. |
525 |
|
|
Container<PathProjectorBuilder_t> pathProjectors; |
526 |
|
|
/// Container of static method that creates a PathPlanner |
527 |
|
|
/// with a problem and a roadmap as input |
528 |
|
|
Container<PathPlannerBuilder_t> pathPlanners; |
529 |
|
|
/// Container of static method that creates a PathOptimizer |
530 |
|
|
/// with a problem as input |
531 |
|
|
Container<PathOptimizerBuilder_t> pathOptimizers; |
532 |
|
|
|
533 |
|
|
/// Container of constraints::Implicit |
534 |
|
|
Container<constraints::ImplicitPtr_t> numericalConstraints; |
535 |
|
|
/// member lockedJoints has been removed. LockedJointPtr_t |
536 |
|
|
/// instances are now stored with constraints::ImplicitPtr_t in |
537 |
|
|
/// member numericalConstraints. |
538 |
|
|
Member_lockedJoints_in_class_ProblemSolver_has_been_removed_use_member_numericalConstraints_instead |
539 |
|
|
lockedJoints; |
540 |
|
|
/// Container of CenterOfMassComputation |
541 |
|
|
Container<CenterOfMassComputationPtr_t> centerOfMassComputations; |
542 |
|
|
/// Container of passive DoFs (as segments_t) |
543 |
|
|
Container<segments_t> passiveDofs; |
544 |
|
|
/// Container of JointAndShapes_t |
545 |
|
|
Container<JointAndShapes_t> jointAndShapes; |
546 |
|
|
/// Container of AffordanceObjects_t |
547 |
|
|
Container<AffordanceObjects_t> affordanceObjects; |
548 |
|
|
/// Container of AffordanceConfig_t |
549 |
|
|
Container<AffordanceConfig_t> affordanceConfigs; |
550 |
|
|
|
551 |
|
|
protected: |
552 |
|
|
/// Constructor |
553 |
|
|
/// |
554 |
|
|
/// Call create to create an instance. |
555 |
|
|
ProblemSolver(); |
556 |
|
|
|
557 |
|
|
/// Store constraints until call to solve. |
558 |
|
|
ConstraintSetPtr_t constraints_; |
559 |
|
|
|
560 |
|
|
/// Set pointer to problem |
561 |
|
|
void problem(ProblemPtr_t problem); |
562 |
|
|
|
563 |
|
|
/// Initialize the new problem |
564 |
|
|
/// \param problem is inserted in the ProblemSolver and initialized. |
565 |
|
|
/// \note The previous Problem, if any, is not deleted. The function |
566 |
|
|
/// should be called when creating Problem object, in resetProblem() |
567 |
|
|
/// and all reimplementation in inherited class. |
568 |
|
|
virtual void initializeProblem(ProblemPtr_t problem); |
569 |
|
|
|
570 |
|
|
/// Robot |
571 |
|
|
DevicePtr_t robot_; |
572 |
|
|
/// Problem |
573 |
|
|
ProblemPtr_t problem_; |
574 |
|
|
|
575 |
|
|
PathPlannerPtr_t pathPlanner_; |
576 |
|
|
/// Store roadmap |
577 |
|
|
RoadmapPtr_t roadmap_; |
578 |
|
|
/// Paths |
579 |
|
|
PathVectors_t paths_; |
580 |
|
|
/// Path projector method |
581 |
|
|
std::string pathProjectorType_; |
582 |
|
|
/// Tolerance of path projector |
583 |
|
|
value_type pathProjectorTolerance_; |
584 |
|
|
|
585 |
|
|
/// Path planner |
586 |
|
|
std::string pathPlannerType_; |
587 |
|
|
|
588 |
|
|
/// Shared pointer to the problem target |
589 |
|
|
ProblemTargetPtr_t target_; |
590 |
|
|
|
591 |
|
|
private: |
592 |
|
|
/// Shared pointer to initial configuration. |
593 |
|
|
Configuration_t initConf_; |
594 |
|
|
/// Shared pointer to goal configuration. |
595 |
|
|
Configurations_t goalConfigurations_; |
596 |
|
|
/// Robot type |
597 |
|
|
std::string robotType_; |
598 |
|
|
/// Configuration shooter |
599 |
|
|
std::string configurationShooterType_; |
600 |
|
|
/// Steering method |
601 |
|
|
std::string distanceType_; |
602 |
|
|
/// Steering method |
603 |
|
|
std::string steeringMethodType_; |
604 |
|
|
/// Path optimizer |
605 |
|
|
PathOptimizerTypes_t pathOptimizerTypes_; |
606 |
|
|
PathOptimizers_t pathOptimizers_; |
607 |
|
|
/// Path validation method |
608 |
|
|
std::string pathValidationType_; |
609 |
|
|
/// Tolerance of path validation |
610 |
|
|
value_type pathValidationTolerance_; |
611 |
|
|
// Config validation methods |
612 |
|
|
ConfigValidationTypes_t configValidationTypes_; |
613 |
|
|
/// Store obstacles until call to solve. |
614 |
|
|
ObjectStdVector_t collisionObstacles_; // FIXME should be removed? |
615 |
|
|
ObjectStdVector_t distanceObstacles_; // FIXME should be removed? |
616 |
|
|
pinocchio::ModelPtr_t obstacleRModel_; // Contains the frames |
617 |
|
|
pinocchio::DataPtr_t obstacleRData_; // Contains the frames |
618 |
|
|
pinocchio::GeomModelPtr_t obstacleModel_; |
619 |
|
|
pinocchio::GeomDataPtr_t obstacleData_; |
620 |
|
|
// Tolerance for numerical constraint resolution |
621 |
|
|
value_type errorThreshold_; |
622 |
|
|
// Maximal number of iterations for numerical constraint resolution |
623 |
|
|
size_type maxIterProjection_; |
624 |
|
|
/// Maximal number of iterations for path planner |
625 |
|
|
unsigned long int maxIterPathPlanning_; |
626 |
|
|
/// Maximal time allocated to the path-planner |
627 |
|
|
double timeOutPathPlanning_; |
628 |
|
|
/// Map of passive dofs |
629 |
|
|
segmentsMap_t passiveDofsMap_; |
630 |
|
|
/// Map of CenterOfMassComputation |
631 |
|
|
CenterOfMassComputationMap_t comcMap_; |
632 |
|
|
/// Computation of distances to obstacles |
633 |
|
|
DistanceBetweenObjectsPtr_t distanceBetweenObjects_; |
634 |
|
|
void initProblem(); |
635 |
|
|
}; // class ProblemSolver |
636 |
|
|
} // namespace core |
637 |
|
|
} // namespace hpp |
638 |
|
|
|
639 |
|
|
#endif // HPP_CORE_PROBLEM_SOLVER_HH |
640 |
|
|
|