Directory: | ./ |
---|---|
File: | include/hpp/constraints/affine-function.hh |
Date: | 2025-05-05 12:19:30 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 50 | 64 | 78.1% |
Branches: | 48 | 106 | 45.3% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | // Copyright (c) 2017, Joseph Mirabel | ||
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 | #ifndef HPP_CONSTRAINTS_AFFINE_FUNCTION_HH | ||
30 | #define HPP_CONSTRAINTS_AFFINE_FUNCTION_HH | ||
31 | |||
32 | #include <hpp/constraints/config.hh> | ||
33 | #include <hpp/constraints/differentiable-function.hh> | ||
34 | #include <hpp/constraints/fwd.hh> | ||
35 | |||
36 | namespace hpp { | ||
37 | namespace constraints { | ||
38 | |||
39 | /// \addtogroup constraints | ||
40 | /// \{ | ||
41 | |||
42 | /// Identity function | ||
43 | /// \f$ q_{out} = q_{in} \f$ | ||
44 | /// | ||
45 | /// \todo should we handle specifically this function is the solvers ? | ||
46 | class HPP_CONSTRAINTS_DLLAPI Identity | ||
47 | : public constraints::DifferentiableFunction { | ||
48 | public: | ||
49 | 1 | static IdentityPtr_t create(const LiegroupSpacePtr_t space, | |
50 | const std::string& name) { | ||
51 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
|
1 | IdentityPtr_t ptr(new Identity(space, name)); |
52 | 1 | return ptr; | |
53 | } | ||
54 | |||
55 | 1 | Identity(const LiegroupSpacePtr_t space, const std::string& name) | |
56 |
1/2✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
|
1 | : DifferentiableFunction(space->nq(), space->nv(), space, name) {} |
57 | |||
58 | protected: | ||
59 | ✗ | void impl_compute(LiegroupElementRef y, vectorIn_t arg) const { | |
60 | ✗ | y.vector() = arg; | |
61 | } | ||
62 | |||
63 | ✗ | void impl_jacobian(matrixOut_t J, vectorIn_t) const { J.setIdentity(); } | |
64 | |||
65 | ✗ | bool isEqual(const DifferentiableFunction& other) const { | |
66 | ✗ | dynamic_cast<const Identity&>(other); | |
67 | ✗ | if (!DifferentiableFunction::isEqual(other)) return false; | |
68 | |||
69 | ✗ | return true; | |
70 | } | ||
71 | |||
72 | private: | ||
73 | ✗ | Identity() {} | |
74 | HPP_SERIALIZABLE(); | ||
75 | }; // class Identity | ||
76 | |||
77 | /// Affine function | ||
78 | /// \f$ f(q) = J * q + b \f$ | ||
79 | /// | ||
80 | /// \todo should we handle specifically this function is the solvers ? | ||
81 | class HPP_CONSTRAINTS_DLLAPI AffineFunction : public DifferentiableFunction { | ||
82 | public: | ||
83 | 1026 | static AffineFunctionPtr_t create(const matrixIn_t& J, | |
84 | const std::string name = "LinearFunction") { | ||
85 |
3/6✓ Branch 2 taken 1026 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1026 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1026 times.
✗ Branch 9 not taken.
|
1026 | return AffineFunctionPtr_t(new AffineFunction(J, name)); |
86 | } | ||
87 | |||
88 | 3 | static AffineFunctionPtr_t create(const matrixIn_t& J, const vectorIn_t& b, | |
89 | const std::string name = "LinearFunction") { | ||
90 |
3/6✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 3 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 3 times.
✗ Branch 9 not taken.
|
3 | return AffineFunctionPtr_t(new AffineFunction(J, b, name)); |
91 | } | ||
92 | |||
93 | protected: | ||
94 | 1028 | AffineFunction(const matrixIn_t& J, const std::string name = "LinearFunction") | |
95 |
1/2✓ Branch 2 taken 1028 times.
✗ Branch 3 not taken.
|
2056 | : DifferentiableFunction(J.cols(), J.cols(), LiegroupSpace::Rn(J.rows()), |
96 | name), | ||
97 | 1028 | J_(J), | |
98 |
4/8✓ Branch 4 taken 1028 times.
✗ Branch 5 not taken.
✓ Branch 8 taken 1028 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 1028 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1028 times.
✗ Branch 16 not taken.
|
3084 | b_(vector_t::Zero(J.rows())) { |
99 |
1/2✓ Branch 1 taken 1028 times.
✗ Branch 2 not taken.
|
1028 | init(); |
100 | 1028 | } | |
101 | |||
102 | 3 | AffineFunction(const matrixIn_t& J, const vectorIn_t& b, | |
103 | const std::string name = "LinearFunction") | ||
104 |
1/2✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
|
6 | : DifferentiableFunction(J.cols(), J.cols(), LiegroupSpace::Rn(J.rows()), |
105 | name), | ||
106 | 3 | J_(J), | |
107 |
3/6✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
✓ Branch 8 taken 3 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 3 times.
✗ Branch 12 not taken.
|
9 | b_(b) { |
108 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | init(); |
109 | 3 | } | |
110 | |||
111 | 8039 | bool isEqual(const DifferentiableFunction& other) const { | |
112 | const AffineFunction& castother = | ||
113 |
2/2✓ Branch 0 taken 8026 times.
✓ Branch 1 taken 13 times.
|
8039 | dynamic_cast<const AffineFunction&>(other); |
114 |
2/2✓ Branch 1 taken 6 times.
✓ Branch 2 taken 8020 times.
|
8026 | if (!DifferentiableFunction::isEqual(other)) return false; |
115 | |||
116 |
1/2✗ Branch 1 not taken.
✓ Branch 2 taken 8020 times.
|
8020 | if (J_ != castother.J_) return false; |
117 |
1/2✗ Branch 1 not taken.
✓ Branch 2 taken 8020 times.
|
8020 | if (b_ != castother.b_) return false; |
118 | |||
119 | 8020 | return true; | |
120 | } | ||
121 | |||
122 | private: | ||
123 | /// User implementation of function evaluation | ||
124 | 12946 | void impl_compute(LiegroupElementRef y, vectorIn_t x) const { | |
125 |
3/6✓ Branch 2 taken 12946 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 12946 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 12946 times.
✗ Branch 10 not taken.
|
12946 | y.vector().noalias() = J_ * x + b_; |
126 | 12946 | } | |
127 | |||
128 | 12809 | void impl_jacobian(matrixOut_t jacobian, vectorIn_t) const { jacobian = J_; } | |
129 | |||
130 | 1031 | void init() { | |
131 |
1/2✗ Branch 2 not taken.
✓ Branch 3 taken 1031 times.
|
1031 | assert(J_.rows() == b_.rows()); |
132 |
5/10✓ Branch 1 taken 1031 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1031 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1031 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1031 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1031 times.
✗ Branch 14 not taken.
|
1031 | activeParameters_ = (J_.array() != 0).colwise().any(); |
133 | 1031 | activeDerivativeParameters_ = activeParameters_; | |
134 | 1031 | } | |
135 | |||
136 | const matrix_t J_; | ||
137 | const vector_t b_; | ||
138 | |||
139 | ✗ | AffineFunction() {} | |
140 | HPP_SERIALIZABLE(); | ||
141 | }; // class AffineFunction | ||
142 | |||
143 | /// Constant function | ||
144 | /// \f$ f(q) = C \f$ | ||
145 | /// | ||
146 | /// \todo should we handle specifically this function is the solvers ? | ||
147 | struct HPP_CONSTRAINTS_DLLAPI ConstantFunction : public DifferentiableFunction { | ||
148 | public: | ||
149 | 2 | static ConstantFunctionPtr_t create( | |
150 | const vector_t& constant, const size_type& sizeIn, | ||
151 | const size_type& sizeInDer, const std::string name = "ConstantFunction") { | ||
152 | return ConstantFunctionPtr_t( | ||
153 |
3/6✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 2 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 2 times.
✗ Branch 9 not taken.
|
2 | new ConstantFunction(constant, sizeIn, sizeInDer, name)); |
154 | } | ||
155 | 7 | static ConstantFunctionPtr_t create( | |
156 | const LiegroupElement& element, const size_type& sizeIn, | ||
157 | const size_type& sizeInDer, const std::string name = "ConstantFunction") { | ||
158 | return ConstantFunctionPtr_t( | ||
159 |
3/6✓ Branch 2 taken 7 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 7 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 7 times.
✗ Branch 9 not taken.
|
7 | new ConstantFunction(element, sizeIn, sizeInDer, name)); |
160 | } | ||
161 | |||
162 | protected: | ||
163 | 2 | ConstantFunction(const vector_t& constant, const size_type& sizeIn, | |
164 | const size_type& sizeInDer, | ||
165 | const std::string name = "ConstantFunction") | ||
166 | 2 | : DifferentiableFunction(sizeIn, sizeInDer, | |
167 |
1/2✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
|
4 | LiegroupSpace::Rn(constant.rows()), name), |
168 |
2/4✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
✓ Branch 7 taken 2 times.
✗ Branch 8 not taken.
|
6 | c_(constant, outputSpace()) {} |
169 | |||
170 | 7 | ConstantFunction(const LiegroupElement& element, const size_type& sizeIn, | |
171 | const size_type& sizeInDer, | ||
172 | const std::string name = "ConstantFunction") | ||
173 | 7 | : DifferentiableFunction(sizeIn, sizeInDer, element.space(), name), | |
174 |
2/4✓ Branch 2 taken 7 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 7 times.
✗ Branch 7 not taken.
|
14 | c_(element) {} |
175 | |||
176 | /// User implementation of function evaluation | ||
177 | 45 | void impl_compute(LiegroupElementRef r, vectorIn_t) const { r = c_; } | |
178 | |||
179 | 22 | void impl_jacobian(matrixOut_t J, vectorIn_t) const { J.setZero(); } | |
180 | |||
181 | ✗ | bool isEqual(const DifferentiableFunction& other) const { | |
182 | const ConstantFunction& castother = | ||
183 | ✗ | dynamic_cast<const ConstantFunction&>(other); | |
184 | ✗ | if (!DifferentiableFunction::isEqual(other)) return false; | |
185 | |||
186 | ✗ | if (c_.vector() == castother.c_.vector()) return false; | |
187 | |||
188 | ✗ | return true; | |
189 | } | ||
190 | |||
191 | const LiegroupElement c_; | ||
192 | |||
193 | private: | ||
194 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
1 | ConstantFunction() {} |
195 | HPP_SERIALIZABLE(); | ||
196 | }; // class ConstantFunction | ||
197 | |||
198 | /// \} | ||
199 | } // namespace constraints | ||
200 | } // namespace hpp | ||
201 | |||
202 | #endif // HPP_CONSTRAINTS_AFFINE_FUNCTION_HH | ||
203 |