Line |
Branch |
Exec |
Source |
1 |
|
|
// Copyright (c) 2019 CNRS |
2 |
|
|
// Authors: Joseph Mirabel |
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/constraints/differentiable-function.hh> |
30 |
|
|
#include <hpp/constraints/implicit.hh> |
31 |
|
|
#include <hpp/core/config-projector.hh> |
32 |
|
|
#include <hpp/core/config-validations.hh> |
33 |
|
|
#include <hpp/core/configuration-shooter.hh> |
34 |
|
|
#include <hpp/core/path-validation.hh> |
35 |
|
|
#include <hpp/core/problem.hh> |
36 |
|
|
#include <hpp/core/roadmap.hh> |
37 |
|
|
#include <hpp/manipulation/path-planner/end-effector-trajectory.hh> |
38 |
|
|
#include <hpp/manipulation/steering-method/end-effector-trajectory.hh> |
39 |
|
|
#include <hpp/pinocchio/device-sync.hh> |
40 |
|
|
#include <hpp/pinocchio/liegroup-element.hh> |
41 |
|
|
#include <hpp/pinocchio/util.hh> |
42 |
|
|
#include <hpp/util/exception-factory.hh> |
43 |
|
|
#include <pinocchio/multibody/data.hpp> |
44 |
|
|
|
45 |
|
|
namespace hpp { |
46 |
|
|
namespace manipulation { |
47 |
|
|
namespace pathPlanner { |
48 |
|
|
typedef manipulation::steeringMethod::EndEffectorTrajectory SM_t; |
49 |
|
|
typedef manipulation::steeringMethod::EndEffectorTrajectoryPtr_t SMPtr_t; |
50 |
|
|
|
51 |
|
✗ |
EndEffectorTrajectoryPtr_t EndEffectorTrajectory::create( |
52 |
|
|
const core::ProblemConstPtr_t& problem) { |
53 |
|
✗ |
EndEffectorTrajectoryPtr_t ptr(new EndEffectorTrajectory(problem)); |
54 |
|
✗ |
ptr->init(ptr); |
55 |
|
✗ |
return ptr; |
56 |
|
|
} |
57 |
|
|
|
58 |
|
✗ |
EndEffectorTrajectoryPtr_t EndEffectorTrajectory::createWithRoadmap( |
59 |
|
|
const core::ProblemConstPtr_t& problem, const core::RoadmapPtr_t& roadmap) { |
60 |
|
✗ |
EndEffectorTrajectoryPtr_t ptr(new EndEffectorTrajectory(problem, roadmap)); |
61 |
|
✗ |
ptr->init(ptr); |
62 |
|
✗ |
return ptr; |
63 |
|
|
} |
64 |
|
|
|
65 |
|
✗ |
void EndEffectorTrajectory::tryConnectInitAndGoals() {} |
66 |
|
|
|
67 |
|
✗ |
void EndEffectorTrajectory::startSolve() { |
68 |
|
|
// core::PathPlanner::startSolve(); |
69 |
|
|
// problem().checkProblem (); |
70 |
|
✗ |
if (!problem()->robot()) { |
71 |
|
✗ |
std::string msg("No device in problem."); |
72 |
|
|
hppDout(error, msg); |
73 |
|
✗ |
throw std::runtime_error(msg); |
74 |
|
|
} |
75 |
|
|
|
76 |
|
✗ |
if (problem()->initConfig().size() == 0) { |
77 |
|
✗ |
std::string msg("No init config in problem."); |
78 |
|
|
hppDout(error, msg); |
79 |
|
✗ |
throw std::runtime_error(msg); |
80 |
|
|
} |
81 |
|
|
|
82 |
|
|
// Tag init and goal configurations in the roadmap |
83 |
|
✗ |
roadmap()->resetGoalNodes(); |
84 |
|
|
|
85 |
|
✗ |
SMPtr_t sm(HPP_DYNAMIC_PTR_CAST(SM_t, problem()->steeringMethod())); |
86 |
|
✗ |
if (!sm) |
87 |
|
✗ |
throw std::invalid_argument( |
88 |
|
|
"Steering method must be of type " |
89 |
|
✗ |
"hpp::manipulation::steeringMethod::EndEffectorTrajectory"); |
90 |
|
|
|
91 |
|
✗ |
if (!sm->constraints() || !sm->constraints()->configProjector()) |
92 |
|
✗ |
throw std::invalid_argument( |
93 |
|
✗ |
"Steering method constraint has no ConfigProjector."); |
94 |
|
✗ |
core::ConfigProjectorPtr_t constraints(sm->constraints()->configProjector()); |
95 |
|
|
|
96 |
|
✗ |
const constraints::ImplicitPtr_t& trajConstraint = sm->trajectoryConstraint(); |
97 |
|
✗ |
if (!trajConstraint) |
98 |
|
✗ |
throw std::invalid_argument( |
99 |
|
✗ |
"EndEffectorTrajectory has no trajectory constraint."); |
100 |
|
✗ |
if (!sm->trajectory()) |
101 |
|
✗ |
throw std::invalid_argument("EndEffectorTrajectory has no trajectory."); |
102 |
|
|
|
103 |
|
✗ |
const core::NumericalConstraints_t& ncs = constraints->numericalConstraints(); |
104 |
|
✗ |
bool ok = false; |
105 |
|
✗ |
for (std::size_t i = 0; i < ncs.size(); ++i) { |
106 |
|
✗ |
if (ncs[i] == trajConstraint) { |
107 |
|
✗ |
ok = true; |
108 |
|
✗ |
break; // Same pointer |
109 |
|
|
} |
110 |
|
|
// Here, we do not check the right hand side on purpose. |
111 |
|
|
// if (*ncs[i] == *trajConstraint) { |
112 |
|
✗ |
if (ncs[i]->functionPtr() == trajConstraint->functionPtr() && |
113 |
|
✗ |
ncs[i]->comparisonType() == trajConstraint->comparisonType()) { |
114 |
|
✗ |
ok = true; |
115 |
|
|
// TODO We should only modify the path constraint. |
116 |
|
|
// However, only the pointers to implicit constraints are copied |
117 |
|
|
// while we would like the implicit constraints to be copied as well. |
118 |
|
✗ |
ncs[i]->rightHandSideFunction(sm->trajectory()); |
119 |
|
✗ |
break; // logically identical |
120 |
|
|
} |
121 |
|
|
} |
122 |
|
✗ |
if (!ok) { |
123 |
|
✗ |
HPP_THROW(std::logic_error, |
124 |
|
|
"EndEffectorTrajectory could not find " |
125 |
|
|
"constraint " |
126 |
|
|
<< trajConstraint->function()); |
127 |
|
|
} |
128 |
|
|
} |
129 |
|
|
|
130 |
|
✗ |
void EndEffectorTrajectory::oneStep() { |
131 |
|
✗ |
SMPtr_t sm(HPP_DYNAMIC_PTR_CAST(SM_t, problem()->steeringMethod())); |
132 |
|
✗ |
if (!sm) |
133 |
|
✗ |
throw std::invalid_argument( |
134 |
|
|
"Steering method must be of type " |
135 |
|
✗ |
"hpp::manipulation::steeringMethod::EndEffectorTrajectory"); |
136 |
|
✗ |
if (!sm->trajectoryConstraint()) |
137 |
|
✗ |
throw std::invalid_argument( |
138 |
|
✗ |
"EndEffectorTrajectory has no trajectory constraint."); |
139 |
|
✗ |
if (!sm->trajectory()) |
140 |
|
✗ |
throw std::invalid_argument("EndEffectorTrajectory has no trajectory."); |
141 |
|
|
|
142 |
|
✗ |
if (!sm->constraints() || !sm->constraints()->configProjector()) |
143 |
|
✗ |
throw std::invalid_argument( |
144 |
|
✗ |
"Steering method constraint has no ConfigProjector."); |
145 |
|
✗ |
core::ConfigProjectorPtr_t constraints(sm->constraints()->configProjector()); |
146 |
|
|
|
147 |
|
✗ |
core::ConfigValidationPtr_t cfgValidation(problem()->configValidations()); |
148 |
|
✗ |
core::PathValidationPtr_t pathValidation(problem()->pathValidation()); |
149 |
|
✗ |
core::ValidationReportPtr_t cfgReport; |
150 |
|
✗ |
core::PathValidationReportPtr_t pathReport; |
151 |
|
|
|
152 |
|
✗ |
core::interval_t timeRange(sm->timeRange()); |
153 |
|
|
|
154 |
|
|
// Generate a vector if configuration where the first one is the initial |
155 |
|
|
// configuration and the following ones are random configurations |
156 |
|
|
std::vector<core::Configuration_t> qs( |
157 |
|
✗ |
configurations(problem()->initConfig())); |
158 |
|
✗ |
if (qs.empty()) { |
159 |
|
|
hppDout(info, "Failed to generate initial configs."); |
160 |
|
✗ |
return; |
161 |
|
|
} |
162 |
|
|
|
163 |
|
|
// Generate a valid initial configuration. |
164 |
|
✗ |
bool success = false; |
165 |
|
✗ |
bool resetRightHandSide = true; |
166 |
|
|
std::size_t i; |
167 |
|
|
|
168 |
|
✗ |
vector_t times(nDiscreteSteps_ + 1); |
169 |
|
✗ |
matrix_t steps(problem()->robot()->configSize(), nDiscreteSteps_ + 1); |
170 |
|
|
|
171 |
|
|
// Discretize definition interval of the steering method into times |
172 |
|
✗ |
times[0] = timeRange.first; |
173 |
|
✗ |
for (int j = 1; j < nDiscreteSteps_; ++j) |
174 |
|
✗ |
times[j] = timeRange.first + |
175 |
|
✗ |
j * (timeRange.second - timeRange.first) / nDiscreteSteps_; |
176 |
|
✗ |
times[nDiscreteSteps_] = timeRange.second; |
177 |
|
|
|
178 |
|
|
// For each random configuration, |
179 |
|
|
// - compute initial configuration of path by projecting the random |
180 |
|
|
// configuration (initial configuration for the first time), |
181 |
|
|
// - compute following samples by projecting current sample after |
182 |
|
|
// updating right hand side. |
183 |
|
|
// If failure, try next random configuration. |
184 |
|
|
// Failure can be due to |
185 |
|
|
// - projection, |
186 |
|
|
// - collision of final configuration, |
187 |
|
|
// - validation of path (for collision mainly). |
188 |
|
✗ |
for (i = 0; i < qs.size(); ++i) { |
189 |
|
✗ |
if (resetRightHandSide) { |
190 |
|
✗ |
constraints->rightHandSideAt(times[0]); |
191 |
|
✗ |
resetRightHandSide = false; |
192 |
|
|
} |
193 |
|
✗ |
Configuration_t& q(qs[i]); |
194 |
|
✗ |
if (!constraints->apply(q)) continue; |
195 |
|
✗ |
if (!cfgValidation->validate(q, cfgReport)) continue; |
196 |
|
✗ |
resetRightHandSide = true; |
197 |
|
|
|
198 |
|
✗ |
steps.col(0) = q; |
199 |
|
✗ |
success = true; |
200 |
|
✗ |
for (int j = 1; j <= nDiscreteSteps_; ++j) { |
201 |
|
✗ |
constraints->rightHandSideAt(times[j]); |
202 |
|
|
hppDout(info, "RHS: " << setpyformat |
203 |
|
|
<< constraints->rightHandSide().transpose()); |
204 |
|
✗ |
steps.col(j) = steps.col(j - 1); |
205 |
|
✗ |
if (!constraints->apply(steps.col(j))) { |
206 |
|
|
hppDout(info, "Failed to generate destination config.\n" |
207 |
|
|
<< setpyformat << *constraints |
208 |
|
|
<< "\nq=" << one_line(q)); |
209 |
|
✗ |
success = false; |
210 |
|
✗ |
break; |
211 |
|
|
} |
212 |
|
|
} |
213 |
|
✗ |
if (!success) continue; |
214 |
|
✗ |
success = false; |
215 |
|
|
|
216 |
|
|
// Test collision of final configuration. |
217 |
|
✗ |
if (!cfgValidation->validate(steps.col(nDiscreteSteps_), cfgReport)) { |
218 |
|
|
hppDout(info, "Destination config is in collision."); |
219 |
|
✗ |
continue; |
220 |
|
|
} |
221 |
|
|
|
222 |
|
✗ |
core::PathPtr_t path = sm->projectedPath(times, steps); |
223 |
|
✗ |
if (!path) { |
224 |
|
|
hppDout(info, "Steering method failed.\n" |
225 |
|
|
<< setpyformat << "times: " << one_line(times) << '\n' |
226 |
|
|
<< "configs:\n" |
227 |
|
|
<< condensed(steps.transpose()) << '\n'); |
228 |
|
✗ |
continue; |
229 |
|
|
} |
230 |
|
|
|
231 |
|
✗ |
core::PathPtr_t validPart; |
232 |
|
✗ |
if (!pathValidation->validate(path, false, validPart, pathReport)) { |
233 |
|
|
hppDout(info, "Path is in collision."); |
234 |
|
✗ |
continue; |
235 |
|
|
} |
236 |
|
|
|
237 |
|
|
// In case of success, |
238 |
|
|
// - insert q_init as initial configuration of the roadmap, |
239 |
|
|
// - insert final configuration as goal node in the roadmap, |
240 |
|
|
// - add a roadmap edge between them and stop. |
241 |
|
✗ |
roadmap()->initNode(steps.col(0)); |
242 |
|
✗ |
core::NodePtr_t init = roadmap()->initNode(); |
243 |
|
✗ |
core::NodePtr_t goal = roadmap()->addGoalNode(steps.col(nDiscreteSteps_)); |
244 |
|
✗ |
roadmap()->addEdge(init, goal, path); |
245 |
|
✗ |
success = true; |
246 |
|
✗ |
if (feasibilityOnly_) break; |
247 |
|
|
} |
248 |
|
|
} |
249 |
|
|
|
250 |
|
✗ |
std::vector<core::Configuration_t> EndEffectorTrajectory::configurations( |
251 |
|
|
const core::Configuration_t& q_init) { |
252 |
|
✗ |
if (!ikSolverInit_) { |
253 |
|
✗ |
std::vector<core::Configuration_t> configs(nRandomConfig_ + 1); |
254 |
|
✗ |
configs[0] = q_init; |
255 |
|
✗ |
for (int i = 1; i < nRandomConfig_ + 1; ++i) |
256 |
|
✗ |
problem()->configurationShooter()->shoot(configs[i]); |
257 |
|
✗ |
return configs; |
258 |
|
|
} |
259 |
|
|
|
260 |
|
|
// TODO Compute the target and call ikSolverInit_ |
261 |
|
|
// See https://gepgitlab.laas.fr/airbus-xtct/hpp_airbus_xtct for an |
262 |
|
|
// example using IKFast. |
263 |
|
✗ |
throw std::runtime_error( |
264 |
|
✗ |
"Using an IkSolverInitialization is not implemented yet"); |
265 |
|
|
} |
266 |
|
|
|
267 |
|
✗ |
EndEffectorTrajectory::EndEffectorTrajectory( |
268 |
|
✗ |
const core::ProblemConstPtr_t& problem) |
269 |
|
✗ |
: core::PathPlanner(problem) {} |
270 |
|
|
|
271 |
|
✗ |
EndEffectorTrajectory::EndEffectorTrajectory( |
272 |
|
✗ |
const core::ProblemConstPtr_t& problem, const core::RoadmapPtr_t& roadmap) |
273 |
|
✗ |
: core::PathPlanner(problem, roadmap) {} |
274 |
|
|
|
275 |
|
✗ |
void EndEffectorTrajectory::checkFeasibilityOnly(bool enable) { |
276 |
|
✗ |
feasibilityOnly_ = enable; |
277 |
|
|
} |
278 |
|
|
|
279 |
|
✗ |
void EndEffectorTrajectory::init(const EndEffectorTrajectoryWkPtr_t& weak) { |
280 |
|
✗ |
core::PathPlanner::init(weak); |
281 |
|
✗ |
weak_ = weak; |
282 |
|
✗ |
nRandomConfig_ = 10; |
283 |
|
✗ |
nDiscreteSteps_ = 1; |
284 |
|
✗ |
feasibilityOnly_ = true; |
285 |
|
|
} |
286 |
|
|
} // namespace pathPlanner |
287 |
|
|
} // namespace manipulation |
288 |
|
|
} // namespace hpp |
289 |
|
|
|