Line |
Branch |
Exec |
Source |
1 |
|
|
// Copyright (c) 2015, LAAS-CNRS |
2 |
|
|
// Authors: Florent Lamiraux |
3 |
|
|
// |
4 |
|
|
|
5 |
|
|
// Redistribution and use in source and binary forms, with or without |
6 |
|
|
// modification, are permitted provided that the following conditions are |
7 |
|
|
// met: |
8 |
|
|
// |
9 |
|
|
// 1. Redistributions of source code must retain the above copyright |
10 |
|
|
// notice, this list of conditions and the following disclaimer. |
11 |
|
|
// |
12 |
|
|
// 2. Redistributions in binary form must reproduce the above copyright |
13 |
|
|
// notice, this list of conditions and the following disclaimer in the |
14 |
|
|
// documentation and/or other materials provided with the distribution. |
15 |
|
|
// |
16 |
|
|
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
17 |
|
|
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
18 |
|
|
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR |
19 |
|
|
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT |
20 |
|
|
// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, |
21 |
|
|
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT |
22 |
|
|
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, |
23 |
|
|
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY |
24 |
|
|
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT |
25 |
|
|
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE |
26 |
|
|
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH |
27 |
|
|
// DAMAGE. |
28 |
|
|
|
29 |
|
|
#ifndef HPP_CONSTRAINTS_EXPLICIT_HH |
30 |
|
|
#define HPP_CONSTRAINTS_EXPLICIT_HH |
31 |
|
|
|
32 |
|
|
#include <hpp/constraints/implicit.hh> |
33 |
|
|
|
34 |
|
|
namespace hpp { |
35 |
|
|
namespace constraints { |
36 |
|
|
/// \addtogroup constraints |
37 |
|
|
/// \{ |
38 |
|
|
|
39 |
|
|
/** Explicit numerical constraint |
40 |
|
|
|
41 |
|
|
An explicit numerical constraint is a constraint such that some |
42 |
|
|
configuration variables called \b output are function of the |
43 |
|
|
others called \b input. |
44 |
|
|
|
45 |
|
|
Let |
46 |
|
|
\li \f$(ic_{1}, \cdots, ic_{n_{ic}})\f$ be the list of indices |
47 |
|
|
corresponding to ordered input configuration variables, |
48 |
|
|
\li \f$(oc_{1}, \cdots, oc_{n_{oc}})\f$ be the list of indices |
49 |
|
|
corresponding to ordered output configuration variables, |
50 |
|
|
\li \f$(iv_{1}, \cdots, iv_{n_{iv}})\f$ be the list of indices |
51 |
|
|
corresponding to ordered input degrees of freedom, |
52 |
|
|
\li \f$(ov_{1}, \cdots, ov_{n_{ov}})\f$ be the list of indices |
53 |
|
|
corresponding to ordered output degrees of freedom. |
54 |
|
|
|
55 |
|
|
Recall that degrees of freedom refer to velocity vectors. |
56 |
|
|
|
57 |
|
|
Let us notice that \f$n_{ic} + n_{oc}\f$ is less than the robot |
58 |
|
|
configuration size, and \f$n_{iv} + n_{ov}\f$ is less than the velocity |
59 |
|
|
size. Some degrees of freedom may indeed be neither input nor output. |
60 |
|
|
|
61 |
|
|
Then the differential function is of the form |
62 |
|
|
\f{eqnarray*}{ |
63 |
|
|
\mathbf{q}_{out} - g \left(\mathbf{q}_{in}\right) |
64 |
|
|
\ \ &\mbox{with}& |
65 |
|
|
\mathbf{q}_{out} = \left(q_{oc_{1}} \cdots q_{oc_{n_{oc}}}\right)^T, |
66 |
|
|
\ \ \ \mathbf{q}_{in} = (q_{ic_{1}} \cdots q_{ic_{n_{ic}}})^T |
67 |
|
|
\f} |
68 |
|
|
It is straightforward that an equality constraint with this function can |
69 |
|
|
solved explicitely: |
70 |
|
|
\f{align*}{ |
71 |
|
|
\mathbf{q}_{out} &- g \left(\mathbf{q}_{in}\right) = rhs \\ |
72 |
|
|
& \mbox {if and only if}\\ |
73 |
|
|
\mathbf{q}_{out} &= g \left(\mathbf{q}_{in}\right) + rhs \\ |
74 |
|
|
\f} |
75 |
|
|
|
76 |
|
|
If function \f$f\f$ takes values in a Lie group (SO(2), SO(3)), |
77 |
|
|
the above "+" between a Lie group element and a tangent vector |
78 |
|
|
has to be undestood as the integration of the constant velocity from |
79 |
|
|
the Lie group element: |
80 |
|
|
\f{equation*}{ |
81 |
|
|
\mathbf{q} + \mathbf{v} = \mathbf{q}.\exp (\mathbf{v}) |
82 |
|
|
\f} |
83 |
|
|
where \f$\mathbf{q}\f$ is a Lie group element and \f$\mathbf{v}\f$ is a |
84 |
|
|
tangent vector. |
85 |
|
|
|
86 |
|
|
Considered as a Implicit instance, the expression of the Jacobian of |
87 |
|
|
the DifferentiableFunction above depends on the output space of function |
88 |
|
|
\f$f\f$. The rows corresponding to values in a vector space are |
89 |
|
|
expressed as follows. |
90 |
|
|
|
91 |
|
|
for any index \f$i\f$ between 0 and the size of velocity vectors, either |
92 |
|
|
\li \f$\dot{q}_i\f$ is an input degree of freedom: |
93 |
|
|
\f$\exists j\f$ integer, \f$1 \leq j \leq n_{iv}\f$ such that |
94 |
|
|
\f$i=iv_{j}\f$, |
95 |
|
|
\li \f$\dot{q}_i\f$ is an output degree of freedom: |
96 |
|
|
\f$\exists j\f$ integer, \f$1\leq j \leq n_{ov}\f$ such that |
97 |
|
|
\f$i=ov_{j}\f$, or |
98 |
|
|
\li \f$\dot{q}_i\f$ neither input nor output. In this case, the |
99 |
|
|
corresponding column is equal to 0. |
100 |
|
|
\f{equation*}{ |
101 |
|
|
J = \left(\begin{array}{cccccccccccc} |
102 |
|
|
\cdots & ov_1 & \cdots & iv_{1} & \cdots & ov_2 & \cdots & iv_2 & \cdots & |
103 |
|
|
ov_{n_{ov}} & \cdots \\ |
104 |
|
|
& 1 & & & & 0 & & & & |
105 |
|
|
& \\ |
106 |
|
|
& 0 & & & & 1 & & & & |
107 |
|
|
& \\ |
108 |
|
|
& & & -\frac{\partial g}{q_1} & & & & -\frac{\partial |
109 |
|
|
g}{q_2} \\ |
110 |
|
|
&&&&&\\ |
111 |
|
|
& 0 & & & & 0 & & & & 1 |
112 |
|
|
\end{array}\right) |
113 |
|
|
\f} |
114 |
|
|
The rows corresponding to values in SO(3) have the following expression. |
115 |
|
|
\f{equation*}{ |
116 |
|
|
J = \left(\begin{array}{cccccccccccc} |
117 |
|
|
ov_1 \ ov_2 \ ov_3 & iv_1 \cdots iv_{n_{iv}} \\ |
118 |
|
|
J_{log}(R_{g}^T R_{out}) & -J_{log}(R_{g}^T R_{out})R_{out}^T R_{g} |
119 |
|
|
\frac{\partial g}{\partial q_{in}} \end{array}\right) \f} where \li |
120 |
|
|
\f$R_{out}\f$ is the rotation matrix corresponding to unit quaternion |
121 |
|
|
\f$(q_{oc1},q_{oc2},q_{oc3},q_{oc4})\f$, \li \f$R_{g}\f$ is the rotation matrix |
122 |
|
|
corresponding to the part of the output value of \f$f\f$ corresponding to SO(3), |
123 |
|
|
\li \f$J_{log}\f$ is the Jacobian matrix of function that associates |
124 |
|
|
to a rotation matrix \f$R\f$ the vector \f$\omega\f$ such that |
125 |
|
|
\f{equation*}{ |
126 |
|
|
R = \exp (\left[\omega\right]_{\times}) |
127 |
|
|
\f} |
128 |
|
|
|
129 |
|
|
|
130 |
|
|
|
131 |
|
|
**/ |
132 |
|
|
class HPP_CONSTRAINTS_DLLAPI Explicit : public Implicit { |
133 |
|
|
public: |
134 |
|
|
/// Copy object and return shared pointer to copy |
135 |
|
|
virtual ImplicitPtr_t copy() const; |
136 |
|
|
|
137 |
|
|
/// Create instance and return shared pointer |
138 |
|
|
/// |
139 |
|
|
/// \param configSpace Configuration space on which the constraint is |
140 |
|
|
/// defined, |
141 |
|
|
/// \param function relation between input configuration variables and |
142 |
|
|
/// output configuration variables, |
143 |
|
|
/// \param inputConf set of integer intervals defining indices |
144 |
|
|
/// \f$(ic_{1}, \cdots, ic_{n_{ic}})\f$, |
145 |
|
|
/// \param outputConf set of integer intervals defining indices |
146 |
|
|
/// \f$(oc_{1}, \cdots, oc_{n_{oc}})\f$, |
147 |
|
|
/// \param inputVelocity set of integer defining indices |
148 |
|
|
/// \f$(iv_{1}, \cdots, iv_{n_{iv}})\f$. |
149 |
|
|
/// \param outputVelocity set of integer defining indices |
150 |
|
|
/// \f$(ov_{1}, \cdots, ov_{n_{ov}})\f$. |
151 |
|
|
/// \param mask mask defining which components of the error are |
152 |
|
|
/// taken into account to determine whether the constraint |
153 |
|
|
/// is satisfied (See parent class for details). |
154 |
|
|
static ExplicitPtr_t create( |
155 |
|
|
const LiegroupSpacePtr_t& configSpace, |
156 |
|
|
const DifferentiableFunctionPtr_t& function, const segments_t& inputConf, |
157 |
|
|
const segments_t& outputConf, const segments_t& inputVelocity, |
158 |
|
|
const segments_t& outputVelocity, |
159 |
|
|
const ComparisonTypes_t& comp = ComparisonTypes_t(), |
160 |
|
|
std::vector<bool> mask = std::vector<bool>()); |
161 |
|
|
|
162 |
|
|
/// Create a copy and return shared pointer |
163 |
|
|
static ExplicitPtr_t createCopy(const ExplicitPtr_t& other); |
164 |
|
|
|
165 |
|
|
/// Function that maps input to output |
166 |
|
|
/// \return function \f$f\f$. |
167 |
|
40229 |
DifferentiableFunctionPtr_t explicitFunction() const { |
168 |
|
40229 |
return inputToOutput_; |
169 |
|
|
} |
170 |
|
|
|
171 |
|
|
/// Get output configuration variables |
172 |
|
26710 |
const segments_t& outputConf() const { return outputConf_; } |
173 |
|
|
/// Get output degrees of freedom |
174 |
|
19690 |
const segments_t& outputVelocity() const { return outputVelocity_; } |
175 |
|
|
/// Get input configuration variables |
176 |
|
34220 |
const segments_t& inputConf() const { return inputConf_; } |
177 |
|
|
/// Get input degrees of freedom |
178 |
|
26192 |
const segments_t& inputVelocity() const { return inputVelocity_; } |
179 |
|
|
/// Compute the value of the output configuration variables |
180 |
|
|
/// \param qin input configuration variables, |
181 |
|
|
/// \param rhs right hand side of constraint |
182 |
|
|
/// |
183 |
|
|
/// The default implementation computes |
184 |
|
|
/// \f{equation} |
185 |
|
|
/// g \left((q_{ic_{1}} \cdots q_{ic_{n_{ic}}})^T\right) + rhs |
186 |
|
|
/// \f} |
187 |
|
|
virtual void outputValue(LiegroupElementRef result, vectorIn_t qin, |
188 |
|
|
LiegroupElementConstRef rhs) const; |
189 |
|
|
|
190 |
|
|
/// Compute Jacobian of output value |
191 |
|
|
/// |
192 |
|
|
/// \f{eqnarray*} |
193 |
|
|
/// J &=& \frac{\partial}{\partial\mathbf{q}_{in}}\left(g(\mathbf{q}_{in}) |
194 |
|
|
/// + rhs\right). |
195 |
|
|
/// \f} |
196 |
|
|
/// \param qin vector of input variables, |
197 |
|
|
/// \param g_value \f$f(\mathbf{q}_{in})\f$ provided to avoid |
198 |
|
|
/// recomputation, |
199 |
|
|
/// \param rhs right hand side (of implicit formulation). |
200 |
|
|
virtual void jacobianOutputValue(vectorIn_t qin, |
201 |
|
|
LiegroupElementConstRef g_value, |
202 |
|
|
LiegroupElementConstRef rhs, |
203 |
|
|
matrixOut_t jacobian) const; |
204 |
|
|
|
205 |
|
|
protected: |
206 |
|
|
/// Constructor |
207 |
|
|
/// |
208 |
|
|
/// \param configSpace Configuration space on which the constraint is |
209 |
|
|
/// defined, |
210 |
|
|
/// \param function relation between input configuration variables and |
211 |
|
|
/// output configuration variables, |
212 |
|
|
/// \param inputConf set of integer intervals defining indices |
213 |
|
|
/// \f$(ic_{1}, \cdots, ic_{n_{ic}})\f$, |
214 |
|
|
/// \param outputConf set of integer intervals defining indices |
215 |
|
|
/// \f$(oc_{1}, \cdots, oc_{n_{oc}})\f$, |
216 |
|
|
/// \param inputVelocity set of integer defining indices |
217 |
|
|
/// \f$(iv_{1}, \cdots, iv_{n_{iv}})\f$. |
218 |
|
|
/// \param outputVelocity set of integer defining indices |
219 |
|
|
/// \f$(ov_{1}, \cdots, ov_{n_{ov}})\f$. |
220 |
|
|
/// \param mask mask defining which components of the error are |
221 |
|
|
/// taken into account to determine whether the constraint |
222 |
|
|
/// is satisfied (See parent class for details). |
223 |
|
|
Explicit(const LiegroupSpacePtr_t& configSpace, |
224 |
|
|
const DifferentiableFunctionPtr_t& function, |
225 |
|
|
const segments_t& inputConf, const segments_t& outputConf, |
226 |
|
|
const segments_t& inputVelocity, const segments_t& outputVelocity, |
227 |
|
|
const ComparisonTypes_t& comp, std::vector<bool> mask); |
228 |
|
|
|
229 |
|
|
/// \copydoc Explicit (const LiegroupSpacePtr_t&, const |
230 |
|
|
/// DifferentiableFunctionPtr_t&, const segments_t& inputConf, const |
231 |
|
|
/// segments_t& outputConf, const segments_t& inputVelocity, const |
232 |
|
|
/// segments_t&, const ComparisonTypes_t&); \param implicitFunction |
233 |
|
|
/// differentiable function of the implicit |
234 |
|
|
/// formulation if different from default expression |
235 |
|
|
/// \f{equation}{ |
236 |
|
|
/// \mathbf{q}_{out} - g \left(\mathbf{q}_{in}\right), |
237 |
|
|
/// \f} |
238 |
|
|
Explicit(const DifferentiableFunctionPtr_t& implicitFunction, |
239 |
|
|
const DifferentiableFunctionPtr_t& function, |
240 |
|
|
const segments_t& inputConf, const segments_t& outputConf, |
241 |
|
|
const segments_t& inputVelocity, const segments_t& outputVelocity, |
242 |
|
|
const ComparisonTypes_t& comp, std::vector<bool> mask); |
243 |
|
|
|
244 |
|
|
/// Copy constructor |
245 |
|
|
Explicit(const Explicit& other); |
246 |
|
|
|
247 |
|
|
bool isEqual(const Implicit& other, bool swapAndTest) const; |
248 |
|
|
|
249 |
|
|
// Store weak pointer to itself |
250 |
|
|
void init(const ExplicitWkPtr_t& weak); |
251 |
|
|
|
252 |
|
|
protected: |
253 |
|
|
// Relation between input and output configuration variables |
254 |
|
|
DifferentiableFunctionPtr_t inputToOutput_; |
255 |
|
|
segments_t inputConf_; |
256 |
|
|
segments_t outputConf_; |
257 |
|
|
segments_t inputVelocity_; |
258 |
|
|
segments_t outputVelocity_; |
259 |
|
|
|
260 |
|
1 |
Explicit() {} |
261 |
|
|
|
262 |
|
|
private: |
263 |
|
|
ExplicitWkPtr_t weak_; |
264 |
|
|
|
265 |
|
|
HPP_SERIALIZABLE(); |
266 |
|
|
}; // class Explicit |
267 |
|
|
/// \} |
268 |
|
|
} // namespace constraints |
269 |
|
|
} // namespace hpp |
270 |
|
|
|
271 |
|
12 |
BOOST_CLASS_EXPORT_KEY(hpp::constraints::Explicit) |
272 |
|
|
|
273 |
|
|
#endif // HPP_CONSTRAINTS_EXPLICIT_HH |
274 |
|
|
|