GCC Code Coverage Report


Directory: ./
File: src/problem-solver.cc
Date: 2025-03-07 11:10:46
Exec Total Coverage
Lines: 0 184 0.0%
Branches: 0 444 0.0%

Line Branch Exec Source
1 // Copyright (c) 2014 CNRS
2 // Author: Florent Lamiraux
3 //
4
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are
7 // met:
8 //
9 // 1. Redistributions of source code must retain the above copyright
10 // notice, this list of conditions and the following disclaimer.
11 //
12 // 2. Redistributions in binary form must reproduce the above copyright
13 // notice, this list of conditions and the following disclaimer in the
14 // documentation and/or other materials provided with the distribution.
15 //
16 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
17 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
18 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
19 // A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
20 // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
21 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
22 // LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23 // DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
24 // THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
26 // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
27 // DAMAGE.
28
29 #include "hpp/manipulation/problem-solver.hh"
30
31 #include <hpp/constraints/convex-shape-contact.hh>
32 #include <hpp/constraints/explicit/convex-shape-contact.hh>
33 #include <hpp/core/continuous-validation/dichotomy.hh>
34 #include <hpp/core/continuous-validation/progressive.hh>
35 #include <hpp/core/path-optimization/partial-shortcut.hh>
36 #include <hpp/core/path-optimization/random-shortcut.hh>
37 #include <hpp/core/path-projector/dichotomy.hh>
38 #include <hpp/core/path-projector/global.hh>
39 #include <hpp/core/path-projector/progressive.hh>
40 #include <hpp/core/path-projector/recursive-hermite.hh>
41 #include <hpp/core/path-validation/discretized-collision-checking.hh>
42 #include <hpp/core/path-validation/discretized-joint-bound.hh>
43 #include <hpp/core/roadmap.hh>
44 #include <hpp/core/steering-method/dubins.hh>
45 #include <hpp/core/steering-method/hermite.hh>
46 #include <hpp/core/steering-method/reeds-shepp.hh>
47 #include <hpp/core/steering-method/snibud.hh>
48 #include <hpp/core/steering-method/straight.hh>
49 #include <hpp/pinocchio/gripper.hh>
50 #include <hpp/util/debug.hh>
51 #include <hpp/util/pointer.hh>
52
53 #include "hpp/manipulation/constraint-set.hh"
54 #include "hpp/manipulation/device.hh"
55 #include "hpp/manipulation/graph-node-optimizer.hh"
56 #include "hpp/manipulation/graph-optimizer.hh"
57 #include "hpp/manipulation/graph-path-validation.hh"
58 #include "hpp/manipulation/graph/graph.hh"
59 #include "hpp/manipulation/handle.hh"
60 #include "hpp/manipulation/manipulation-planner.hh"
61 #include "hpp/manipulation/package-config.hh" // HPP_MANIPULATION_HAS_WHOLEBODY_STEP
62 #include "hpp/manipulation/path-optimization/enforce-transition-semantic.hh"
63 #include "hpp/manipulation/path-optimization/random-shortcut.hh"
64 #include "hpp/manipulation/path-planner/end-effector-trajectory.hh"
65 #include "hpp/manipulation/path-planner/states-path-finder.hh"
66 #include "hpp/manipulation/path-planner/transition-planner.hh"
67 #include "hpp/manipulation/problem-target/state.hh"
68 #include "hpp/manipulation/problem.hh"
69 #include "hpp/manipulation/roadmap.hh"
70 #include "hpp/manipulation/steering-method/cross-state-optimization.hh"
71 #include "hpp/manipulation/steering-method/end-effector-trajectory.hh"
72 #include "hpp/manipulation/steering-method/graph.hh"
73
74 namespace hpp {
75 namespace manipulation {
76 typedef constraints::Implicit Implicit;
77 typedef constraints::ImplicitPtr_t ImplicitPtr_t;
78 namespace {
79 struct PartialShortcutTraits : core::pathOptimization::PartialShortcutTraits {
80 static bool removeLockedJoints() { return false; }
81 };
82
83 #define MAKE_GRAPH_PATH_VALIDATION_BUILDER(name, function) \
84 PathValidationPtr_t create##name##GraphPathValidation( \
85 const core::DevicePtr_t& robot, const value_type& stepSize) { \
86 return GraphPathValidation::create(function(robot, stepSize)); \
87 }
88 MAKE_GRAPH_PATH_VALIDATION_BUILDER(
89 DiscretizedCollision,
90 core::pathValidation::createDiscretizedCollisionChecking)
91 MAKE_GRAPH_PATH_VALIDATION_BUILDER(
92 DiscretizedJointBound, core::pathValidation::createDiscretizedJointBound)
93 // MAKE_GRAPH_PATH_VALIDATION_BUILDER(DiscretizedCollisionAndJointBound,
94 // createDiscretizedJointBoundAndCollisionChecking)
95
96 template <typename ParentSM_t, typename ChildSM_t>
97 core::SteeringMethodPtr_t createSMWithGuess(
98 const core::ProblemConstPtr_t& problem) {
99 shared_ptr<ParentSM_t> sm = ParentSM_t::create(problem);
100 sm->innerSteeringMethod(ChildSM_t::createWithGuess(problem));
101 return sm;
102 }
103
104 template <typename PathProjectorType>
105 core::PathProjectorPtr_t createPathProjector(
106 const core::ProblemConstPtr_t& problem, const value_type& step) {
107 steeringMethod::GraphPtr_t gsm =
108 HPP_DYNAMIC_PTR_CAST(steeringMethod::Graph, problem->steeringMethod());
109 if (!gsm)
110 return PathProjectorType::create(problem->distance(),
111 problem->steeringMethod(), step);
112 return PathProjectorType::create(problem->distance(),
113 gsm->innerSteeringMethod(), step);
114 }
115 } // namespace
116
117 std::ostream& operator<<(std::ostream& os, const Device& robot) {
118 return robot.print(os);
119 }
120
121 ProblemSolver::ProblemSolver() : core::ProblemSolver(), robot_(), problem_() {
122 robots.add("hpp::manipulation::Device", manipulation::Device::create);
123 robotType("hpp::manipulation::Device");
124
125 pathPlanners.add("M-RRT", ManipulationPlanner::create);
126 pathPlanners.add("EndEffectorTrajectory",
127 pathPlanner::EndEffectorTrajectory::createWithRoadmap);
128 pathPlanners.add("StatesPathFinder",
129 pathPlanner::StatesPathFinder::createWithRoadmap);
130 pathPlanners.add("TransitionPlanner",
131 pathPlanner::TransitionPlanner::createWithRoadmap);
132 pathValidations.add("Graph-Discretized",
133 createDiscretizedCollisionGraphPathValidation);
134 pathValidations.add("Graph-DiscretizedCollision",
135 createDiscretizedCollisionGraphPathValidation);
136 pathValidations.add("Graph-DiscretizedJointBound",
137 createDiscretizedJointBoundGraphPathValidation);
138 // pathValidations.add ("Graph-DiscretizedCollisionAndJointBound",
139 // createDiscretizedCollisionAndJointBoundGraphPathValidation);
140 pathValidations.add(
141 "Graph-Dichotomy",
142 GraphPathValidation::create<core::continuousValidation::Dichotomy>);
143 pathValidations.add(
144 "Graph-Progressive",
145 GraphPathValidation::create<core::continuousValidation::Progressive>);
146
147 // TODO Uncomment to make Graph-Discretized the default.
148 // pathValidationType ("Graph-Discretized", 0.05);
149
150 pathOptimizers.add("RandomShortcut",
151 pathOptimization::RandomShortcut::create);
152 pathOptimizers.add(
153 "Graph-RandomShortcut",
154 GraphOptimizer::create<core::pathOptimization::RandomShortcut>);
155 pathOptimizers.add("PartialShortcut",
156 core::pathOptimization::PartialShortcut::createWithTraits<
157 PartialShortcutTraits>);
158 pathOptimizers.add(
159 "Graph-PartialShortcut",
160 GraphOptimizer::create<core::pathOptimization::PartialShortcut>);
161 pathOptimizers.add("EnforceTransitionSemantic",
162 pathOptimization::EnforceTransitionSemantic::create);
163
164 pathProjectors.add("Progressive",
165 createPathProjector<core::pathProjector::Progressive>);
166 pathProjectors.add("Dichotomy",
167 createPathProjector<core::pathProjector::Dichotomy>);
168 pathProjectors.add("Global",
169 createPathProjector<core::pathProjector::Global>);
170 pathProjectors.add(
171 "RecursiveHermite",
172 createPathProjector<core::pathProjector::RecursiveHermite>);
173
174 steeringMethods.add(
175 "Graph-Straight",
176 steeringMethod::Graph::create<core::steeringMethod::Straight>);
177 steeringMethods.add(
178 "Graph-Hermite",
179 steeringMethod::Graph::create<core::steeringMethod::Hermite>);
180 steeringMethods.add("Graph-ReedsShepp",
181 createSMWithGuess<steeringMethod::Graph,
182 core::steeringMethod::ReedsShepp>);
183 steeringMethods.add(
184 "Graph-Dubins",
185 createSMWithGuess<steeringMethod::Graph, core::steeringMethod::Dubins>);
186 steeringMethods.add(
187 "Graph-Snibud",
188 createSMWithGuess<steeringMethod::Graph, core::steeringMethod::Snibud>);
189 steeringMethods.add("CrossStateOptimization-Straight",
190 steeringMethod::CrossStateOptimization::create<
191 core::steeringMethod::Straight>);
192 steeringMethods.add("CrossStateOptimization-ReedsShepp",
193 createSMWithGuess<steeringMethod::CrossStateOptimization,
194 core::steeringMethod::ReedsShepp>);
195 steeringMethods.add("CrossStateOptimization-Dubins",
196 createSMWithGuess<steeringMethod::CrossStateOptimization,
197 core::steeringMethod::Dubins>);
198 steeringMethods.add("CrossStateOptimization-Snibud",
199 createSMWithGuess<steeringMethod::CrossStateOptimization,
200 core::steeringMethod::Snibud>);
201 steeringMethods.add("EndEffectorTrajectory",
202 steeringMethod::EndEffectorTrajectory::create);
203
204 pathPlannerType("M-RRT");
205 steeringMethodType("Graph-Straight");
206 }
207
208 ProblemSolverPtr_t ProblemSolver::create() {
209 return ProblemSolverPtr_t(new ProblemSolver());
210 }
211
212 void ProblemSolver::resetProblem() {
213 ProblemPtr_t p(Problem::create(robot_));
214 if (problem_) {
215 p->parameters = problem_->parameters;
216 }
217 initializeProblem(p);
218 }
219
220 void ProblemSolver::initializeProblem(ProblemPtr_t problem) {
221 problem_ = problem;
222 core::ProblemSolver::initializeProblem(problem_);
223 if (constraintGraph_) problem_->constraintGraph(constraintGraph_);
224 value_type tolerance;
225 const std::string& type = parent_t::pathValidationType(tolerance);
226 problem_->setPathValidationFactory(pathValidations.get(type), tolerance);
227 }
228
229 void ProblemSolver::constraintGraph(const std::string& graphName) {
230 if (!graphs.has(graphName))
231 throw std::invalid_argument("ProblemSolver has no graph named " +
232 graphName);
233 constraintGraph_ = graphs.get(graphName);
234 RoadmapPtr_t r = HPP_DYNAMIC_PTR_CAST(Roadmap, roadmap());
235 if (r) r->constraintGraph(constraintGraph_);
236 if (problem_) problem_->constraintGraph(constraintGraph_);
237 }
238
239 graph::GraphPtr_t ProblemSolver::constraintGraph() const {
240 return constraintGraph_;
241 }
242
243 void ProblemSolver::initConstraintGraph() {
244 if (!constraintGraph_) throw std::runtime_error("The graph is not defined.");
245 initSteeringMethod();
246 constraintGraph_->clearConstraintsAndComplement();
247 for (std::size_t i = 0; i < constraintsAndComplements.size(); ++i) {
248 const ConstraintAndComplement_t& c = constraintsAndComplements[i];
249 constraintGraph()->registerConstraints(c.constraint, c.complement, c.both);
250 }
251 constraintGraph_->initialize();
252 }
253
254 void ProblemSolver::createPlacementConstraint(const std::string& name,
255 const Strings_t& surface1,
256 const Strings_t& surface2,
257 const value_type& margin) {
258 bool explicit_(true);
259 if (!robot_) throw std::runtime_error("No robot loaded");
260 JointAndShapes_t floorSurfaces, objectSurfaces, l;
261 for (Strings_t::const_iterator it1 = surface1.begin(); it1 != surface1.end();
262 ++it1) {
263 if (!robot_->jointAndShapes.has(*it1))
264 throw std::runtime_error("First list of triangles not found.");
265 l = robot_->jointAndShapes.get(*it1);
266 objectSurfaces.insert(objectSurfaces.end(), l.begin(), l.end());
267 for (auto js : l) {
268 JointPtr_t j(js.first);
269 // If one robot contact surface is not on a freeflying object,
270 // The contact constraint cannot be expressed by an explicit
271 // constraint.
272 if ((j->parentJoint()) ||
273 ((*j->configurationSpace() != *pinocchio::LiegroupSpace::SE3()) &&
274 (*j->configurationSpace() != *pinocchio::LiegroupSpace::R3xSO3()))) {
275 explicit_ = false;
276 }
277 }
278 }
279
280 for (Strings_t::const_iterator it2 = surface2.begin(); it2 != surface2.end();
281 ++it2) {
282 // Search first robot triangles
283 if (robot_->jointAndShapes.has(*it2)) l = robot_->jointAndShapes.get(*it2);
284 // and then environment triangles.
285 else if (jointAndShapes.has(*it2))
286 l = jointAndShapes.get(*it2);
287 else
288 throw std::runtime_error("Second list of triangles not found.");
289 floorSurfaces.insert(floorSurfaces.end(), l.begin(), l.end());
290 }
291
292 if (explicit_) {
293 typedef hpp::constraints::explicit_::ConvexShapeContact Constraint_t;
294 Constraint_t::Constraints_t constraints(
295 Constraint_t::createConstraintAndComplement(name, robot_, floorSurfaces,
296 objectSurfaces, margin));
297
298 addNumericalConstraint(std::get<0>(constraints)->function().name(),
299 std::get<0>(constraints));
300 addNumericalConstraint(std::get<1>(constraints)->function().name(),
301 std::get<1>(constraints));
302 addNumericalConstraint(std::get<2>(constraints)->function().name(),
303 std::get<2>(constraints));
304 // Set security margin to contact constraint
305 assert(HPP_DYNAMIC_PTR_CAST(constraints::ConvexShapeContact,
306 std::get<0>(constraints)->functionPtr()));
307 constraints::ConvexShapeContactPtr_t contactFunction(
308 HPP_STATIC_PTR_CAST(constraints::ConvexShapeContact,
309 std::get<0>(constraints)->functionPtr()));
310 contactFunction->setNormalMargin(margin);
311 constraintsAndComplements.push_back(ConstraintAndComplement_t(
312 std::get<0>(constraints), std::get<1>(constraints),
313 std::get<2>(constraints)));
314 } else {
315 using constraints::ComparisonTypes_t;
316 using constraints::Equality;
317 using constraints::EqualToZero;
318 using constraints::Implicit;
319 std::pair<hpp::constraints::ConvexShapeContactPtr_t,
320 hpp::constraints::ConvexShapeContactComplementPtr_t>
321 functions(constraints::ConvexShapeContactComplement::createPair(
322 name, robot_, floorSurfaces, objectSurfaces));
323 functions.first->setNormalMargin(margin);
324 addNumericalConstraint(functions.first->name(),
325 Implicit::create(functions.first, 5 * EqualToZero));
326 addNumericalConstraint(
327 functions.second->name(),
328 Implicit::create(
329 functions.second,
330 ComparisonTypes_t(functions.second->outputSize(), Equality)));
331 }
332 }
333
334 void ProblemSolver::createPrePlacementConstraint(const std::string& name,
335 const Strings_t& surface1,
336 const Strings_t& surface2,
337 const value_type& width,
338 const value_type& margin) {
339 if (!robot_) throw std::runtime_error("No robot loaded");
340 JointAndShapes_t floorSurfaces, objectSurfaces, l;
341 for (Strings_t::const_iterator it1 = surface1.begin(); it1 != surface1.end();
342 ++it1) {
343 if (!robot_->jointAndShapes.has(*it1))
344 throw std::runtime_error("First list of triangles not found.");
345 l = robot_->jointAndShapes.get(*it1);
346 objectSurfaces.insert(objectSurfaces.end(), l.begin(), l.end());
347 }
348
349 for (Strings_t::const_iterator it2 = surface2.begin(); it2 != surface2.end();
350 ++it2) {
351 // Search first robot triangles
352 if (robot_->jointAndShapes.has(*it2)) l = robot_->jointAndShapes.get(*it2);
353 // and then environment triangles.
354 else if (jointAndShapes.has(*it2))
355 l = jointAndShapes.get(*it2);
356 else
357 throw std::runtime_error("Second list of triangles not found.");
358 floorSurfaces.insert(floorSurfaces.end(), l.begin(), l.end());
359 }
360
361 hpp::constraints::ConvexShapeContactPtr_t cvxShape(
362 hpp::constraints::ConvexShapeContact::create(name, robot_, floorSurfaces,
363 objectSurfaces));
364 cvxShape->setNormalMargin(margin + width);
365 addNumericalConstraint(
366 name, Implicit::create(cvxShape, 5 * constraints::EqualToZero));
367 }
368
369 void ProblemSolver::createGraspConstraint(const std::string& name,
370 const std::string& gripper,
371 const std::string& handle) {
372 GripperPtr_t g = robot_->grippers.get(gripper, GripperPtr_t());
373 if (!g) throw std::runtime_error("No gripper with name " + gripper + ".");
374 HandlePtr_t h = robot_->handles.get(handle, HandlePtr_t());
375 if (!h) throw std::runtime_error("No handle with name " + handle + ".");
376 const std::string cname = name + "/complement";
377 const std::string bname = name + "/hold";
378 ImplicitPtr_t constraint(h->createGrasp(g, name));
379 ImplicitPtr_t complement(h->createGraspComplement(g, cname));
380 ImplicitPtr_t both(h->createGraspAndComplement(g, bname));
381 addNumericalConstraint(name, constraint);
382 addNumericalConstraint(cname, complement);
383 addNumericalConstraint(bname, both);
384
385 constraintsAndComplements.push_back(
386 ConstraintAndComplement_t(constraint, complement, both));
387 }
388
389 void ProblemSolver::createPreGraspConstraint(const std::string& name,
390 const std::string& gripper,
391 const std::string& handle) {
392 GripperPtr_t g = robot_->grippers.get(gripper, GripperPtr_t());
393 if (!g) throw std::runtime_error("No gripper with name " + gripper + ".");
394 HandlePtr_t h = robot_->handles.get(handle, HandlePtr_t());
395 if (!h) throw std::runtime_error("No handle with name " + handle + ".");
396
397 value_type c = h->clearance() + g->clearance();
398 ImplicitPtr_t constraint = h->createPreGrasp(g, c, name);
399 addNumericalConstraint(name, constraint);
400 }
401
402 void ProblemSolver::pathValidationType(const std::string& type,
403 const value_type& tolerance) {
404 parent_t::pathValidationType(type, tolerance);
405 if (problem_)
406 problem_->setPathValidationFactory(pathValidations.get(type), tolerance);
407 }
408
409 void ProblemSolver::resetRoadmap() {
410 if (!problem()) throw std::runtime_error("The problem is not defined.");
411 if (roadmap()) roadmap()->clear();
412 RoadmapPtr_t r(Roadmap::create(problem()->distance(), problem()->robot()));
413 if (constraintGraph_) r->constraintGraph(constraintGraph_);
414 roadmap(r);
415 }
416
417 void ProblemSolver::setTargetState(const graph::StatePtr_t state) {
418 problemTarget::StatePtr_t t = problemTarget::State::create(ProblemPtr_t());
419 t->target(state);
420 target_ = t;
421 }
422 } // namespace manipulation
423 } // namespace hpp
424