Line |
Branch |
Exec |
Source |
1 |
|
|
// Copyright (c) 2019, LAAS-CNRS |
2 |
|
|
// Authors: Joseph Mirabel (joseph.mirabel@laas.fr) |
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/interpolated-path.hh> |
33 |
|
|
#include <hpp/core/path-vector.hh> |
34 |
|
|
#include <hpp/core/path.hh> |
35 |
|
|
#include <hpp/core/problem.hh> |
36 |
|
|
#include <hpp/core/straight-path.hh> |
37 |
|
|
#include <hpp/manipulation/steering-method/end-effector-trajectory.hh> |
38 |
|
|
#include <hpp/pinocchio/device.hh> |
39 |
|
|
#include <hpp/pinocchio/urdf/util.hh> |
40 |
|
|
#include <hpp/pinocchio/util.hh> |
41 |
|
|
#include <hpp/util/indent.hh> |
42 |
|
|
|
43 |
|
|
namespace hpp { |
44 |
|
|
namespace manipulation { |
45 |
|
|
namespace steeringMethod { |
46 |
|
|
namespace { |
47 |
|
|
template <bool SE3> |
48 |
|
|
class FunctionFromPath : public constraints::DifferentiableFunction { |
49 |
|
|
public: |
50 |
|
✗ |
FunctionFromPath(const PathPtr_t& p) |
51 |
|
|
: DifferentiableFunction( |
52 |
|
|
1, 1, |
53 |
|
✗ |
SE3 ? LiegroupSpace::R3xSO3() : LiegroupSpace::Rn(p->outputSize())), |
54 |
|
✗ |
path_(p) { |
55 |
|
✗ |
assert(!SE3 || (p->outputSize() == 7 && p->outputDerivativeSize() == 6)); |
56 |
|
|
} |
57 |
|
|
|
58 |
|
|
const PathPtr_t& path() const { return path_; } |
59 |
|
|
|
60 |
|
✗ |
std::ostream& print(std::ostream& os) const { |
61 |
|
✗ |
return os << (SE3 ? "FunctionFromSE3Path: " : "FunctionFromPath: ") |
62 |
|
✗ |
<< path_->timeRange().first << ", " << path_->timeRange().second; |
63 |
|
|
} |
64 |
|
|
|
65 |
|
|
protected: |
66 |
|
✗ |
void impl_compute(core::LiegroupElementRef result, vectorIn_t arg) const { |
67 |
|
✗ |
bool success = path_->eval(result.vector(), arg[0]); |
68 |
|
✗ |
if (!success) { |
69 |
|
|
hppDout(warning, "Failed to evaluate path at param " |
70 |
|
|
<< arg[0] << incindent << iendl << *path_ |
71 |
|
|
<< decindent); |
72 |
|
|
} |
73 |
|
|
} |
74 |
|
|
|
75 |
|
✗ |
void impl_jacobian(matrixOut_t jacobian, vectorIn_t arg) const { |
76 |
|
✗ |
path_->derivative(jacobian.col(0), arg[0], 1); |
77 |
|
|
} |
78 |
|
|
|
79 |
|
|
private: |
80 |
|
|
PathPtr_t path_; |
81 |
|
|
}; |
82 |
|
|
} // namespace |
83 |
|
|
|
84 |
|
✗ |
PathPtr_t EndEffectorTrajectory::makePiecewiseLinearTrajectory( |
85 |
|
|
matrixIn_t points, vectorIn_t weights) { |
86 |
|
✗ |
if (points.cols() != 7) |
87 |
|
✗ |
throw std::invalid_argument("The input matrix should have 7 columns"); |
88 |
|
✗ |
if (weights.size() != 6) |
89 |
|
✗ |
throw std::invalid_argument("The weights vector should have 6 elements"); |
90 |
|
✗ |
LiegroupSpacePtr_t se3 = LiegroupSpace::SE3(); |
91 |
|
✗ |
core::PathVectorPtr_t path = core::PathVector::create(7, 6); |
92 |
|
✗ |
if (points.rows() == 1) |
93 |
|
✗ |
path->appendPath(core::StraightPath::create( |
94 |
|
✗ |
se3, points.row(0), points.row(0), interval_t(0, 0))); |
95 |
|
|
else |
96 |
|
✗ |
for (size_type i = 1; i < points.rows(); ++i) { |
97 |
|
✗ |
value_type d = (se3->elementConstRef(points.row(i)) - |
98 |
|
✗ |
se3->elementConstRef(points.row(i - 1))) |
99 |
|
✗ |
.cwiseProduct(weights) |
100 |
|
✗ |
.norm(); |
101 |
|
✗ |
path->appendPath(core::StraightPath::create( |
102 |
|
✗ |
se3, points.row(i - 1), points.row(i), interval_t(0, d))); |
103 |
|
|
} |
104 |
|
✗ |
return path; |
105 |
|
|
} |
106 |
|
|
|
107 |
|
✗ |
void EndEffectorTrajectory::trajectoryConstraint( |
108 |
|
|
const constraints::ImplicitPtr_t& ic) { |
109 |
|
✗ |
constraint_ = ic; |
110 |
|
✗ |
if (eeTraj_) trajectory(eeTraj_, timeRange_); |
111 |
|
|
} |
112 |
|
|
|
113 |
|
✗ |
void EndEffectorTrajectory::trajectory(const PathPtr_t& eeTraj, |
114 |
|
|
bool se3Output) { |
115 |
|
✗ |
if (se3Output) |
116 |
|
✗ |
trajectory(DifferentiableFunctionPtr_t(new FunctionFromPath<true>(eeTraj)), |
117 |
|
✗ |
eeTraj->timeRange()); |
118 |
|
|
else |
119 |
|
✗ |
trajectory(DifferentiableFunctionPtr_t(new FunctionFromPath<false>(eeTraj)), |
120 |
|
✗ |
eeTraj->timeRange()); |
121 |
|
|
} |
122 |
|
|
|
123 |
|
✗ |
void EndEffectorTrajectory::trajectory( |
124 |
|
|
const DifferentiableFunctionPtr_t& eeTraj, const interval_t& tr) { |
125 |
|
✗ |
assert(eeTraj->inputSize() == 1); |
126 |
|
✗ |
assert(eeTraj->inputDerivativeSize() == 1); |
127 |
|
✗ |
eeTraj_ = eeTraj; |
128 |
|
✗ |
timeRange_ = tr; |
129 |
|
|
|
130 |
|
✗ |
if (!constraint_) return; |
131 |
|
|
|
132 |
|
✗ |
constraint_->rightHandSideFunction(eeTraj_); |
133 |
|
|
} |
134 |
|
|
|
135 |
|
✗ |
PathPtr_t EndEffectorTrajectory::impl_compute(ConfigurationIn_t q1, |
136 |
|
|
ConfigurationIn_t q2) const { |
137 |
|
|
try { |
138 |
|
✗ |
core::ConstraintSetPtr_t c(getUpdatedConstraints()); |
139 |
|
|
|
140 |
|
✗ |
return core::StraightPath::create(problem()->robot(), q1, q2, timeRange_, |
141 |
|
✗ |
c); |
142 |
|
✗ |
} catch (const std::exception& e) { |
143 |
|
✗ |
std::ostringstream os; |
144 |
|
✗ |
os << "steeringMethod::EndEffectorTrajectory failed: " << e.what() |
145 |
|
✗ |
<< std::endl; |
146 |
|
✗ |
os << "time range: [" << timeRange_.first << ", " << timeRange_.second |
147 |
|
✗ |
<< "]\n"; |
148 |
|
✗ |
if (eeTraj_) |
149 |
|
✗ |
os << (*eeTraj_)(vector_t::Constant(1, timeRange_.first)) << '\n' |
150 |
|
✗ |
<< (*eeTraj_)(vector_t::Constant(1, timeRange_.second)) << std::endl; |
151 |
|
✗ |
if (constraints()) os << *constraints() << std::endl; |
152 |
|
✗ |
throw std::runtime_error(os.str().c_str()); |
153 |
|
|
} |
154 |
|
|
} |
155 |
|
|
|
156 |
|
✗ |
PathPtr_t EndEffectorTrajectory::projectedPath(vectorIn_t times, |
157 |
|
|
matrixIn_t configs) const { |
158 |
|
✗ |
core::ConstraintSetPtr_t c(getUpdatedConstraints()); |
159 |
|
|
|
160 |
|
✗ |
size_type N = configs.cols(); |
161 |
|
✗ |
if (timeRange_.first != times[0] || timeRange_.second != times[N - 1]) { |
162 |
|
✗ |
HPP_THROW(std::logic_error, |
163 |
|
|
"Time range (" << timeRange_.first << ", " << timeRange_.second |
164 |
|
|
<< ") does not match configuration " |
165 |
|
|
"times (" |
166 |
|
|
<< times[0] << ", " << times[N - 1]); |
167 |
|
|
} |
168 |
|
|
|
169 |
|
|
using core::InterpolatedPath; |
170 |
|
|
using core::InterpolatedPathPtr_t; |
171 |
|
|
|
172 |
|
|
InterpolatedPathPtr_t path = InterpolatedPath::create( |
173 |
|
✗ |
problem()->robot(), configs.col(0), configs.col(N - 1), timeRange_, c); |
174 |
|
|
|
175 |
|
✗ |
for (size_type i = 1; i < configs.cols() - 1; ++i) |
176 |
|
✗ |
path->insert(times[i], configs.col(i)); |
177 |
|
|
|
178 |
|
✗ |
return path; |
179 |
|
|
} |
180 |
|
|
|
181 |
|
✗ |
core::ConstraintSetPtr_t EndEffectorTrajectory::getUpdatedConstraints() const { |
182 |
|
✗ |
if (!eeTraj_) |
183 |
|
✗ |
throw std::logic_error("EndEffectorTrajectory not initialized."); |
184 |
|
|
|
185 |
|
|
// Update (or check) the constraints |
186 |
|
✗ |
core::ConstraintSetPtr_t c(constraints()); |
187 |
|
✗ |
if (!c || !c->configProjector()) { |
188 |
|
✗ |
throw std::logic_error( |
189 |
|
|
"EndEffectorTrajectory steering method must " |
190 |
|
✗ |
"have a ConfigProjector"); |
191 |
|
|
} |
192 |
|
✗ |
ConfigProjectorPtr_t cp(c->configProjector()); |
193 |
|
|
|
194 |
|
✗ |
const core::NumericalConstraints_t& ncs = cp->numericalConstraints(); |
195 |
|
✗ |
bool ok = false; |
196 |
|
✗ |
for (std::size_t i = 0; i < ncs.size(); ++i) { |
197 |
|
✗ |
if (ncs[i] == constraint_) { |
198 |
|
✗ |
ok = true; |
199 |
|
✗ |
break; // Same pointer |
200 |
|
|
} |
201 |
|
|
// Here, we do not check the right hand side on purpose. |
202 |
|
|
// if (*ncs[i] == *constraint_) { |
203 |
|
✗ |
if (ncs[i]->functionPtr() == constraint_->functionPtr() && |
204 |
|
✗ |
ncs[i]->comparisonType() == constraint_->comparisonType()) { |
205 |
|
✗ |
ok = true; |
206 |
|
|
// TODO We should only modify the path constraint. |
207 |
|
|
// However, only the pointers to implicit constraints are copied |
208 |
|
|
// while we would like the implicit constraints to be copied as well. |
209 |
|
✗ |
ncs[i]->rightHandSideFunction(eeTraj_); |
210 |
|
✗ |
break; // logically identical |
211 |
|
|
} |
212 |
|
|
} |
213 |
|
✗ |
if (!ok) { |
214 |
|
✗ |
HPP_THROW(std::logic_error, |
215 |
|
|
"EndEffectorTrajectory could not find " |
216 |
|
|
"constraint " |
217 |
|
|
<< constraint_->function()); |
218 |
|
|
} |
219 |
|
✗ |
return c; |
220 |
|
|
} |
221 |
|
|
} // namespace steeringMethod |
222 |
|
|
} // namespace manipulation |
223 |
|
|
} // namespace hpp |
224 |
|
|
|