Directory: | ./ |
---|---|
File: | src/path-planner/states-path-finder.cc |
Date: | 2025-03-07 11:10:46 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 18 | 983 | 1.8% |
Branches: | 40 | 1954 | 2.0% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | // Copyright (c) 2021, Joseph Mirabel | ||
2 | // Authors: Joseph Mirabel (joseph.mirabel@laas.fr), | ||
3 | // Florent Lamiraux (florent.lamiraux@laas.fr) | ||
4 | // Alexandre Thiault (athiault@laas.fr) | ||
5 | // Le Quang Anh (quang-anh.le@laas.fr) | ||
6 | // | ||
7 | // This file is part of hpp-manipulation. | ||
8 | // hpp-manipulation is free software: you can redistribute it | ||
9 | // and/or modify it under the terms of the GNU Lesser General Public | ||
10 | // License as published by the Free Software Foundation, either version | ||
11 | // 3 of the License, or (at your option) any later version. | ||
12 | // | ||
13 | // hpp-manipulation is distributed in the hope that it will be | ||
14 | // useful, but WITHOUT ANY WARRANTY; without even the implied warranty | ||
15 | // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU | ||
16 | // General Lesser Public License for more details. You should have | ||
17 | // received a copy of the GNU Lesser General Public License along with | ||
18 | // hpp-manipulation. If not, see <http://www.gnu.org/licenses/>. | ||
19 | |||
20 | #include <algorithm> | ||
21 | #include <hpp/constraints/affine-function.hh> | ||
22 | #include <hpp/constraints/explicit.hh> | ||
23 | #include <hpp/constraints/locked-joint.hh> | ||
24 | #include <hpp/constraints/solver/by-substitution.hh> | ||
25 | #include <hpp/core/collision-validation-report.hh> | ||
26 | #include <hpp/core/collision-validation.hh> | ||
27 | #include <hpp/core/configuration-shooter.hh> | ||
28 | #include <hpp/core/diffusing-planner.hh> | ||
29 | #include <hpp/core/path-optimization/random-shortcut.hh> | ||
30 | #include <hpp/core/path-planning-failed.hh> | ||
31 | #include <hpp/core/path-projector/progressive.hh> | ||
32 | #include <hpp/core/path-validation.hh> | ||
33 | #include <hpp/core/path-vector.hh> | ||
34 | #include <hpp/core/problem-target/goal-configurations.hh> | ||
35 | #include <hpp/core/problem-target/task-target.hh> | ||
36 | #include <hpp/manipulation/constraint-set.hh> | ||
37 | #include <hpp/manipulation/graph/edge.hh> | ||
38 | #include <hpp/manipulation/graph/state-selector.hh> | ||
39 | #include <hpp/manipulation/graph/state.hh> | ||
40 | #include <hpp/manipulation/path-planner/states-path-finder.hh> | ||
41 | #include <hpp/manipulation/roadmap.hh> | ||
42 | #include <hpp/pinocchio/configuration.hh> | ||
43 | #include <hpp/pinocchio/joint-collection.hh> | ||
44 | #include <hpp/util/debug.hh> | ||
45 | #include <hpp/util/exception-factory.hh> | ||
46 | #include <hpp/util/timer.hh> | ||
47 | #include <iomanip> | ||
48 | #include <map> | ||
49 | #include <pinocchio/fwd.hpp> | ||
50 | #include <pinocchio/multibody/model.hpp> | ||
51 | #include <typeinfo> | ||
52 | #include <vector> | ||
53 | |||
54 | namespace hpp { | ||
55 | namespace manipulation { | ||
56 | namespace pathPlanner { | ||
57 | |||
58 | using Eigen::ColBlockIndices; | ||
59 | using Eigen::RowBlockIndices; | ||
60 | |||
61 | using graph::EdgePtr_t; | ||
62 | using graph::Edges_t; | ||
63 | using graph::LockedJoints_t; | ||
64 | using graph::Neighbors_t; | ||
65 | using graph::NumericalConstraints_t; | ||
66 | using graph::segments_t; | ||
67 | using graph::StatePtr_t; | ||
68 | using graph::States_t; | ||
69 | |||
70 | using core::ProblemTargetPtr_t; | ||
71 | using core::problemTarget::GoalConfigurations; | ||
72 | using core::problemTarget::GoalConfigurationsPtr_t; | ||
73 | using core::problemTarget::TaskTarget; | ||
74 | using core::problemTarget::TaskTargetPtr_t; | ||
75 | |||
76 | #ifdef HPP_DEBUG | ||
77 | static void displayRoadmap(const core::RoadmapPtr_t& roadmap) { | ||
78 | unsigned i = 0; | ||
79 | for (auto cc : roadmap->connectedComponents()) { | ||
80 | hppDout(info, " CC " << i++); | ||
81 | for (auto n : cc->nodes()) { | ||
82 | hppDout(info, pinocchio::displayConfig(n->configuration())); | ||
83 | } | ||
84 | } | ||
85 | } | ||
86 | #endif | ||
87 | |||
88 | ✗ | StatesPathFinder::StatesPathFinder(const core::ProblemConstPtr_t& problem, | |
89 | ✗ | const core::RoadmapPtr_t& roadmap) | |
90 | : PathPlanner(problem, roadmap), | ||
91 | ✗ | problem_(HPP_STATIC_PTR_CAST(const manipulation::Problem, problem)), | |
92 | ✗ | constraints_(), | |
93 | ✗ | index_(), | |
94 | ✗ | sameRightHandSide_(), | |
95 | ✗ | stricterConstraints_(), | |
96 | ✗ | optData_(0x0), | |
97 | ✗ | graphData_(0x0), | |
98 | ✗ | lastBuiltTransitions_(), | |
99 | ✗ | goalConstraints_(), | |
100 | ✗ | goalDefinedByConstraints_(false), | |
101 | ✗ | q1_(), | |
102 | ✗ | q2_(), | |
103 | ✗ | configList_(), | |
104 | ✗ | idxConfigList_(0), | |
105 | ✗ | nTryConfigList_(0), | |
106 | ✗ | solved_(false), | |
107 | ✗ | interrupt_(false), | |
108 | ✗ | weak_() { | |
109 | ✗ | gatherGraphConstraints(); | |
110 | ✗ | inStateProblem_ = core::Problem::create(problem_->robot()); | |
111 | } | ||
112 | |||
113 | ✗ | StatesPathFinder::StatesPathFinder(const StatesPathFinder& other) | |
114 | ✗ | : PathPlanner(other.problem_), | |
115 | ✗ | problem_(other.problem_), | |
116 | ✗ | constraints_(), | |
117 | ✗ | index_(other.index_), | |
118 | ✗ | sameRightHandSide_(other.sameRightHandSide_), | |
119 | ✗ | weak_() {} | |
120 | |||
121 | ✗ | StatesPathFinderPtr_t StatesPathFinder::create( | |
122 | const core::ProblemConstPtr_t& problem) { | ||
123 | StatesPathFinder* ptr; | ||
124 | ✗ | RoadmapPtr_t r = Roadmap::create(problem->distance(), problem->robot()); | |
125 | try { | ||
126 | ✗ | ProblemConstPtr_t p(HPP_DYNAMIC_PTR_CAST(const Problem, problem)); | |
127 | ✗ | ptr = new StatesPathFinder(p, r); | |
128 | ✗ | } catch (std::exception&) { | |
129 | ✗ | throw std::invalid_argument( | |
130 | ✗ | "The problem must be of type hpp::manipulation::Problem."); | |
131 | } | ||
132 | ✗ | StatesPathFinderPtr_t shPtr(ptr); | |
133 | ✗ | ptr->init(shPtr); | |
134 | ✗ | return shPtr; | |
135 | } | ||
136 | |||
137 | ✗ | StatesPathFinderPtr_t StatesPathFinder::createWithRoadmap( | |
138 | const core::ProblemConstPtr_t& problem, const core::RoadmapPtr_t& roadmap) { | ||
139 | StatesPathFinder* ptr; | ||
140 | ✗ | ProblemConstPtr_t p = HPP_DYNAMIC_PTR_CAST(const Problem, problem); | |
141 | ✗ | RoadmapPtr_t r = HPP_DYNAMIC_PTR_CAST(Roadmap, roadmap); | |
142 | ✗ | if (!r) | |
143 | ✗ | throw std::invalid_argument( | |
144 | ✗ | "The roadmap must be of type hpp::manipulation::Roadmap."); | |
145 | ✗ | if (!p) | |
146 | ✗ | throw std::invalid_argument( | |
147 | ✗ | "The problem must be of type hpp::manipulation::Problem."); | |
148 | |||
149 | ✗ | ptr = new StatesPathFinder(p, r); | |
150 | ✗ | StatesPathFinderPtr_t shPtr(ptr); | |
151 | ✗ | ptr->init(shPtr); | |
152 | ✗ | return shPtr; | |
153 | } | ||
154 | |||
155 | ✗ | StatesPathFinderPtr_t StatesPathFinder::copy() const { | |
156 | ✗ | StatesPathFinder* ptr = new StatesPathFinder(*this); | |
157 | ✗ | StatesPathFinderPtr_t shPtr(ptr); | |
158 | ✗ | ptr->init(shPtr); | |
159 | ✗ | return shPtr; | |
160 | } | ||
161 | |||
162 | struct StatesPathFinder::GraphSearchData { | ||
163 | StatePtr_t s1; | ||
164 | // list of potential goal states | ||
165 | // can be multiple if goal is defined as a set of constraints | ||
166 | graph::States_t s2; | ||
167 | |||
168 | // index of the transition list | ||
169 | size_t idxSol; | ||
170 | |||
171 | // Datas for findNextTransitions | ||
172 | struct state_with_depth { | ||
173 | StatePtr_t s; | ||
174 | EdgePtr_t e; | ||
175 | std::size_t l; // depth to root | ||
176 | std::size_t i; // index in parent state_with_depths | ||
177 | // constructor used for root node | ||
178 | ✗ | inline state_with_depth() : s(), e(), l(0), i(0) {} | |
179 | // constructor used for non-root node | ||
180 | ✗ | inline state_with_depth(EdgePtr_t _e, std::size_t _l, std::size_t _i) | |
181 | ✗ | : s(_e->stateFrom()), e(_e), l(_l), i(_i) {} | |
182 | }; | ||
183 | typedef std::vector<state_with_depth> state_with_depths; | ||
184 | typedef std::map<StatePtr_t, state_with_depths> StateMap_t; | ||
185 | /// std::size_t is the index in state_with_depths at StateMap_t::iterator | ||
186 | struct state_with_depth_ptr_t { | ||
187 | StateMap_t::iterator state; | ||
188 | std::size_t parentIdx; | ||
189 | ✗ | state_with_depth_ptr_t(const StateMap_t::iterator& it, std::size_t idx) | |
190 | ✗ | : state(it), parentIdx(idx) {} | |
191 | }; | ||
192 | typedef std::deque<state_with_depth_ptr_t> Deque_t; | ||
193 | // vector of pointers to state with depth | ||
194 | typedef std::vector<state_with_depth_ptr_t> state_with_depths_t; | ||
195 | // transition lists exceeding this depth in the constraint graph will not be | ||
196 | // considered | ||
197 | std::size_t maxDepth; | ||
198 | // map each state X to a list of preceding states in transition lists that | ||
199 | // visit X state_with_depth struct gives info to trace the entire transition | ||
200 | // lists | ||
201 | StateMap_t parent1; | ||
202 | // store a vector of pointers to the end state of each transition list | ||
203 | state_with_depths_t solutions; | ||
204 | // the frontier of the graph search | ||
205 | // consists states that have not been expanded on | ||
206 | Deque_t queue1; | ||
207 | |||
208 | // track index of first transition list that has not been checked out | ||
209 | // only needed when goal is defined as set of constraints | ||
210 | size_t queueIt; | ||
211 | |||
212 | ✗ | const state_with_depth& getParent(const state_with_depth_ptr_t& _p) const { | |
213 | ✗ | const state_with_depths& parents = _p.state->second; | |
214 | ✗ | return parents[_p.parentIdx]; | |
215 | } | ||
216 | |||
217 | // add initial state (root node) to the map parent1 | ||
218 | ✗ | state_with_depth_ptr_t addInitState() { | |
219 | StateMap_t::iterator next = | ||
220 | ✗ | parent1.insert(StateMap_t::value_type(s1, state_with_depths(1))).first; | |
221 | ✗ | return state_with_depth_ptr_t(next, 0); | |
222 | } | ||
223 | |||
224 | // store a transition to the map parent1 | ||
225 | ✗ | state_with_depth_ptr_t addParent(const state_with_depth_ptr_t& _p, | |
226 | const EdgePtr_t& transition) { | ||
227 | ✗ | const state_with_depths& parents = _p.state->second; | |
228 | ✗ | const state_with_depth& from = parents[_p.parentIdx]; | |
229 | |||
230 | // Insert state to if necessary | ||
231 | StateMap_t::iterator next = | ||
232 | parent1 | ||
233 | ✗ | .insert(StateMap_t::value_type(transition->stateTo(), | |
234 | ✗ | state_with_depths())) | |
235 | ✗ | .first; | |
236 | |||
237 | ✗ | next->second.push_back( | |
238 | ✗ | state_with_depth(transition, from.l + 1, _p.parentIdx)); | |
239 | |||
240 | ✗ | return state_with_depth_ptr_t(next, next->second.size() - 1); | |
241 | } | ||
242 | }; | ||
243 | |||
244 | ✗ | static bool containsLevelSet(const graph::EdgePtr_t& e) { | |
245 | ✗ | graph::WaypointEdgePtr_t we = HPP_DYNAMIC_PTR_CAST(graph::WaypointEdge, e); | |
246 | ✗ | if (!we) return false; | |
247 | ✗ | for (std::size_t i = 0; i <= we->nbWaypoints(); i++) { | |
248 | graph::LevelSetEdgePtr_t lse = | ||
249 | ✗ | HPP_DYNAMIC_PTR_CAST(graph::LevelSetEdge, we->waypoint(i)); | |
250 | ✗ | if (lse) return true; | |
251 | } | ||
252 | ✗ | return false; | |
253 | } | ||
254 | |||
255 | ✗ | static bool isLoopTransition(const graph::EdgePtr_t& transition) { | |
256 | ✗ | return transition->stateTo() == transition->stateFrom(); | |
257 | } | ||
258 | |||
259 | ✗ | void StatesPathFinder::gatherGraphConstraints() { | |
260 | typedef graph::Edge Edge; | ||
261 | typedef graph::EdgePtr_t EdgePtr_t; | ||
262 | typedef graph::GraphPtr_t GraphPtr_t; | ||
263 | typedef constraints::solver::BySubstitution Solver_t; | ||
264 | |||
265 | ✗ | GraphPtr_t cg(problem_->constraintGraph()); | |
266 | ✗ | const ConstraintsAndComplements_t& cac(cg->constraintsAndComplements()); | |
267 | ✗ | for (std::size_t i = 0; i < cg->nbComponents(); ++i) { | |
268 | ✗ | EdgePtr_t edge(HPP_DYNAMIC_PTR_CAST(Edge, cg->get(i).lock())); | |
269 | |||
270 | // only gather the edge constraints | ||
271 | ✗ | if (!edge) continue; | |
272 | |||
273 | // Don't even consider level set edges | ||
274 | ✗ | if (containsLevelSet(edge)) continue; | |
275 | |||
276 | ✗ | const Solver_t& solver(edge->pathConstraint()->configProjector()->solver()); | |
277 | ✗ | const NumericalConstraints_t& constraints(solver.numericalConstraints()); | |
278 | ✗ | for (NumericalConstraints_t::const_iterator it(constraints.begin()); | |
279 | ✗ | it != constraints.end(); ++it) { | |
280 | // only look at parameterized constraint | ||
281 | ✗ | if ((*it)->parameterSize() == 0) continue; | |
282 | |||
283 | ✗ | const std::string& name((*it)->function().name()); | |
284 | // if constraint is in map, no need to add it | ||
285 | ✗ | if (index_.find(name) != index_.end()) continue; | |
286 | |||
287 | ✗ | index_[name] = constraints_.size(); | |
288 | // Check whether constraint is equivalent to a previous one | ||
289 | ✗ | for (NumericalConstraints_t::const_iterator it1(constraints_.begin()); | |
290 | ✗ | it1 != constraints_.end(); ++it1) { | |
291 | ✗ | for (ConstraintsAndComplements_t::const_iterator it2(cac.begin()); | |
292 | ✗ | it2 != cac.end(); ++it2) { | |
293 | ✗ | if (((**it1 == *(it2->complement)) && (**it == *(it2->both))) || | |
294 | ✗ | ((**it1 == *(it2->both)) && (**it == *(it2->complement)))) { | |
295 | ✗ | assert(sameRightHandSide_.count(*it1) == 0); | |
296 | ✗ | assert(sameRightHandSide_.count(*it) == 0); | |
297 | ✗ | sameRightHandSide_[*it1] = *it; | |
298 | ✗ | sameRightHandSide_[*it] = *it1; | |
299 | } | ||
300 | } | ||
301 | } | ||
302 | ✗ | constraints_.push_back(*it); | |
303 | hppDout(info, "Adding constraint \"" << name << "\""); | ||
304 | hppDout(info, "Edge \"" << edge->name() << "\""); | ||
305 | hppDout(info, "parameter size: " << (*it)->parameterSize()); | ||
306 | } | ||
307 | } | ||
308 | // constraint/both is the intersection of both constraint and | ||
309 | // constraint/complement | ||
310 | ✗ | for (ConstraintsAndComplements_t::const_iterator it(cac.begin()); | |
311 | ✗ | it != cac.end(); ++it) { | |
312 | ✗ | stricterConstraints_[it->constraint] = it->both; | |
313 | ✗ | stricterConstraints_[it->complement] = it->both; | |
314 | } | ||
315 | } | ||
316 | |||
317 | ✗ | bool StatesPathFinder::findTransitions(GraphSearchData& d) const { | |
318 | // all potential solutions should be attempted before finding more | ||
319 | ✗ | if (d.idxSol < d.solutions.size()) return false; | |
320 | ✗ | bool done = false; | |
321 | ✗ | while (!d.queue1.empty() && !done) { | |
322 | ✗ | GraphSearchData::state_with_depth_ptr_t _state = d.queue1.front(); | |
323 | |||
324 | ✗ | const GraphSearchData::state_with_depth& parent = d.getParent(_state); | |
325 | ✗ | if (parent.l >= d.maxDepth) return true; | |
326 | ✗ | d.queue1.pop_front(); | |
327 | |||
328 | ✗ | const Neighbors_t& neighbors = _state.state->first->neighbors(); | |
329 | ✗ | for (Neighbors_t::const_iterator _n = neighbors.begin(); | |
330 | ✗ | _n != neighbors.end(); ++_n) { | |
331 | ✗ | EdgePtr_t transition = _n->second; | |
332 | |||
333 | // Don't even consider level set edges | ||
334 | ✗ | if (containsLevelSet(transition)) continue; | |
335 | |||
336 | // Avoid identical consecutive transition | ||
337 | ✗ | if (transition == parent.e) continue; | |
338 | |||
339 | // Avoid loop transitions | ||
340 | ✗ | if (isLoopTransition(transition)) continue; | |
341 | |||
342 | // Insert the end state of the new path to parent | ||
343 | GraphSearchData::state_with_depth_ptr_t endState = | ||
344 | ✗ | d.addParent(_state, transition); | |
345 | ✗ | d.queue1.push_back(endState); | |
346 | |||
347 | // done if last state is one of potential goal states | ||
348 | ✗ | if (std::find(d.s2.begin(), d.s2.end(), transition->stateTo()) != | |
349 | ✗ | d.s2.end()) { | |
350 | ✗ | done = true; | |
351 | ✗ | d.solutions.push_back(endState); | |
352 | } | ||
353 | } | ||
354 | } | ||
355 | // return true if search is exhausted and goal state not found | ||
356 | ✗ | if (!done) return true; | |
357 | ✗ | return false; | |
358 | } | ||
359 | |||
360 | ✗ | Edges_t StatesPathFinder::getTransitionList(const GraphSearchData& d, | |
361 | const std::size_t& idxSol) const { | ||
362 | ✗ | Edges_t transitions; | |
363 | ✗ | if (idxSol >= d.solutions.size()) return transitions; | |
364 | |||
365 | ✗ | const GraphSearchData::state_with_depth_ptr_t endState = d.solutions[idxSol]; | |
366 | ✗ | const GraphSearchData::state_with_depth* current = &d.getParent(endState); | |
367 | ✗ | transitions.reserve(current->l); | |
368 | ✗ | graph::WaypointEdgePtr_t we; | |
369 | ✗ | while (current->e) { | |
370 | ✗ | assert(current->l > 0); | |
371 | ✗ | we = HPP_DYNAMIC_PTR_CAST(graph::WaypointEdge, current->e); | |
372 | ✗ | if (we) { | |
373 | ✗ | for (int i = (int)we->nbWaypoints(); i >= 0; --i) | |
374 | ✗ | transitions.push_back(we->waypoint(i)); | |
375 | } else { | ||
376 | ✗ | transitions.push_back(current->e); | |
377 | } | ||
378 | ✗ | current = &d.parent1.at(current->s)[current->i]; | |
379 | } | ||
380 | ✗ | std::reverse(transitions.begin(), transitions.end()); | |
381 | ✗ | return transitions; | |
382 | } | ||
383 | |||
384 | struct StatesPathFinder::OptimizationData { | ||
385 | typedef constraints::solver::HierarchicalIterative::Saturation_t Saturation_t; | ||
386 | enum RightHandSideStatus_t { | ||
387 | // Constraint is not in solver for this waypoint | ||
388 | ABSENT, | ||
389 | // right hand side of constraint for this waypoint is equal to | ||
390 | // right hand side for previous waypoint | ||
391 | EQUAL_TO_PREVIOUS, | ||
392 | // right hand side of constraint for this waypoint is equal to | ||
393 | // right hand side for initial configuration | ||
394 | EQUAL_TO_INIT, | ||
395 | // right hand side of constraint for this waypoint is equal to | ||
396 | // right hand side for goal configuration | ||
397 | EQUAL_TO_GOAL | ||
398 | }; // enum RightHandSideStatus_t | ||
399 | const std::size_t N, nq, nv; | ||
400 | std::vector<Solver_t> solvers; | ||
401 | std::vector<bool> isTargetWaypoint; | ||
402 | // Waypoints lying in each intermediate state | ||
403 | matrix_t waypoint; | ||
404 | const Configuration_t q1; | ||
405 | Configuration_t q2; | ||
406 | core::DevicePtr_t robot; | ||
407 | // Matrix specifying for each constraint and each waypoint how | ||
408 | // the right hand side is initialized in the solver. | ||
409 | Eigen::Matrix<LiegroupElement, Eigen::Dynamic, Eigen::Dynamic> M_rhs; | ||
410 | Eigen::Matrix<RightHandSideStatus_t, Eigen::Dynamic, Eigen::Dynamic> M_status; | ||
411 | // Number of trials to generate each waypoint configuration | ||
412 | // _solveGoalConfig: whether we need to solve for goal configuration | ||
413 | ✗ | OptimizationData(const core::ProblemConstPtr_t _problem, | |
414 | ConfigurationIn_t _q1, ConfigurationIn_t _q2, | ||
415 | const Edges_t& transitions, const bool _solveGoalConfig) | ||
416 | ✗ | : N(_solveGoalConfig ? transitions.size() : transitions.size() - 1), | |
417 | ✗ | nq(_problem->robot()->configSize()), | |
418 | ✗ | nv(_problem->robot()->numberDof()), | |
419 | ✗ | solvers(N, _problem->robot()->configSpace()), | |
420 | ✗ | waypoint(nq, N), | |
421 | ✗ | q1(_q1), | |
422 | ✗ | robot(_problem->robot()), | |
423 | ✗ | M_rhs(), | |
424 | ✗ | M_status() { | |
425 | ✗ | if (!_solveGoalConfig) { | |
426 | ✗ | assert(_q2.size() > 0); | |
427 | ✗ | q2 = _q2; | |
428 | } | ||
429 | ✗ | waypoint.setZero(); | |
430 | ✗ | for (auto solver : solvers) { | |
431 | // Set maximal number of iterations for each solver | ||
432 | ✗ | solver.maxIterations( | |
433 | ✗ | _problem->getParameter("StatesPathFinder/maxIteration").intValue()); | |
434 | // Set error threshold for each solver | ||
435 | ✗ | solver.errorThreshold( | |
436 | ✗ | _problem->getParameter("StatesPathFinder/errorThreshold") | |
437 | ✗ | .floatValue()); | |
438 | } | ||
439 | ✗ | assert(transitions.size() > 0); | |
440 | ✗ | isTargetWaypoint.assign(transitions.size(), false); | |
441 | ✗ | for (std::size_t i = 0; i < transitions.size(); i++) | |
442 | ✗ | isTargetWaypoint[i] = transitions[i]->stateTo()->isWaypoint(); | |
443 | } | ||
444 | }; | ||
445 | |||
446 | ✗ | bool StatesPathFinder::checkConstantRightHandSide(size_type index) { | |
447 | // a goal configuration is required to check if constraint is satisfied | ||
448 | // between initial and final configurations | ||
449 | ✗ | assert(!goalDefinedByConstraints_); | |
450 | ✗ | OptimizationData& d = *optData_; | |
451 | ✗ | const ImplicitPtr_t c(constraints_[index]); | |
452 | ✗ | LiegroupElement rhsInit(c->function().outputSpace()); | |
453 | ✗ | c->rightHandSideFromConfig(d.q1, rhsInit); | |
454 | ✗ | LiegroupElement rhsGoal(c->function().outputSpace()); | |
455 | ✗ | c->rightHandSideFromConfig(d.q2, rhsGoal); | |
456 | // Check that right hand sides are close to each other | ||
457 | ✗ | value_type eps(problem_->constraintGraph()->errorThreshold()); | |
458 | ✗ | value_type eps2(eps * eps); | |
459 | ✗ | if ((rhsGoal - rhsInit).squaredNorm() > eps2) { | |
460 | ✗ | return false; | |
461 | } | ||
462 | // Matrix of solver right hand sides | ||
463 | ✗ | for (size_type j = 0; j < d.M_rhs.cols(); ++j) { | |
464 | ✗ | d.M_rhs(index, j) = rhsInit; | |
465 | } | ||
466 | ✗ | return true; | |
467 | } | ||
468 | |||
469 | ✗ | bool StatesPathFinder::checkWaypointRightHandSide(std::size_t ictr, | |
470 | std::size_t jslv) const { | ||
471 | ✗ | const OptimizationData& d = *optData_; | |
472 | ✗ | ImplicitPtr_t c = constraints_[ictr]->copy(); | |
473 | ✗ | LiegroupElement rhsNow(c->function().outputSpace()); | |
474 | ✗ | assert(rhsNow.size() == c->rightHandSideSize()); | |
475 | ✗ | c->rightHandSideFromConfig(d.waypoint.col(jslv), rhsNow); | |
476 | ✗ | c = constraints_[ictr]->copy(); | |
477 | ✗ | LiegroupElement rhsOther(c->function().outputSpace()); | |
478 | ✗ | switch (d.M_status(ictr, jslv)) { | |
479 | ✗ | case OptimizationData::EQUAL_TO_INIT: | |
480 | ✗ | c->rightHandSideFromConfig(d.q1, rhsOther); | |
481 | ✗ | break; | |
482 | ✗ | case OptimizationData::EQUAL_TO_GOAL: | |
483 | ✗ | assert(!goalDefinedByConstraints_); | |
484 | ✗ | c->rightHandSideFromConfig(d.q2, rhsOther); | |
485 | ✗ | break; | |
486 | ✗ | case OptimizationData::EQUAL_TO_PREVIOUS: | |
487 | ✗ | c->rightHandSideFromConfig(d.waypoint.col(jslv - 1), rhsOther); | |
488 | ✗ | break; | |
489 | ✗ | case OptimizationData::ABSENT: | |
490 | default: | ||
491 | ✗ | return true; | |
492 | } | ||
493 | ✗ | hpp::pinocchio::vector_t diff = rhsOther - rhsNow; | |
494 | hpp::pinocchio::vector_t diffmask = | ||
495 | ✗ | hpp::pinocchio::vector_t::Zero(diff.size()); | |
496 | ✗ | for (auto k : c->activeRows()) // filter with constraint mask | |
497 | ✗ | for (size_type kk = k.first; kk < k.first + k.second; kk++) | |
498 | ✗ | diffmask[kk] = diff[kk]; | |
499 | ✗ | value_type eps(problem_->constraintGraph()->errorThreshold()); | |
500 | ✗ | value_type eps2(eps * eps); | |
501 | ✗ | return diffmask.squaredNorm() < eps2; | |
502 | } | ||
503 | |||
504 | ✗ | bool StatesPathFinder::checkWaypointRightHandSide(std::size_t jslv) const { | |
505 | ✗ | for (std::size_t ictr = 0; ictr < constraints_.size(); ictr++) | |
506 | ✗ | if (!checkWaypointRightHandSide(ictr, jslv)) return false; | |
507 | ✗ | return true; | |
508 | } | ||
509 | |||
510 | ✗ | void StatesPathFinder::displayRhsMatrix() { | |
511 | ✗ | OptimizationData& d = *optData_; | |
512 | ✗ | Eigen::Matrix<LiegroupElement, Eigen::Dynamic, Eigen::Dynamic>& m = d.M_rhs; | |
513 | |||
514 | ✗ | for (std::size_t i = 0; i < constraints_.size(); i++) { | |
515 | ✗ | const ImplicitPtr_t& constraint = constraints_[i]; | |
516 | ✗ | for (std::size_t j = 0; j < d.solvers.size(); j++) { | |
517 | ✗ | const vectorIn_t& config = d.waypoint.col(j); | |
518 | ✗ | LiegroupElement le(constraint->function().outputSpace()); | |
519 | ✗ | constraint->rightHandSideFromConfig(d.waypoint.col(j), le); | |
520 | ✗ | m(i, j) = le; | |
521 | } | ||
522 | } | ||
523 | |||
524 | ✗ | std::ostringstream oss; | |
525 | ✗ | oss.precision(2); | |
526 | ✗ | oss << "\\documentclass[12pt,landscape]{article}" << std::endl; | |
527 | ✗ | oss << "\\usepackage[a3paper]{geometry}" << std::endl; | |
528 | ✗ | oss << "\\begin {document}" << std::endl; | |
529 | |||
530 | ✗ | for (size_type ii = 0; ii < (m.cols() + 7) / 8; ii++) { | |
531 | ✗ | size_type j0 = ii * 8; | |
532 | ✗ | size_type j1 = std::min(ii * 8 + 8, m.cols()); | |
533 | ✗ | size_type dj = j1 - j0; | |
534 | ✗ | oss << "\\begin {tabular}{"; | |
535 | ✗ | for (size_type j = 0; j < dj + 2; ++j) oss << "c"; | |
536 | ✗ | oss << "}" << std::endl; | |
537 | ✗ | oss << "Constraint & mask"; | |
538 | ✗ | for (size_type j = j0; j < j1; ++j) oss << " & WP" << j; | |
539 | ✗ | oss << "\\\\" << std::endl; | |
540 | ✗ | for (size_type i = 0; i < m.rows(); ++i) { | |
541 | ✗ | std::vector<int> mask(constraints_[i]->parameterSize()); | |
542 | ✗ | for (auto k : constraints_[i]->activeRows()) | |
543 | ✗ | for (size_type kk = k.first; kk < k.first + k.second; kk++) | |
544 | ✗ | mask[kk] = 1; | |
545 | ✗ | std::ostringstream oss1; | |
546 | ✗ | oss1.precision(2); | |
547 | ✗ | std::ostringstream oss2; | |
548 | ✗ | oss2.precision(2); | |
549 | ✗ | oss1 << constraints_[i]->function().name() << " & "; | |
550 | |||
551 | ✗ | oss1 << "$\\left(\\begin{array}{c} "; | |
552 | ✗ | for (std::size_t k = 0; k < mask.size(); ++k) { | |
553 | ✗ | oss1 << mask[k] << "\\\\ "; | |
554 | } | ||
555 | ✗ | oss1 << "\\end{array}\\right)$" << std::endl; | |
556 | ✗ | oss1 << " & " << std::endl; | |
557 | |||
558 | ✗ | for (size_type j = j0; j < j1; ++j) { | |
559 | ✗ | if (d.M_status(i, j) != OptimizationData::ABSENT || | |
560 | ✗ | (j < m.cols() - 1 && | |
561 | ✗ | d.M_status(i, j + 1) == OptimizationData::EQUAL_TO_PREVIOUS)) { | |
562 | ✗ | oss2 << "$\\left(\\begin{array}{c} "; | |
563 | ✗ | for (size_type k = 0; k < m(i, j).size(); ++k) { | |
564 | ✗ | oss2 << ((abs(m(i, j).vector()[k]) < 1e-6) ? 0 | |
565 | ✗ | : m(i, j).vector()[k]) | |
566 | ✗ | << "\\\\ "; | |
567 | } | ||
568 | ✗ | oss2 << "\\end{array}\\right)$" << std::endl; | |
569 | } | ||
570 | ✗ | if (j < j1 - 1) { | |
571 | ✗ | oss2 << " & " << std::endl; | |
572 | } | ||
573 | } | ||
574 | ✗ | std::string str2 = oss2.str(); | |
575 | ✗ | if (str2.size() > 50) { // don't display constraints used nowhere | |
576 | ✗ | oss << oss1.str() << str2 << "\\\\" << std::endl; | |
577 | } | ||
578 | } | ||
579 | ✗ | oss << "\\end{tabular}" << std::endl << std::endl; | |
580 | } | ||
581 | ✗ | oss << "\\end{document}" << std::endl; | |
582 | |||
583 | ✗ | std::string s = oss.str(); | |
584 | ✗ | std::string s2 = ""; | |
585 | ✗ | for (std::size_t i = 0; i < s.size(); i++) { | |
586 | ✗ | if (s[i] == '_') | |
587 | ✗ | s2 += "\\_"; | |
588 | else | ||
589 | ✗ | s2.push_back(s[i]); | |
590 | } | ||
591 | hppDout(info, s2); | ||
592 | } | ||
593 | |||
594 | ✗ | void StatesPathFinder::displayStatusMatrix(const graph::Edges_t& transitions) { | |
595 | const Eigen::Matrix<OptimizationData::RightHandSideStatus_t, Eigen::Dynamic, | ||
596 | ✗ | Eigen::Dynamic>& m = optData_->M_status; | |
597 | ✗ | std::ostringstream oss; | |
598 | ✗ | oss.precision(5); | |
599 | ✗ | oss << "\\documentclass[12pt,landscape]{article}" << std::endl; | |
600 | ✗ | oss << "\\usepackage[a3paper]{geometry}" << std::endl; | |
601 | ✗ | oss << "\\begin {document}" << std::endl; | |
602 | ✗ | oss << "\\paragraph{Edges}" << std::endl; | |
603 | ✗ | oss << "\\begin{enumerate}" << std::endl; | |
604 | ✗ | for (auto edge : transitions) { | |
605 | ✗ | oss << "\\item \\texttt{" << edge->name() << "}" << std::endl; | |
606 | } | ||
607 | ✗ | oss << "\\end{enumerate}" << std::endl; | |
608 | ✗ | oss << "\\begin {tabular}{l|"; | |
609 | ✗ | for (size_type j = 0; j < m.cols(); ++j) | |
610 | ✗ | if (transitions[j]->stateTo()->isWaypoint()) | |
611 | ✗ | oss << "c"; | |
612 | else | ||
613 | ✗ | oss << "|c|"; | |
614 | ✗ | oss << "|}" << std::endl; | |
615 | ✗ | oss << "Constraint"; | |
616 | ✗ | for (size_type j = 0; j < m.cols(); ++j) oss << " & " << j + 1; | |
617 | ✗ | oss << "\\\\" << std::endl; | |
618 | ✗ | for (size_type i = 0; i < m.rows(); ++i) { | |
619 | ✗ | oss << "\\texttt{" << constraints_[i]->function().name() << "} & " | |
620 | ✗ | << std::endl; | |
621 | ✗ | for (size_type j = 0; j < m.cols(); ++j) { | |
622 | ✗ | oss << m(i, j); | |
623 | ✗ | if (j < m.cols() - 1) oss << " & "; | |
624 | } | ||
625 | ✗ | oss << "\\\\" << std::endl; | |
626 | } | ||
627 | ✗ | oss << "\\end{tabular}" << std::endl; | |
628 | ✗ | oss << "\\end{document}" << std::endl; | |
629 | |||
630 | ✗ | std::string s = oss.str(); | |
631 | ✗ | std::string s2 = ""; | |
632 | ✗ | for (std::size_t i = 0; i < s.size(); i++) { | |
633 | ✗ | if (s[i] == '_') | |
634 | ✗ | s2 += "\\_"; | |
635 | else | ||
636 | ✗ | s2.push_back(s[i]); | |
637 | } | ||
638 | hppDout(info, s2); | ||
639 | } | ||
640 | |||
641 | ✗ | bool StatesPathFinder::contains(const Solver_t& solver, | |
642 | const ImplicitPtr_t& c) const { | ||
643 | ✗ | if (solver.contains(c)) return true; | |
644 | std::map<ImplicitPtr_t, ImplicitPtr_t>::const_iterator it( | ||
645 | ✗ | sameRightHandSide_.find(c)); | |
646 | ✗ | if (it != sameRightHandSide_.end() && solver.contains(it->second)) | |
647 | ✗ | return true; | |
648 | ✗ | return false; | |
649 | } | ||
650 | |||
651 | ✗ | bool StatesPathFinder::containsStricter(const Solver_t& solver, | |
652 | const ImplicitPtr_t& c) const { | ||
653 | ✗ | if (solver.contains(c)) return true; | |
654 | std::map<ImplicitPtr_t, ImplicitPtr_t>::const_iterator it( | ||
655 | ✗ | stricterConstraints_.find(c)); | |
656 | ✗ | if (it != stricterConstraints_.end() && solver.contains(it->second)) | |
657 | ✗ | return true; | |
658 | ✗ | return false; | |
659 | } | ||
660 | |||
661 | ✗ | bool StatesPathFinder::buildOptimizationProblem( | |
662 | const graph::Edges_t& transitions) { | ||
663 | ✗ | OptimizationData& d = *optData_; | |
664 | // if no waypoint, check init and goal has same RHS | ||
665 | ✗ | if (d.N == 0) { | |
666 | ✗ | assert(transitions.size() == 1); | |
667 | ✗ | assert(!goalDefinedByConstraints_); | |
668 | ✗ | size_type index = 0; | |
669 | ✗ | for (NumericalConstraints_t::const_iterator it(constraints_.begin()); | |
670 | ✗ | it != constraints_.end(); ++it, ++index) { | |
671 | ✗ | const ImplicitPtr_t& c(*it); | |
672 | // Get transition solver | ||
673 | const Solver_t& trSolver( | ||
674 | ✗ | transitions[0]->pathConstraint()->configProjector()->solver()); | |
675 | ✗ | if (!contains(trSolver, c)) continue; | |
676 | ✗ | if (!checkConstantRightHandSide(index)) return false; | |
677 | } | ||
678 | ✗ | return true; | |
679 | } | ||
680 | ✗ | d.M_status.resize(constraints_.size(), d.N); | |
681 | ✗ | d.M_status.fill(OptimizationData::ABSENT); | |
682 | ✗ | d.M_rhs.resize(constraints_.size(), d.N); | |
683 | ✗ | d.M_rhs.fill(LiegroupElement()); | |
684 | ✗ | size_type index = 0; | |
685 | // Loop over constraints | ||
686 | ✗ | for (NumericalConstraints_t::const_iterator it(constraints_.begin()); | |
687 | ✗ | it != constraints_.end(); ++it, ++index) { | |
688 | ✗ | const ImplicitPtr_t& c(*it); | |
689 | // Loop forward over waypoints to determine right hand sides equal | ||
690 | // to initial configuration or previous configuration | ||
691 | ✗ | for (std::size_t j = 0; j < d.N; ++j) { | |
692 | // Get transition solver | ||
693 | const Solver_t& trSolver( | ||
694 | ✗ | transitions[j]->pathConstraint()->configProjector()->solver()); | |
695 | ✗ | if (!contains(trSolver, c)) continue; | |
696 | |||
697 | ✗ | if ((j == 0) || | |
698 | ✗ | d.M_status(index, j - 1) == OptimizationData::EQUAL_TO_INIT) { | |
699 | ✗ | d.M_status(index, j) = OptimizationData::EQUAL_TO_INIT; | |
700 | } else { | ||
701 | ✗ | d.M_status(index, j) = OptimizationData::EQUAL_TO_PREVIOUS; | |
702 | } | ||
703 | } | ||
704 | // If the goal configuration is not given | ||
705 | // no need to determine if RHS equal to goal configuration | ||
706 | ✗ | if (goalDefinedByConstraints_) { | |
707 | ✗ | continue; | |
708 | } | ||
709 | // Loop backward over waypoints to determine right hand sides equal | ||
710 | // to final configuration | ||
711 | ✗ | for (size_type j = d.N - 1; j > 0; --j) { | |
712 | // Get transition solver | ||
713 | ✗ | const Solver_t& trSolver(transitions[(std::size_t)j + 1] | |
714 | ✗ | ->pathConstraint() | |
715 | ✗ | ->configProjector() | |
716 | ✗ | ->solver()); | |
717 | ✗ | if (!contains(trSolver, c)) break; | |
718 | |||
719 | ✗ | if ((j == (size_type)d.N - 1) || | |
720 | ✗ | d.M_status(index, j + 1) == OptimizationData::EQUAL_TO_GOAL) { | |
721 | // if constraint right hand side is already equal to | ||
722 | // initial config, check that right hand side is equal | ||
723 | // for init and goal configs. | ||
724 | ✗ | if (d.M_status(index, j) == OptimizationData::EQUAL_TO_INIT) { | |
725 | ✗ | if (checkConstantRightHandSide(index)) { | |
726 | // stop for this constraint | ||
727 | ✗ | break; | |
728 | } else { | ||
729 | // Right hand side of constraint should be equal along the | ||
730 | // whole path but is different at init and at goal configs. | ||
731 | ✗ | return false; | |
732 | } | ||
733 | } else { | ||
734 | ✗ | d.M_status(index, j) = OptimizationData::EQUAL_TO_GOAL; | |
735 | } | ||
736 | } | ||
737 | } | ||
738 | } // for (NumericalConstraints_t::const_iterator it | ||
739 | #ifdef HPP_DEBUG | ||
740 | displayStatusMatrix(transitions); | ||
741 | #endif | ||
742 | // Fill solvers with target constraints of transition | ||
743 | ✗ | for (std::size_t j = 0; j < d.N; ++j) { | |
744 | ✗ | d.solvers[j] = | |
745 | ✗ | transitions[j]->targetConstraint()->configProjector()->solver(); | |
746 | ✗ | if (goalDefinedByConstraints_) { | |
747 | ✗ | continue; | |
748 | } | ||
749 | // when goal configuration is given, and if something | ||
750 | // (eg relative pose of two objects grasping) is fixed until goal, | ||
751 | // we need to propagate the constraint to an earlier solver, | ||
752 | // otherwise the chance it solves for the correct config is very low | ||
753 | ✗ | if (j > 0 && j < d.N - 1) { | |
754 | const Solver_t& otherSolver = | ||
755 | ✗ | transitions[j + 1]->pathConstraint()->configProjector()->solver(); | |
756 | ✗ | for (std::size_t i = 0; i < constraints_.size(); i++) { | |
757 | // transition from j-1 to j does not contain this constraint | ||
758 | // transition from j to j+1 (all the way to goal) has constraint | ||
759 | // constraint must be added to solve for waypoint at j (WP_j+1) | ||
760 | ✗ | if (d.M_status(i, j - 1) == OptimizationData::ABSENT && | |
761 | ✗ | d.M_status(i, j) == OptimizationData::EQUAL_TO_GOAL && | |
762 | ✗ | !contains(d.solvers[j], constraints_[i]) && | |
763 | ✗ | otherSolver.contains(constraints_[i])) { | |
764 | ✗ | d.solvers[j].add(constraints_[i]); | |
765 | hppDout(info, "Adding missing constraint " | ||
766 | << constraints_[i]->function().name() | ||
767 | << " to solver for waypoint" << j + 1); | ||
768 | } | ||
769 | } | ||
770 | } | ||
771 | } | ||
772 | |||
773 | // if goal is defined by constraints, some goal constraints may be | ||
774 | // missing from the end state. we should add these constraints to solver | ||
775 | // for the config in the final state | ||
776 | ✗ | if (goalDefinedByConstraints_) { | |
777 | ✗ | for (auto goalConstraint : goalConstraints_) { | |
778 | ✗ | if (!containsStricter(d.solvers[d.N - 1], goalConstraint)) { | |
779 | ✗ | d.solvers[d.N - 1].add(goalConstraint); | |
780 | hppDout(info, "Adding goal constraint " | ||
781 | << goalConstraint->function().name() | ||
782 | << " to solver for waypoint" << d.N); | ||
783 | } | ||
784 | } | ||
785 | } | ||
786 | |||
787 | ✗ | return true; | |
788 | } | ||
789 | |||
790 | ✗ | bool StatesPathFinder::checkSolverRightHandSide(std::size_t ictr, | |
791 | std::size_t jslv) const { | ||
792 | ✗ | const OptimizationData& d = *optData_; | |
793 | ✗ | ImplicitPtr_t c = constraints_[ictr]->copy(); | |
794 | ✗ | const Solver_t& solver = d.solvers[jslv]; | |
795 | ✗ | vector_t rhs(c->rightHandSideSize()); | |
796 | ✗ | solver.getRightHandSide(c, rhs); | |
797 | ✗ | LiegroupElement rhsNow(c->function().outputSpace()); | |
798 | ✗ | assert(rhsNow.size() == rhs.size()); | |
799 | ✗ | rhsNow.vector() = rhs; | |
800 | ✗ | LiegroupElement rhsOther(c->function().outputSpace()); | |
801 | ✗ | switch (d.M_status(ictr, jslv)) { | |
802 | ✗ | case OptimizationData::EQUAL_TO_INIT: | |
803 | ✗ | c->rightHandSideFromConfig(d.q1, rhsOther); | |
804 | ✗ | break; | |
805 | ✗ | case OptimizationData::EQUAL_TO_GOAL: | |
806 | ✗ | assert(!goalDefinedByConstraints_); | |
807 | ✗ | c->rightHandSideFromConfig(d.q2, rhsOther); | |
808 | ✗ | break; | |
809 | ✗ | case OptimizationData::EQUAL_TO_PREVIOUS: | |
810 | ✗ | c->rightHandSideFromConfig(d.waypoint.col(jslv - 1), rhsOther); | |
811 | ✗ | break; | |
812 | ✗ | case OptimizationData::ABSENT: | |
813 | default: | ||
814 | ✗ | return true; | |
815 | } | ||
816 | ✗ | hpp::pinocchio::vector_t diff = rhsOther - rhsNow; | |
817 | hpp::pinocchio::vector_t diffmask = | ||
818 | ✗ | hpp::pinocchio::vector_t::Zero(diff.size()); | |
819 | ✗ | for (auto k : c->activeRows()) // filter with constraint mask | |
820 | ✗ | for (size_type kk = k.first; kk < k.first + k.second; kk++) | |
821 | ✗ | diffmask[kk] = diff[kk]; | |
822 | ✗ | value_type eps(problem_->constraintGraph()->errorThreshold()); | |
823 | ✗ | value_type eps2(eps * eps); | |
824 | ✗ | if (diffmask.squaredNorm() > eps2) | |
825 | hppDout(warning, diffmask.squaredNorm() << " vs " << eps2); | ||
826 | ✗ | return diffmask.squaredNorm() < eps2; | |
827 | } | ||
828 | |||
829 | ✗ | bool StatesPathFinder::checkSolverRightHandSide(std::size_t jslv) const { | |
830 | ✗ | for (std::size_t ictr = 0; ictr < constraints_.size(); ictr++) | |
831 | ✗ | if (!checkSolverRightHandSide(ictr, jslv)) return false; | |
832 | ✗ | return true; | |
833 | } | ||
834 | |||
835 | ✗ | bool StatesPathFinder::buildOptimizationProblemFromNames( | |
836 | std::vector<std::string> names) { | ||
837 | ✗ | graph::Edges_t transitions; | |
838 | ✗ | graph::GraphPtr_t cg(problem_->constraintGraph()); | |
839 | ✗ | for (const std::string& name : names) { | |
840 | ✗ | for (std::size_t i = 0; i < cg->nbComponents(); ++i) { | |
841 | graph::EdgePtr_t edge( | ||
842 | ✗ | HPP_DYNAMIC_PTR_CAST(graph::Edge, cg->get(i).lock())); | |
843 | ✗ | if (edge && edge->name() == name) transitions.push_back(edge); | |
844 | } | ||
845 | } | ||
846 | ✗ | return buildOptimizationProblem(transitions); | |
847 | } | ||
848 | |||
849 | ✗ | void StatesPathFinder::preInitializeRHS(std::size_t j, Configuration_t& q) { | |
850 | ✗ | OptimizationData& d = *optData_; | |
851 | ✗ | Solver_t& solver(d.solvers[j]); | |
852 | ✗ | for (std::size_t i = 0; i < constraints_.size(); ++i) { | |
853 | ✗ | const ImplicitPtr_t& c(constraints_[i]); | |
854 | ✗ | bool ok = true; | |
855 | ✗ | switch (d.M_status((size_type)i, (size_type)j)) { | |
856 | ✗ | case OptimizationData::EQUAL_TO_INIT: | |
857 | ✗ | ok = solver.rightHandSideFromConfig(c, d.q1); | |
858 | ✗ | break; | |
859 | ✗ | case OptimizationData::EQUAL_TO_GOAL: | |
860 | ✗ | assert(!goalDefinedByConstraints_); | |
861 | ✗ | ok = solver.rightHandSideFromConfig(c, d.q2); | |
862 | ✗ | break; | |
863 | ✗ | case OptimizationData::EQUAL_TO_PREVIOUS: | |
864 | ✗ | ok = solver.rightHandSideFromConfig(c, q); | |
865 | ✗ | break; | |
866 | ✗ | case OptimizationData::ABSENT: | |
867 | default:; | ||
868 | } | ||
869 | ✗ | ok |= contains(solver, constraints_[i]); | |
870 | ✗ | if (!ok) { | |
871 | ✗ | std::ostringstream err_msg; | |
872 | ✗ | err_msg << "\nConstraint " << i << " missing for waypoint " << j + 1 | |
873 | ✗ | << " (" << c->function().name() << ")\n" | |
874 | ✗ | << "The constraints in this solver are:\n"; | |
875 | ✗ | for (const std::string& name : constraintNamesFromSolverAtWaypoint(j + 1)) | |
876 | ✗ | err_msg << name << "\n"; | |
877 | hppDout(warning, err_msg.str()); | ||
878 | } | ||
879 | ✗ | assert(ok); | |
880 | } | ||
881 | } | ||
882 | |||
883 | ✗ | bool StatesPathFinder::analyseOptimizationProblem( | |
884 | const graph::Edges_t& transitions, core::ProblemConstPtr_t _problem) { | ||
885 | typedef constraints::JointConstPtr_t JointConstPtr_t; | ||
886 | typedef core::RelativeMotion RelativeMotion; | ||
887 | |||
888 | ✗ | OptimizationData& d = *optData_; | |
889 | // map from pair of joint indices to vectors of constraints | ||
890 | typedef std::map<std::pair<size_type, size_type>, NumericalConstraints_t> | ||
891 | JointConstraintMap; | ||
892 | ✗ | JointConstraintMap jcmap; | |
893 | |||
894 | // iterate over all the transitions, propagate only constrained pairs | ||
895 | ✗ | for (std::size_t i = 0; i <= transitions.size() - 1; ++i) { | |
896 | // get index of the transition | ||
897 | ✗ | std::size_t transIdx = transitions.size() - 1 - i; | |
898 | ✗ | const EdgePtr_t& edge = transitions[transIdx]; | |
899 | ✗ | RelativeMotion::matrix_type m = edge->relativeMotion(); | |
900 | |||
901 | // check through the pairs already existing in jcmap | ||
902 | ✗ | JointConstraintMap::iterator it = jcmap.begin(); | |
903 | ✗ | while (it != jcmap.end()) { | |
904 | RelativeMotion::RelativeMotionType rmt = | ||
905 | ✗ | m(it->first.first, it->first.second); | |
906 | ✗ | if (rmt == RelativeMotion::RelativeMotionType::Unconstrained) { | |
907 | ✗ | JointConstraintMap::iterator toErase = it; | |
908 | ✗ | ++it; | |
909 | ✗ | jcmap.erase(toErase); | |
910 | } else { | ||
911 | ✗ | ++it; | |
912 | } | ||
913 | } | ||
914 | ✗ | NumericalConstraints_t currentConstraints; | |
915 | ✗ | if (transIdx == transitions.size() - 1 && !goalDefinedByConstraints_) { | |
916 | // get the constraints from the goal state | ||
917 | ✗ | currentConstraints = transitions[transIdx] | |
918 | ✗ | ->targetConstraint() | |
919 | ✗ | ->configProjector() | |
920 | ✗ | ->solver() | |
921 | ✗ | .constraints(); | |
922 | } else { | ||
923 | ✗ | currentConstraints = d.solvers[transIdx].constraints(); | |
924 | } | ||
925 | // loop through all constraints in the target node of the transition | ||
926 | ✗ | for (auto constraint : currentConstraints) { | |
927 | std::pair<JointConstPtr_t, JointConstPtr_t> jointPair = | ||
928 | ✗ | constraint->functionPtr()->dependsOnRelPoseBetween(_problem->robot()); | |
929 | ✗ | JointConstPtr_t joint1 = jointPair.first; | |
930 | ✗ | size_type index1 = RelativeMotion::idx(joint1); | |
931 | ✗ | JointConstPtr_t joint2 = jointPair.second; | |
932 | ✗ | size_type index2 = RelativeMotion::idx(joint2); | |
933 | |||
934 | // ignore constraint if it involves the same joint | ||
935 | ✗ | if (index1 == index2) continue; | |
936 | |||
937 | // check that the two joints are constrained in the transition | ||
938 | ✗ | RelativeMotion::RelativeMotionType rmt = m(index1, index2); | |
939 | ✗ | if (rmt == RelativeMotion::RelativeMotionType::Unconstrained) continue; | |
940 | |||
941 | // insert if necessary | ||
942 | JointConstraintMap::iterator next = | ||
943 | jcmap | ||
944 | ✗ | .insert(JointConstraintMap::value_type( | |
945 | ✗ | std::make_pair(index1, index2), NumericalConstraints_t())) | |
946 | ✗ | .first; | |
947 | // if constraint is not in map, insert it | ||
948 | ✗ | if (find_if(next->second.begin(), next->second.end(), | |
949 | ✗ | [&constraint](const ImplicitPtr_t& arg) { | |
950 | ✗ | return *arg == *constraint; | |
951 | ✗ | }) == next->second.end()) { | |
952 | ✗ | next->second.push_back(constraint); | |
953 | } | ||
954 | } | ||
955 | } | ||
956 | // at this point jcmap contains all the constraints that | ||
957 | // - depend on relative pose between 2 joints j1 and j2, | ||
958 | // - are present in the solver of any waypoint wp_i | ||
959 | // - j1 and j2 are constrained by all the transitions from q_init to wp_i | ||
960 | // | ||
961 | // in the following we test that q_init satisfies the above constraints | ||
962 | // otherwise the list of transitions is discarded | ||
963 | ✗ | if (jcmap.size() == 0) { | |
964 | ✗ | return true; | |
965 | } | ||
966 | |||
967 | ✗ | Solver_t analyseSolver(_problem->robot()->configSpace()); | |
968 | ✗ | analyseSolver.errorThreshold( | |
969 | ✗ | _problem->getParameter("StatesPathFinder/errorThreshold").floatValue()); | |
970 | // iterate through all the pairs that are left, | ||
971 | // and check that the initial config satisfies all the constraints | ||
972 | ✗ | for (JointConstraintMap::iterator it(jcmap.begin()); it != jcmap.end(); | |
973 | ✗ | it++) { | |
974 | ✗ | NumericalConstraints_t constraintList = it->second; | |
975 | hppDout(info, "Constraints involving joints " | ||
976 | << it->first.first << " and " << it->first.second | ||
977 | << " should be satisfied at q init"); | ||
978 | ✗ | for (NumericalConstraints_t::iterator ctrIt(constraintList.begin()); | |
979 | ✗ | ctrIt != constraintList.end(); ++ctrIt) { | |
980 | ✗ | analyseSolver.add((*ctrIt)->copy()); | |
981 | } | ||
982 | } | ||
983 | // initialize the right hand side with the initial config | ||
984 | ✗ | analyseSolver.rightHandSideFromConfig(q1_); | |
985 | ✗ | if (analyseSolver.isSatisfied(q1_)) { | |
986 | ✗ | return true; | |
987 | } | ||
988 | hppDout(info, | ||
989 | "Analysis found initial configuration does not satisfy constraint"); | ||
990 | ✗ | return false; | |
991 | } | ||
992 | |||
993 | ✗ | void StatesPathFinder::initializeRHS(std::size_t j) { | |
994 | ✗ | OptimizationData& d = *optData_; | |
995 | ✗ | Solver_t& solver(d.solvers[j]); | |
996 | ✗ | for (std::size_t i = 0; i < constraints_.size(); ++i) { | |
997 | ✗ | const ImplicitPtr_t& c(constraints_[i]); | |
998 | ✗ | bool ok = true; | |
999 | ✗ | switch (d.M_status((size_type)i, (size_type)j)) { | |
1000 | ✗ | case OptimizationData::EQUAL_TO_PREVIOUS: | |
1001 | ✗ | assert(j != 0); | |
1002 | ✗ | ok = solver.rightHandSideFromConfig(c, d.waypoint.col(j - 1)); | |
1003 | ✗ | break; | |
1004 | ✗ | case OptimizationData::EQUAL_TO_INIT: | |
1005 | ✗ | ok = solver.rightHandSideFromConfig(c, d.q1); | |
1006 | ✗ | break; | |
1007 | ✗ | case OptimizationData::EQUAL_TO_GOAL: | |
1008 | ✗ | assert(!goalDefinedByConstraints_); | |
1009 | ✗ | ok = solver.rightHandSideFromConfig(c, d.q2); | |
1010 | ✗ | break; | |
1011 | ✗ | case OptimizationData::ABSENT: | |
1012 | default:; | ||
1013 | } | ||
1014 | ✗ | ok |= contains(solver, constraints_[i]); | |
1015 | ✗ | if (!ok) { | |
1016 | ✗ | std::ostringstream err_msg; | |
1017 | ✗ | err_msg << "\nConstraint " << i << " missing for waypoint " << j + 1 | |
1018 | ✗ | << " (" << c->function().name() << ")\n" | |
1019 | ✗ | << "The constraints in this solver are:\n"; | |
1020 | ✗ | for (const std::string& name : constraintNamesFromSolverAtWaypoint(j + 1)) | |
1021 | ✗ | err_msg << name << "\n"; | |
1022 | hppDout(warning, err_msg.str()); | ||
1023 | } | ||
1024 | ✗ | assert(ok); | |
1025 | } | ||
1026 | } | ||
1027 | |||
1028 | ✗ | void StatesPathFinder::initWPRandom(std::size_t wp) { | |
1029 | ✗ | assert(wp >= 1 && wp <= (std::size_t)optData_->waypoint.cols()); | |
1030 | ✗ | initializeRHS(wp - 1); | |
1031 | ✗ | optData_->waypoint.col(wp - 1) = problem()->configurationShooter()->shoot(); | |
1032 | } | ||
1033 | ✗ | void StatesPathFinder::initWPNear(std::size_t wp) { | |
1034 | ✗ | assert(wp >= 1 && wp <= (std::size_t)optData_->waypoint.cols()); | |
1035 | ✗ | initializeRHS(wp - 1); | |
1036 | ✗ | if (wp == 1) | |
1037 | ✗ | optData_->waypoint.col(wp - 1) = optData_->q1; | |
1038 | else | ||
1039 | ✗ | optData_->waypoint.col(wp - 1) = optData_->waypoint.col(wp - 2); | |
1040 | } | ||
1041 | ✗ | void StatesPathFinder::initWP(std::size_t wp, ConfigurationIn_t q) { | |
1042 | ✗ | assert(wp >= 1 && wp <= (std::size_t)optData_->waypoint.cols()); | |
1043 | ✗ | initializeRHS(wp - 1); | |
1044 | ✗ | optData_->waypoint.col(wp - 1) = q; | |
1045 | } | ||
1046 | |||
1047 | ✗ | StatesPathFinder::SolveStepStatus StatesPathFinder::solveStep(std::size_t wp) { | |
1048 | ✗ | assert(wp >= 1 && wp <= (std::size_t)optData_->waypoint.cols()); | |
1049 | ✗ | std::size_t j = wp - 1; | |
1050 | ✗ | Solver_t& solver(optData_->solvers[j]); | |
1051 | Solver_t::Status status = | ||
1052 | ✗ | solver.solve(optData_->waypoint.col(j), | |
1053 | ✗ | constraints::solver::lineSearch::Backtracking()); | |
1054 | ✗ | if (status == Solver_t::SUCCESS) { | |
1055 | ✗ | assert(checkWaypointRightHandSide(j)); | |
1056 | ✗ | const graph::Edges_t& edges = lastBuiltTransitions_; | |
1057 | ✗ | core::ValidationReportPtr_t report; | |
1058 | // check collision based on preceeding edge to the waypoint | ||
1059 | ✗ | if (!edges[j]->pathValidation()->validate(optData_->waypoint.col(j), | |
1060 | report)) | ||
1061 | ✗ | return SolveStepStatus::COLLISION_BEFORE; | |
1062 | // if wp is not the goal node, check collision based on following edge | ||
1063 | ✗ | if (j < edges.size() - 1 && !edges[j + 1]->pathValidation()->validate( | |
1064 | ✗ | optData_->waypoint.col(j), report)) { | |
1065 | ✗ | return SolveStepStatus::COLLISION_AFTER; | |
1066 | } | ||
1067 | ✗ | return SolveStepStatus::VALID_SOLUTION; | |
1068 | } | ||
1069 | ✗ | return SolveStepStatus::NO_SOLUTION; | |
1070 | } | ||
1071 | |||
1072 | ✗ | std::string StatesPathFinder::displayConfigsSolved() const { | |
1073 | ✗ | const OptimizationData& d = *optData_; | |
1074 | ✗ | std::ostringstream oss; | |
1075 | ✗ | oss << "configs = [" << std::endl; | |
1076 | ✗ | oss << " " << pinocchio::displayConfig(d.q1) << ", # 0" << std::endl; | |
1077 | ✗ | for (size_type j = 0; j < d.waypoint.cols(); j++) | |
1078 | ✗ | oss << " " << pinocchio::displayConfig(d.waypoint.col(j)) << ", # " | |
1079 | ✗ | << j + 1 << std::endl; | |
1080 | ✗ | if (!goalDefinedByConstraints_) { | |
1081 | ✗ | oss << " " << pinocchio::displayConfig(d.q2) << " # " | |
1082 | ✗ | << d.waypoint.cols() + 1 << std::endl; | |
1083 | } | ||
1084 | ✗ | oss << "]" << std::endl; | |
1085 | ✗ | std::string ans = oss.str(); | |
1086 | hppDout(info, ans); | ||
1087 | ✗ | return ans; | |
1088 | } | ||
1089 | |||
1090 | // Get a configuration in accordance with the statuts matrix at a step j for the | ||
1091 | // constraint i | ||
1092 | ✗ | Configuration_t StatesPathFinder::getConfigStatus(size_type i, | |
1093 | size_type j) const { | ||
1094 | ✗ | switch (optData_->M_status(i, j)) { | |
1095 | ✗ | case OptimizationData::EQUAL_TO_PREVIOUS: | |
1096 | ✗ | return optData_->waypoint.col(j - 1); | |
1097 | ✗ | case OptimizationData::EQUAL_TO_INIT: | |
1098 | ✗ | return optData_->q1; | |
1099 | ✗ | case OptimizationData::EQUAL_TO_GOAL: | |
1100 | ✗ | return optData_->q2; | |
1101 | ✗ | default: | |
1102 | ✗ | return optData_->waypoint.col(j); | |
1103 | } | ||
1104 | } | ||
1105 | |||
1106 | // Get the right hand side of a constraint w.r.t a set configuration for this | ||
1107 | // constraint | ||
1108 | ✗ | vector_t StatesPathFinder::getConstraintRHS(ImplicitPtr_t constraint, | |
1109 | Configuration_t q) const { | ||
1110 | ✗ | LiegroupElement rhs(constraint->copy()->function().outputSpace()); | |
1111 | ✗ | constraint->rightHandSideFromConfig(q, rhs); | |
1112 | ✗ | return rhs.vector(); | |
1113 | } | ||
1114 | |||
1115 | // Hash a vector of right hand side into a long unsigned integer | ||
1116 | ✗ | size_t StatesPathFinder::hashRHS(vector_t rhs) const { | |
1117 | ✗ | std::stringstream ss; | |
1118 | ✗ | ss << std::setprecision(3) << (0.01 < rhs.array().abs()).select(rhs, 0.0f); | |
1119 | ✗ | return std::hash<std::string>{}(ss.str()); | |
1120 | } | ||
1121 | |||
1122 | // Check if a solution (a list of transitions) contains impossible to solve | ||
1123 | // steps due to inevitable collisions. A step is impossible to solve if it has | ||
1124 | // two constraints set from init or goal which have produced a collision between | ||
1125 | // objects constrained by them. | ||
1126 | // The list of such known constraint pairs are memorized in pairMap table and | ||
1127 | // individually in constraintMap. | ||
1128 | // | ||
1129 | // Return : true if no impossible to solve steps, false otherwise | ||
1130 | ✗ | bool StatesPathFinder::checkSolvers( | |
1131 | ConstraintMap_t const& pairMap, | ||
1132 | ConstraintMap_t const& constraintMap) const { | ||
1133 | // do nothing if there is no known incompatible constraint pairs. | ||
1134 | ✗ | if (constraintMap.empty()) return true; | |
1135 | |||
1136 | // for each steps of the solution | ||
1137 | ✗ | for (long unsigned i{0}; i < optData_->solvers.size(); i++) { | |
1138 | ✗ | std::vector<std::pair<ImplicitPtr_t, Configuration_t>> constraints{}; | |
1139 | |||
1140 | // gather all constraints of this step which are set from init or goal | ||
1141 | // configuration | ||
1142 | ✗ | for (long unsigned j{0}; j < constraints_.size(); j++) { | |
1143 | ✗ | auto c = constraints_[j]; | |
1144 | ✗ | auto status = optData_->M_status(j, i); | |
1145 | ✗ | if (status != OptimizationData::EQUAL_TO_INIT && | |
1146 | status != OptimizationData::EQUAL_TO_GOAL) // if not init or goal | ||
1147 | ✗ | continue; | |
1148 | ✗ | auto q = getConfigStatus(j, i); | |
1149 | ✗ | auto name = std::hash<std::string>{}(c->function().name()); | |
1150 | ✗ | if (constraintMap.count(name)) | |
1151 | ✗ | constraints.push_back(std::make_pair(c, q)); | |
1152 | } | ||
1153 | |||
1154 | // if there are less than two constraints gathered, go to next step | ||
1155 | ✗ | if (constraints.size() < 2) continue; | |
1156 | |||
1157 | // else, check if there is a pair of constraints in the table of known | ||
1158 | // incompatible pairs | ||
1159 | ✗ | for (auto& c1 : constraints) { | |
1160 | ✗ | auto rhs_1 = hashRHS(getConstraintRHS(std::get<0>(c1), std::get<1>(c1))); | |
1161 | auto name_1 = | ||
1162 | ✗ | std::hash<std::string>{}(std::get<0>(c1)->function().name()); | |
1163 | ✗ | if (constraintMap.count(name_1)) | |
1164 | ✗ | for (auto& c2 : constraints) { | |
1165 | auto rhs_2 = | ||
1166 | ✗ | hashRHS(getConstraintRHS(std::get<0>(c2), std::get<1>(c2))); | |
1167 | auto name_2 = | ||
1168 | ✗ | std::hash<std::string>{}(std::get<0>(c2)->function().name()); | |
1169 | ✗ | auto namesPair = name_1 * name_2; | |
1170 | ✗ | auto rhsPair = rhs_1 * rhs_2; | |
1171 | ✗ | if (name_1 != name_2 && pairMap.count(namesPair) && | |
1172 | ✗ | pairMap.at(namesPair) == rhsPair) | |
1173 | ✗ | return false; | |
1174 | } | ||
1175 | } | ||
1176 | } | ||
1177 | |||
1178 | ✗ | return true; | |
1179 | } | ||
1180 | |||
1181 | ✗ | core::JointConstPtr_t StatesPathFinder::maximalJoint(size_t const wp, | |
1182 | core::JointConstPtr_t a) { | ||
1183 | ✗ | const auto& current_edge = lastBuiltTransitions_[wp + 1]; | |
1184 | ✗ | core::RelativeMotion::matrix_type m = current_edge->relativeMotion(); | |
1185 | |||
1186 | ✗ | size_t ida = core::RelativeMotion::idx(a); | |
1187 | |||
1188 | ✗ | core::JointConstPtr_t last = nullptr; | |
1189 | ✗ | core::JointConstPtr_t current = a; | |
1190 | |||
1191 | ✗ | while (current != nullptr) { | |
1192 | ✗ | auto parent = current->parentJoint(); | |
1193 | ✗ | size_t idp = core::RelativeMotion::idx(parent); | |
1194 | ✗ | last = current; | |
1195 | ✗ | if (parent && m(ida, idp)) | |
1196 | ✗ | current = current->parentJoint(); | |
1197 | else | ||
1198 | ✗ | break; | |
1199 | } | ||
1200 | |||
1201 | ✗ | return last; | |
1202 | } | ||
1203 | |||
1204 | // For a certain step wp during solving check for collision impossible to solve. | ||
1205 | // If there is any store the constraints involved and stop the resolution | ||
1206 | // | ||
1207 | // Return : true if there is no collision or impossible to solve ones, false | ||
1208 | // otherwise. | ||
1209 | ✗ | bool StatesPathFinder::saveIncompatibleRHS(ConstraintMap_t& pairMap, | |
1210 | ConstraintMap_t& constraintMap, | ||
1211 | size_type const wp) { | ||
1212 | ✗ | core::ValidationReportPtr_t validationReport; | |
1213 | ✗ | auto q = optData_->waypoint.col(wp - 1); | |
1214 | ✗ | bool nocollision{true}; | |
1215 | |||
1216 | core::CollisionValidationPtr_t collisionValidations = | ||
1217 | ✗ | core::CollisionValidation::create(problem_->robot()); | |
1218 | ✗ | collisionValidations->checkParameterized(true); | |
1219 | ✗ | collisionValidations->computeAllContacts(true); | |
1220 | |||
1221 | // If there was a collision in the last configuration | ||
1222 | ✗ | if (!collisionValidations->validate(q, validationReport)) { | |
1223 | ✗ | auto allReports = HPP_DYNAMIC_PTR_CAST(core::AllCollisionsValidationReport, | |
1224 | validationReport); | ||
1225 | |||
1226 | // check all collision reports between joints | ||
1227 | ✗ | for (auto& report : allReports->collisionReports) { | |
1228 | // Store the two joints involved | ||
1229 | ✗ | core::JointConstPtr_t j1 = report->object1->joint(); | |
1230 | ✗ | core::JointConstPtr_t j2 = report->object2->joint(); | |
1231 | |||
1232 | // check that there is indeed two joints | ||
1233 | ✗ | if (!j1 || !j2) return nocollision; | |
1234 | |||
1235 | // get the maximal parent joint which are constrained with their child | ||
1236 | ✗ | j1 = maximalJoint(wp, j1); | |
1237 | ✗ | j2 = maximalJoint(wp, j2); | |
1238 | |||
1239 | // Function to check if two joints are equals, bye their address is | ||
1240 | // nullptr, by their value otherwise | ||
1241 | ✗ | auto equalJoints = [](core::JointConstPtr_t a, core::JointConstPtr_t b) { | |
1242 | ✗ | return (a && b) ? *a == *b : a == b; | |
1243 | }; | ||
1244 | |||
1245 | // std::cout << "test are constrained for j1 & j2: " << areConstrained(wp, | ||
1246 | // j1, j2) << std::endl; | ||
1247 | |||
1248 | typedef std::pair<core::JointConstPtr_t, size_t> jointOfConstraint; | ||
1249 | |||
1250 | // Get all constraints which involve a joint | ||
1251 | ✗ | auto associatedConstraints = [&](core::JointConstPtr_t j) { | |
1252 | ✗ | std::vector<jointOfConstraint> constraints{}; | |
1253 | ✗ | for (size_t i{0}; i < constraints_.size(); i++) { | |
1254 | ✗ | auto constraint = constraints_[i]; | |
1255 | auto joints = | ||
1256 | ✗ | constraint->doesConstrainRelPoseBetween(problem_->robot()); | |
1257 | ✗ | if (equalJoints(j, std::get<0>(joints)) || | |
1258 | ✗ | equalJoints(j, std::get<1>(joints))) { | |
1259 | ✗ | auto joint = (j == std::get<0>(joints)) ? std::get<1>(joints) | |
1260 | ✗ | : std::get<0>(joints); | |
1261 | ✗ | constraints.push_back(std::make_pair(joint, i)); | |
1262 | } | ||
1263 | } | ||
1264 | ✗ | return constraints; | |
1265 | ✗ | }; | |
1266 | |||
1267 | // We get all the constraints which contain j1 | ||
1268 | ✗ | auto constraints_j1 = associatedConstraints(j1); | |
1269 | |||
1270 | ✗ | const auto& current_edge = lastBuiltTransitions_[wp + 1]; | |
1271 | ✗ | core::RelativeMotion::matrix_type m = current_edge->relativeMotion(); | |
1272 | |||
1273 | ✗ | std::vector<short> visited(constraints_.size(), 0); | |
1274 | std::function<std::vector<int>(core::JointConstPtr_t, jointOfConstraint, | ||
1275 | int)> | ||
1276 | ✗ | exploreJOC; | |
1277 | |||
1278 | // Check if a joint is indirectly co-constrained with an other, return the | ||
1279 | // indices of their respective constraints | ||
1280 | ✗ | exploreJOC = [&](core::JointConstPtr_t j, jointOfConstraint current, | |
1281 | int initial) { | ||
1282 | ✗ | size_t constraint_index = std::get<1>(current); | |
1283 | ✗ | visited[constraint_index]++; | |
1284 | ✗ | core::JointConstPtr_t current_joint = std::get<0>(current); | |
1285 | ✗ | auto iconstraint = constraints_[constraint_index]; | |
1286 | ✗ | auto JOCs = associatedConstraints(current_joint); | |
1287 | ✗ | auto id_cj = core::RelativeMotion::idx(current_joint); | |
1288 | |||
1289 | ✗ | for (auto& joc : JOCs) { | |
1290 | ✗ | size_t ci = std::get<1>(joc); | |
1291 | ✗ | core::JointConstPtr_t ji = std::get<0>(joc); | |
1292 | ✗ | auto id_ji = core::RelativeMotion::idx(ji); | |
1293 | ✗ | if (m(id_cj, id_ji) == | |
1294 | core::RelativeMotion::RelativeMotionType::Unconstrained) | ||
1295 | ✗ | continue; | |
1296 | ✗ | if (equalJoints(ji, j)) | |
1297 | ✗ | return std::vector<int>{initial, (int)ci}; | |
1298 | ✗ | else if (visited[ci] < 2) { | |
1299 | ✗ | return exploreJOC(j, joc, initial); | |
1300 | } | ||
1301 | } | ||
1302 | ✗ | return std::vector<int>{-1, -1}; | |
1303 | ✗ | }; | |
1304 | |||
1305 | // get the indices of the constraints associated to the two joints | ||
1306 | ✗ | auto getIndices = [&]() -> std::vector<int> { | |
1307 | ✗ | for (auto& joc : constraints_j1) { | |
1308 | ✗ | visited[std::get<1>(joc)] = 1; | |
1309 | ✗ | auto indices = exploreJOC(j2, joc, (int)std::get<1>(joc)); | |
1310 | ✗ | if (indices[0] >= 0 || indices[1] >= 0) return indices; | |
1311 | } | ||
1312 | ✗ | return std::vector<int>{-1, -1}; | |
1313 | ✗ | }; | |
1314 | |||
1315 | // indices contains the two indices of the constraints that constraint | ||
1316 | // pose of j1 with respect to j2, if any, or { -1, -1} | ||
1317 | ✗ | auto indices = getIndices(); | |
1318 | |||
1319 | // Make sure indices are all defined | ||
1320 | ✗ | if (indices[0] < 0 || indices[1] < 0) return nocollision; | |
1321 | |||
1322 | // for each of the two constraint identified | ||
1323 | ✗ | std::vector<std::pair<size_t, size_t>> constraints{}; | |
1324 | ✗ | for (auto ic : indices) { | |
1325 | // check that there are set from goal or init configurations | ||
1326 | ✗ | auto status = optData_->M_status((size_t)ic, wp - 1); | |
1327 | ✗ | if (status != OptimizationData::EQUAL_TO_INIT && | |
1328 | status != OptimizationData::EQUAL_TO_GOAL) | ||
1329 | ✗ | return nocollision; | |
1330 | |||
1331 | // if so prepare to store them in the tables of known incompatible | ||
1332 | // constraints | ||
1333 | ✗ | auto c = constraints_[(size_t)ic]; | |
1334 | ✗ | auto rhs = hashRHS(getConstraintRHS(c, q)); | |
1335 | ✗ | auto name = std::hash<std::string>{}(c->function().name()); | |
1336 | |||
1337 | ✗ | constraints.push_back(std::make_pair(name, rhs)); | |
1338 | } | ||
1339 | |||
1340 | // then add them both in the tables of incompatible constraints | ||
1341 | ✗ | nocollision = false; | |
1342 | |||
1343 | // first, individually, in constraintMap | ||
1344 | ✗ | for (auto& c : constraints) | |
1345 | ✗ | if (!constraintMap.count(std::get<0>(c))) | |
1346 | ✗ | constraintMap[std::get<0>(c)] = std::get<1>(c); | |
1347 | |||
1348 | // then, both merged together in pairMap | ||
1349 | auto names = | ||
1350 | ✗ | std::get<0>(constraints[0]) * std::get<0>(constraints[1]); // key | |
1351 | auto rhs = | ||
1352 | ✗ | std::get<1>(constraints[0]) * std::get<1>(constraints[1]); // value | |
1353 | |||
1354 | ✗ | if (!pairMap.count(names)) pairMap[names] = rhs; | |
1355 | } | ||
1356 | } | ||
1357 | |||
1358 | ✗ | return nocollision; | |
1359 | } | ||
1360 | |||
1361 | ✗ | bool StatesPathFinder::solveOptimizationProblem() { | |
1362 | ✗ | static ConstraintMap_t pairMap{}; | |
1363 | ✗ | static ConstraintMap_t constraintMap{}; | |
1364 | |||
1365 | // check if the solution is feasible (no inevitable collision), if not abort | ||
1366 | // the solving | ||
1367 | ✗ | if (!checkSolvers(pairMap, constraintMap)) { | |
1368 | hppDout(info, "Path is invalid for collision is inevitable"); | ||
1369 | ✗ | return false; | |
1370 | } | ||
1371 | |||
1372 | ✗ | OptimizationData& d = *optData_; | |
1373 | // Try to solve with sets of random configs for each waypoint | ||
1374 | std::size_t nTriesMax = | ||
1375 | ✗ | problem_->getParameter("StatesPathFinder/nTriesUntilBacktrack") | |
1376 | ✗ | .intValue(); | |
1377 | ✗ | std::size_t nTriesMax1 = nTriesMax * 10; // more tries for the first waypoint | |
1378 | ✗ | std::size_t nFailsMax = | |
1379 | nTriesMax * 20; // fails before reseting the whole solution | ||
1380 | ✗ | std::size_t nBadSolvesMax = | |
1381 | nTriesMax * 50; // bad solve fails before reseting the whole solution | ||
1382 | ✗ | std::vector<std::size_t> nTriesDone(d.solvers.size() + 1, 0); | |
1383 | ✗ | std::size_t nFails = 0; | |
1384 | ✗ | std::size_t nBadSolves = 0; | |
1385 | ✗ | std::size_t wp = 1; // waypoint index starting at 1 (wp 0 = q1) | |
1386 | ✗ | std::size_t wp_max = 0; // all waypoints up to this index are valid solved | |
1387 | ✗ | matrix_t longestSolved(d.nq, d.N); | |
1388 | ✗ | longestSolved.setZero(); | |
1389 | ✗ | while (wp <= d.solvers.size()) { | |
1390 | ✗ | if (wp == 1) { | |
1391 | // stop if number of tries for the first waypoint exceeds | ||
1392 | ✗ | if (nTriesDone[1] >= nTriesMax1) { | |
1393 | // if cannot solve all the way, return longest VALID sequence | ||
1394 | ✗ | d.waypoint = longestSolved; | |
1395 | ✗ | return false; | |
1396 | } | ||
1397 | // Reset the fail counter while the solution is empty | ||
1398 | ✗ | nFails = 0; | |
1399 | ✗ | nBadSolves = 0; | |
1400 | |||
1401 | ✗ | } else if (nFails >= nFailsMax || nBadSolves >= nBadSolvesMax) { | |
1402 | // Completely reset a solution when too many tries have failed | ||
1403 | |||
1404 | // update the longest valid sequence of waypoints solved | ||
1405 | ✗ | if (wp - 1 > wp_max) { | |
1406 | // update the maximum index of valid waypoint | ||
1407 | ✗ | wp_max = wp - 1; | |
1408 | // save the sequence | ||
1409 | ✗ | longestSolved.leftCols(wp_max) = d.waypoint.leftCols(wp_max); | |
1410 | } | ||
1411 | |||
1412 | ✗ | std::fill(nTriesDone.begin() + 2, nTriesDone.end(), 0); | |
1413 | ✗ | wp = 1; | |
1414 | |||
1415 | #ifdef HPP_DEBUG | ||
1416 | if (nFails >= nFailsMax) { | ||
1417 | hppDout(warning, " Solution " | ||
1418 | << graphData_->idxSol | ||
1419 | << ": too many collisions. Resetting back to WP1"); | ||
1420 | } | ||
1421 | if (nBadSolves >= nBadSolvesMax) { | ||
1422 | hppDout(warning, | ||
1423 | " Solution " | ||
1424 | << graphData_->idxSol | ||
1425 | << ": too many bad solve statuses. Resetting back to WP1"); | ||
1426 | } | ||
1427 | #endif | ||
1428 | |||
1429 | ✗ | continue; | |
1430 | |||
1431 | ✗ | } else if (nTriesDone[wp] >= nTriesMax) { | |
1432 | // enough tries for a waypoint: backtrack | ||
1433 | |||
1434 | // update the longest valid sequence of waypoints solved | ||
1435 | ✗ | if (wp - 1 > wp_max) { | |
1436 | // update the maximum index of valid waypoint | ||
1437 | ✗ | wp_max = wp - 1; | |
1438 | // save the sequence | ||
1439 | ✗ | longestSolved.leftCols(wp_max) = d.waypoint.leftCols(wp_max); | |
1440 | } | ||
1441 | |||
1442 | do { | ||
1443 | ✗ | nTriesDone[wp] = 0; | |
1444 | ✗ | wp--; // backtrack: try a new solution for the latest waypoint | |
1445 | ✗ | } while (wp > 1 && | |
1446 | ✗ | (d.isTargetWaypoint[wp - 1] || nTriesDone[wp] >= nTriesMax)); | |
1447 | |||
1448 | ✗ | continue; | |
1449 | } | ||
1450 | |||
1451 | // Initialize right hand sides, and | ||
1452 | // Choose a starting configuration for the solver.solve method: | ||
1453 | // - from previous waypoint if it's the first time we see this solver | ||
1454 | // given current solvers 0 to j-1 | ||
1455 | // - with a random configuration if the other initialization has been | ||
1456 | // tried and failed | ||
1457 | ✗ | if (nTriesDone[wp] == 0) | |
1458 | ✗ | initWPNear(wp); | |
1459 | else | ||
1460 | ✗ | initWPRandom(wp); | |
1461 | |||
1462 | ✗ | nTriesDone[wp]++; // Backtrack to last state when this gets too big | |
1463 | |||
1464 | ✗ | SolveStepStatus out = solveStep(wp); | |
1465 | hppDout(info, "solveStep exit code at WP" << wp << ": " << out); | ||
1466 | ✗ | switch (out) { | |
1467 | ✗ | case SolveStepStatus::VALID_SOLUTION: // Valid solution, go to next | |
1468 | // waypoint | ||
1469 | ✗ | wp++; | |
1470 | ✗ | break; | |
1471 | ✗ | case SolveStepStatus::NO_SOLUTION: // Bad solve status, considered usual | |
1472 | // so has higher threshold before | ||
1473 | // going back to first waypoint | ||
1474 | ✗ | nBadSolves++; | |
1475 | ✗ | break; | |
1476 | ✗ | case SolveStepStatus::COLLISION_BEFORE: // Collision. If that happens too | |
1477 | // much, go back to first | ||
1478 | // waypoint | ||
1479 | case SolveStepStatus::COLLISION_AFTER: | ||
1480 | // if collision check that it is not due to non-solvable constraints, | ||
1481 | // if so, store the constraints involved and abort the solving | ||
1482 | ✗ | if (!saveIncompatibleRHS(pairMap, constraintMap, wp)) { | |
1483 | hppDout(info, "Path is invalid, found inevitable collision"); | ||
1484 | ✗ | return false; | |
1485 | } | ||
1486 | ✗ | nFails++; | |
1487 | ✗ | break; | |
1488 | ✗ | default: | |
1489 | ✗ | throw(std::logic_error("Unintended exit code for solveStep")); | |
1490 | } | ||
1491 | } | ||
1492 | |||
1493 | ✗ | return true; | |
1494 | } | ||
1495 | |||
1496 | // Get list of configurations from solution of optimization problem | ||
1497 | ✗ | core::Configurations_t StatesPathFinder::getConfigList() const { | |
1498 | ✗ | OptimizationData& d = *optData_; | |
1499 | ✗ | core::Configurations_t pv; | |
1500 | ✗ | pv.push_back(d.q1); | |
1501 | ✗ | for (std::size_t i = 0; i < d.N; ++i) { | |
1502 | ✗ | pv.push_back(d.waypoint.col(i)); | |
1503 | } | ||
1504 | ✗ | if (!goalDefinedByConstraints_) { | |
1505 | ✗ | pv.push_back(d.q2); | |
1506 | } | ||
1507 | ✗ | return pv; | |
1508 | } | ||
1509 | |||
1510 | // Loop over all the possible paths in the constraint graph between | ||
1511 | // the state of the initial configuration | ||
1512 | // and either [the state of the final configurations if given] OR | ||
1513 | // [one of potential goal states if goal defined as set of constraints] | ||
1514 | // and compute waypoint configurations in each state. | ||
1515 | ✗ | core::Configurations_t StatesPathFinder::computeConfigList( | |
1516 | ConfigurationIn_t q1, ConfigurationIn_t q2) { | ||
1517 | ✗ | const graph::GraphPtr_t& graph(problem_->constraintGraph()); | |
1518 | ✗ | GraphSearchData& d = *graphData_; | |
1519 | ✗ | size_t& idxSol = d.idxSol; | |
1520 | |||
1521 | bool maxDepthReached; | ||
1522 | ✗ | while (!(maxDepthReached = findTransitions(d))) { // mut | |
1523 | // if there is a working sequence, try it first before getting another | ||
1524 | // transition list | ||
1525 | ✗ | Edges_t transitions = (nTryConfigList_ > 0) | |
1526 | ✗ | ? lastBuiltTransitions_ | |
1527 | ✗ | : getTransitionList(d, idxSol); // const, const | |
1528 | ✗ | while (!transitions.empty()) { | |
1529 | #ifdef HPP_DEBUG | ||
1530 | std::ostringstream ss; | ||
1531 | ss << " Trying solution " << idxSol << ": \n\t"; | ||
1532 | for (std::size_t j = 0; j < transitions.size(); ++j) | ||
1533 | ss << transitions[j]->name() << ", \n\t"; | ||
1534 | hppDout(info, ss.str()); | ||
1535 | #endif // HPP_DEBUG | ||
1536 | ✗ | if (optData_) { | |
1537 | ✗ | delete optData_; | |
1538 | ✗ | optData_ = nullptr; | |
1539 | } | ||
1540 | ✗ | optData_ = new OptimizationData(problem(), q1, q2, transitions, | |
1541 | ✗ | goalDefinedByConstraints_); | |
1542 | |||
1543 | ✗ | if (buildOptimizationProblem(transitions)) { | |
1544 | ✗ | lastBuiltTransitions_ = transitions; | |
1545 | ✗ | if (nTryConfigList_ > 0 || | |
1546 | ✗ | analyseOptimizationProblem(transitions, problem())) { | |
1547 | ✗ | if (solveOptimizationProblem()) { | |
1548 | ✗ | core::Configurations_t path = getConfigList(); | |
1549 | hppDout(warning, | ||
1550 | " Solution " << idxSol << ": solved configurations list"); | ||
1551 | ✗ | return path; | |
1552 | ✗ | } else { | |
1553 | hppDout(info, " Failed solution " << idxSol | ||
1554 | << " at step 5 (solve opt pb)"); | ||
1555 | } | ||
1556 | } else { | ||
1557 | hppDout(info, " Failed solution " << idxSol | ||
1558 | << " at step 4 (analyse opt pb)"); | ||
1559 | } | ||
1560 | } else { | ||
1561 | hppDout(info, | ||
1562 | " Failed solution " << idxSol << " at step 3 (build opt pb)"); | ||
1563 | } | ||
1564 | ✗ | transitions = getTransitionList(d, ++idxSol); | |
1565 | // reset of the number of tries for a sequence | ||
1566 | // nTryConfigList_ = 0; | ||
1567 | } | ||
1568 | } | ||
1569 | ✗ | core::Configurations_t empty_path; | |
1570 | ✗ | empty_path.push_back(q1); | |
1571 | ✗ | return empty_path; | |
1572 | } | ||
1573 | |||
1574 | ✗ | void StatesPathFinder::reset() { | |
1575 | // when debugging, if we want to start from a certain transition list, | ||
1576 | // we can set it here | ||
1577 | ✗ | graphData_->idxSol = 0; | |
1578 | ✗ | if (optData_) { | |
1579 | ✗ | delete optData_; | |
1580 | ✗ | optData_ = nullptr; | |
1581 | } | ||
1582 | ✗ | lastBuiltTransitions_.clear(); | |
1583 | ✗ | idxConfigList_ = 0; | |
1584 | ✗ | nTryConfigList_ = 0; | |
1585 | } | ||
1586 | |||
1587 | ✗ | void StatesPathFinder::startSolve() { | |
1588 | ✗ | PathPlanner::startSolve(); | |
1589 | ✗ | assert(problem_); | |
1590 | ✗ | q1_ = problem_->initConfig(); | |
1591 | ✗ | assert(q1_.size() > 0); | |
1592 | |||
1593 | // core::PathProjectorPtr_t pathProjector | ||
1594 | // (core::pathProjector::Progressive::create(inStateProblem_, 0.01)); | ||
1595 | // inStateProblem_->pathProjector(pathProjector); | ||
1596 | ✗ | inStateProblem_->pathProjector(problem_->pathProjector()); | |
1597 | ✗ | const graph::GraphPtr_t& graph(problem_->constraintGraph()); | |
1598 | ✗ | graphData_.reset(new GraphSearchData()); | |
1599 | ✗ | GraphSearchData& d = *graphData_; | |
1600 | ✗ | d.s1 = graph->getState(q1_); | |
1601 | ✗ | d.maxDepth = problem_->getParameter("StatesPathFinder/maxDepth").intValue(); | |
1602 | |||
1603 | ✗ | d.queue1.push_back(d.addInitState()); | |
1604 | ✗ | d.queueIt = d.queue1.size(); | |
1605 | |||
1606 | #ifdef HPP_DEBUG | ||
1607 | // Print out the names of all the states in graph in debug mode | ||
1608 | States_t allStates = graph->stateSelector()->getStates(); | ||
1609 | hppDout(info, "Constraint graph has " << allStates.size() << " nodes"); | ||
1610 | for (auto state : allStates) { | ||
1611 | hppDout(info, "State: id = " << state->id() << " name = \"" << state->name() | ||
1612 | << "\""); | ||
1613 | } | ||
1614 | hppDout(info, | ||
1615 | "Constraint graph has " << graph->nbComponents() << " components"); | ||
1616 | #endif | ||
1617 | // Detect whether the goal is defined by a configuration or by a | ||
1618 | // set of constraints | ||
1619 | ✗ | ProblemTargetPtr_t target(problem()->target()); | |
1620 | GoalConfigurationsPtr_t goalConfigs( | ||
1621 | ✗ | HPP_DYNAMIC_PTR_CAST(GoalConfigurations, target)); | |
1622 | ✗ | if (goalConfigs) { | |
1623 | ✗ | goalDefinedByConstraints_ = false; | |
1624 | ✗ | core::Configurations_t q2s = goalConfigs->configurations(); | |
1625 | ✗ | if (q2s.size() != 1) { | |
1626 | ✗ | std::ostringstream os; | |
1627 | os << "StatesPathFinder accept one and only one goal " | ||
1628 | ✗ | "configuration, "; | |
1629 | ✗ | os << q2s.size() << " provided."; | |
1630 | ✗ | throw std::logic_error(os.str().c_str()); | |
1631 | } | ||
1632 | ✗ | q2_ = q2s[0]; | |
1633 | ✗ | d.s2.push_back(graph->getState(q2_)); | |
1634 | ✗ | } else { | |
1635 | ✗ | TaskTargetPtr_t taskTarget(HPP_DYNAMIC_PTR_CAST(TaskTarget, target)); | |
1636 | ✗ | if (!taskTarget) { | |
1637 | ✗ | std::ostringstream os; | |
1638 | os << "StatesPathFinder only accept goal defined as " | ||
1639 | ✗ | "either a configuration or a set of constraints."; | |
1640 | ✗ | throw std::logic_error(os.str().c_str()); | |
1641 | } | ||
1642 | ✗ | assert(q2_.size() == 0); | |
1643 | ✗ | goalDefinedByConstraints_ = true; | |
1644 | ✗ | goalConstraints_ = taskTarget->constraints(); | |
1645 | hppDout(info, "goal defined as a set of constraints"); | ||
1646 | |||
1647 | ✗ | int maxNumConstr = -1; | |
1648 | ✗ | for (StatePtr_t state : graph->stateSelector()->getStates()) { | |
1649 | ✗ | NumericalConstraints_t stateConstr = state->numericalConstraints(); | |
1650 | ✗ | int numConstr = 0; | |
1651 | ✗ | for (auto goalConstraint : goalConstraints_) { | |
1652 | ✗ | if (std::find(stateConstr.begin(), stateConstr.end(), goalConstraint) != | |
1653 | ✗ | stateConstr.end()) { | |
1654 | ✗ | ++numConstr; | |
1655 | hppDout(info, "State \"" << state->name() << "\" " | ||
1656 | << "has goal constraint: \"" | ||
1657 | << goalConstraint->function().name() | ||
1658 | << "\""); | ||
1659 | } | ||
1660 | } | ||
1661 | ✗ | if (numConstr > maxNumConstr) { | |
1662 | ✗ | d.s2.clear(); | |
1663 | ✗ | d.s2.push_back(state); | |
1664 | ✗ | maxNumConstr = numConstr; | |
1665 | ✗ | } else if (numConstr == maxNumConstr) { | |
1666 | ✗ | d.s2.push_back(state); | |
1667 | } | ||
1668 | } | ||
1669 | ✗ | d.idxSol = 0; | |
1670 | } | ||
1671 | ✗ | reset(); | |
1672 | } | ||
1673 | |||
1674 | ✗ | void StatesPathFinder::oneStep() { | |
1675 | ✗ | if (idxConfigList_ == 0) { | |
1676 | // TODO: accommodate when goal is a set of constraints | ||
1677 | ✗ | assert(q1_.size() > 0); | |
1678 | ✗ | configList_ = computeConfigList(q1_, q2_); | |
1679 | ✗ | if (configList_.size() <= 1) { // max depth reached | |
1680 | ✗ | reset(); | |
1681 | ✗ | throw core::path_planning_failed("Maximal depth reached."); | |
1682 | } | ||
1683 | } | ||
1684 | ✗ | size_t& idxSol = graphData_->idxSol; | |
1685 | ✗ | Configuration_t q1, q2; | |
1686 | ✗ | if (idxConfigList_ >= configList_.size() - 1) { | |
1687 | ✗ | reset(); | |
1688 | ✗ | throw core::path_planning_failed( | |
1689 | ✗ | "Final config reached but goal is not reached."); | |
1690 | } | ||
1691 | ✗ | q1 = configList_[idxConfigList_]; | |
1692 | ✗ | q2 = configList_[idxConfigList_ + 1]; | |
1693 | ✗ | const graph::EdgePtr_t& edge(lastBuiltTransitions_[idxConfigList_]); | |
1694 | // Copy edge constraints | ||
1695 | ✗ | core::ConstraintSetPtr_t constraints(HPP_DYNAMIC_PTR_CAST( | |
1696 | ✗ | core::ConstraintSet, edge->pathConstraint()->copy())); | |
1697 | // Initialize right hand side | ||
1698 | ✗ | constraints->configProjector()->rightHandSideFromConfig(q1); | |
1699 | ✗ | assert(constraints->isSatisfied(q2)); | |
1700 | ✗ | inStateProblem_->constraints(constraints); | |
1701 | ✗ | inStateProblem_->pathValidation(edge->pathValidation()); | |
1702 | ✗ | inStateProblem_->steeringMethod(edge->steeringMethod()); | |
1703 | ✗ | inStateProblem_->initConfig(q1); | |
1704 | ✗ | inStateProblem_->resetGoalConfigs(); | |
1705 | ✗ | inStateProblem_->addGoalConfig(q2); | |
1706 | |||
1707 | /// use inner state planner to plan path between two configurations. | ||
1708 | /// these configs lie on same leaf (same RHS wrt edge constraints) | ||
1709 | /// eg consecutive configs in the solved config list | ||
1710 | core::PathPlannerPtr_t inStatePlanner( | ||
1711 | ✗ | core::DiffusingPlanner::create(inStateProblem_)); | |
1712 | ✗ | inStatePlanner->maxIterations( | |
1713 | ✗ | problem_->getParameter("StatesPathFinder/innerPlannerMaxIterations") | |
1714 | ✗ | .intValue()); | |
1715 | value_type innerPlannerTimeout = | ||
1716 | ✗ | problem_->getParameter("StatesPathFinder/innerPlannerTimeOut") | |
1717 | ✗ | .floatValue(); | |
1718 | // only set timeout if it is more than 0. default is infinity | ||
1719 | ✗ | if (innerPlannerTimeout > 0.) { | |
1720 | ✗ | inStatePlanner->timeOut(innerPlannerTimeout); | |
1721 | } | ||
1722 | hppDout(info, | ||
1723 | "calling InStatePlanner_.solve for transition " << idxConfigList_); | ||
1724 | ✗ | core::PathVectorPtr_t path; | |
1725 | try { | ||
1726 | ✗ | path = inStatePlanner->solve(); | |
1727 | ✗ | for (std::size_t r = 0; r < path->numberPaths() - 1; r++) | |
1728 | ✗ | assert(path->pathAtRank(r)->end() == path->pathAtRank(r + 1)->initial()); | |
1729 | ✗ | idxConfigList_++; | |
1730 | ✗ | if (idxConfigList_ == configList_.size() - 1) { | |
1731 | hppDout( | ||
1732 | warning, "Solution " | ||
1733 | << idxSol << ": Success" | ||
1734 | << "\n-----------------------------------------------"); | ||
1735 | } | ||
1736 | ✗ | } catch (const core::path_planning_failed& error) { | |
1737 | ✗ | std::ostringstream oss; | |
1738 | ✗ | oss << "Error " << error.what() << "\n"; | |
1739 | ✗ | oss << "Solution " << idxSol << ": Failed to build path at edge " | |
1740 | ✗ | << idxConfigList_ << ": "; | |
1741 | ✗ | oss << lastBuiltTransitions_[idxConfigList_]->name(); | |
1742 | hppDout(warning, oss.str()); | ||
1743 | |||
1744 | ✗ | idxConfigList_ = 0; | |
1745 | // Retry nTryMax times to build another solution for the same states list | ||
1746 | size_type nTryMax = | ||
1747 | ✗ | problem_->getParameter("StatesPathFinder/maxTriesBuildPath").intValue(); | |
1748 | ✗ | if (++nTryConfigList_ >= nTryMax) { | |
1749 | ✗ | nTryConfigList_ = 0; | |
1750 | ✗ | idxSol++; | |
1751 | } | ||
1752 | } | ||
1753 | ✗ | roadmap()->merge(inStatePlanner->roadmap()); | |
1754 | // if (path) { | ||
1755 | // core::PathOptimizerPtr_t inStateOptimizer | ||
1756 | // (core::pathOptimization::RandomShortcut::create(inStateProblem_)); | ||
1757 | // core::PathVectorPtr_t opt = inStateOptimizer->optimize(path); | ||
1758 | // roadmap()->insertPathVector(opt, true); | ||
1759 | // } | ||
1760 | } | ||
1761 | |||
1762 | ✗ | void StatesPathFinder::tryConnectInitAndGoals() { | |
1763 | ✗ | GraphSearchData& d = *graphData_; | |
1764 | // if start state is not one of the potential goal states, return | ||
1765 | ✗ | if (std::find(d.s2.begin(), d.s2.end(), d.s1) == d.s2.end()) { | |
1766 | ✗ | return; | |
1767 | } | ||
1768 | |||
1769 | // get the loop edge connecting the initial state to itself | ||
1770 | const graph::Edges_t& loopEdges( | ||
1771 | ✗ | problem_->constraintGraph()->getEdges(d.s1, d.s1)); | |
1772 | // check that there is 1 loop edge | ||
1773 | ✗ | assert(loopEdges.size() == 1); | |
1774 | // add the loop transition as transition list | ||
1775 | ✗ | GraphSearchData::state_with_depth_ptr_t _state = d.queue1.front(); | |
1776 | GraphSearchData::state_with_depth_ptr_t _endState = | ||
1777 | ✗ | d.addParent(_state, loopEdges[0]); | |
1778 | ✗ | d.solutions.push_back(_endState); | |
1779 | |||
1780 | // try connecting initial and final configurations directly | ||
1781 | ✗ | if (!goalDefinedByConstraints_) PathPlanner::tryConnectInitAndGoals(); | |
1782 | } | ||
1783 | |||
1784 | ✗ | std::vector<std::string> StatesPathFinder::constraintNamesFromSolverAtWaypoint( | |
1785 | std::size_t wp) { | ||
1786 | ✗ | assert(wp > 0 && wp <= optData_->solvers.size()); | |
1787 | ✗ | constraints::solver::BySubstitution& solver(optData_->solvers[wp - 1]); | |
1788 | ✗ | std::vector<std::string> ans; | |
1789 | ✗ | for (std::size_t i = 0; i < solver.constraints().size(); i++) | |
1790 | ✗ | ans.push_back(solver.constraints()[i]->function().name()); | |
1791 | ✗ | return ans; | |
1792 | } | ||
1793 | |||
1794 | ✗ | std::vector<std::string> StatesPathFinder::lastBuiltTransitions() const { | |
1795 | ✗ | std::vector<std::string> ans; | |
1796 | ✗ | for (const EdgePtr_t& edge : lastBuiltTransitions_) | |
1797 | ✗ | ans.push_back(edge->name()); | |
1798 | ✗ | return ans; | |
1799 | } | ||
1800 | |||
1801 | using core::Parameter; | ||
1802 | using core::ParameterDescription; | ||
1803 | |||
1804 | 1 | HPP_START_PARAMETER_DECLARATION(StatesPathFinder) | |
1805 |
4/8✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
|
1 | core::Problem::declareParameter(ParameterDescription( |
1806 | Parameter::INT, "StatesPathFinder/maxDepth", | ||
1807 | "Maximum number of transitions to look for.", | ||
1808 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | Parameter((size_type)std::numeric_limits<int>::max()))); |
1809 |
4/8✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
|
1 | core::Problem::declareParameter(ParameterDescription( |
1810 | Parameter::INT, "StatesPathFinder/maxIteration", | ||
1811 | "Maximum number of iterations of the Newton Raphson algorithm.", | ||
1812 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Parameter((size_type)60))); |
1813 |
4/8✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
|
1 | core::Problem::declareParameter(ParameterDescription( |
1814 | Parameter::FLOAT, "StatesPathFinder/errorThreshold", | ||
1815 | "Error threshold of the Newton Raphson algorithm." | ||
1816 | "Should be at most the same as error threshold in constraint graph", | ||
1817 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Parameter(1e-4))); |
1818 |
4/8✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
|
1 | core::Problem::declareParameter(ParameterDescription( |
1819 | Parameter::INT, "StatesPathFinder/nTriesUntilBacktrack", | ||
1820 | "Number of tries when sampling configurations before backtracking" | ||
1821 | "in function solveOptimizationProblem.", | ||
1822 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Parameter((size_type)3))); |
1823 |
4/8✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
|
1 | core::Problem::declareParameter(ParameterDescription( |
1824 | Parameter::INT, "StatesPathFinder/maxTriesCollisionAnalysis", | ||
1825 | "Number of solve tries before stopping the collision analysis," | ||
1826 | "before the actual solving part." | ||
1827 | "Set to 0 to skip this part of the algorithm.", | ||
1828 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Parameter((size_type)100))); |
1829 |
4/8✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
|
1 | core::Problem::declareParameter(ParameterDescription( |
1830 | Parameter::INT, "StatesPathFinder/maxTriesBuildPath", | ||
1831 | "Number of solutions with a given states list to try to build a" | ||
1832 | "continuous path from, before skipping to the next states list", | ||
1833 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Parameter((size_type)5))); |
1834 |
4/8✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
|
1 | core::Problem::declareParameter(ParameterDescription( |
1835 | Parameter::FLOAT, "StatesPathFinder/innerPlannerTimeOut", | ||
1836 | "This will set ::timeOut accordingly in the inner" | ||
1837 | "planner used for building a path after intermediate" | ||
1838 | "configurations have been found." | ||
1839 | "If set to 0, no timeout: only maxIterations will be used to stop" | ||
1840 | "the innerPlanner if it does not find a path.", | ||
1841 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Parameter(2.0))); |
1842 |
4/8✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
|
1 | core::Problem::declareParameter(ParameterDescription( |
1843 | Parameter::INT, "StatesPathFinder/innerPlannerMaxIterations", | ||
1844 | "This will set ::maxIterations accordingly in the inner" | ||
1845 | "planner used for building a path after intermediate" | ||
1846 | "configurations have been found", | ||
1847 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Parameter((size_type)1000))); |
1848 | 1 | HPP_END_PARAMETER_DECLARATION(StatesPathFinder) | |
1849 | } // namespace pathPlanner | ||
1850 | } // namespace manipulation | ||
1851 | } // namespace hpp | ||
1852 |