GCC Code Coverage Report


Directory: ./
File: unittest/test_wrench_cone.cpp
Date: 2025-05-13 10:30:51
Exec Total Coverage
Lines: 0 252 0.0%
Branches: 0 2090 0.0%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2021-2025, University of Edinburgh, University of Oxford,
5 // Heriot-Watt University
6 // Copyright note valid unless otherwise stated in individual files.
7 // All rights reserved.
8 ///////////////////////////////////////////////////////////////////////////////
9
10 #define BOOST_TEST_NO_MAIN
11 #define BOOST_TEST_ALTERNATIVE_INIT_API
12
13 #include <pinocchio/math/quaternion.hpp>
14
15 #include "crocoddyl/core/activations/quadratic-barrier.hpp"
16 #include "crocoddyl/multibody/cop-support.hpp"
17 #include "crocoddyl/multibody/friction-cone.hpp"
18 #include "crocoddyl/multibody/wrench-cone.hpp"
19 #include "unittest_common.hpp"
20
21 using namespace boost::unit_test;
22 using namespace crocoddyl::unittest;
23
24 void test_constructor() {
25 // Common parameters
26 double mu = random_real_in_range(0.01, 1.);
27 Eigen::Vector2d box = Eigen::Vector2d(random_real_in_range(0.01, 0.1),
28 random_real_in_range(0.01, 0.1));
29 std::size_t nf = 2 * random_int_in_range(2, 16);
30 bool inner_appr = false;
31
32 // No rotation
33 Eigen::Matrix3d R = Eigen::Matrix3d::Identity();
34
35 // Create the wrench cone
36 crocoddyl::WrenchCone cone(R, mu, box, nf, inner_appr);
37 crocoddyl::WrenchCone casted_cone = cone.cast<double>();
38
39 BOOST_CHECK(cone.get_R().isApprox(R));
40 BOOST_CHECK(cone.get_mu() == mu);
41 BOOST_CHECK(cone.get_nf() == nf);
42 BOOST_CHECK(cone.get_box().isApprox(box));
43 BOOST_CHECK(cone.get_inner_appr() == inner_appr);
44 BOOST_CHECK(static_cast<std::size_t>(cone.get_A().rows()) == nf + 13);
45 BOOST_CHECK(static_cast<std::size_t>(cone.get_lb().size()) == nf + 13);
46 BOOST_CHECK(static_cast<std::size_t>(cone.get_ub().size()) == nf + 13);
47
48 // Checking that casted computation is the same
49 BOOST_CHECK(casted_cone.get_R().isApprox(R));
50 BOOST_CHECK(casted_cone.get_mu() == mu);
51 BOOST_CHECK(casted_cone.get_nf() == nf);
52 BOOST_CHECK(casted_cone.get_box().isApprox(box));
53 BOOST_CHECK(casted_cone.get_inner_appr() == inner_appr);
54 BOOST_CHECK(static_cast<std::size_t>(casted_cone.get_A().rows()) == nf + 13);
55 BOOST_CHECK(static_cast<std::size_t>(casted_cone.get_lb().size()) == nf + 13);
56 BOOST_CHECK(static_cast<std::size_t>(casted_cone.get_ub().size()) == nf + 13);
57
58 // With rotation
59 Eigen::Quaterniond q;
60 pinocchio::quaternion::uniformRandom(q);
61 R = q.toRotationMatrix();
62
63 // Create the wrench cone
64 cone = crocoddyl::WrenchCone(R, mu, box, nf, inner_appr);
65 casted_cone = cone.cast<double>();
66
67 BOOST_CHECK(cone.get_R().isApprox(R));
68 BOOST_CHECK(cone.get_mu() == mu);
69 BOOST_CHECK(cone.get_nf() == nf);
70 BOOST_CHECK(cone.get_box().isApprox(box));
71 BOOST_CHECK(cone.get_inner_appr() == inner_appr);
72 BOOST_CHECK(static_cast<std::size_t>(cone.get_A().rows()) == nf + 13);
73 BOOST_CHECK(static_cast<std::size_t>(cone.get_lb().size()) == nf + 13);
74 BOOST_CHECK(static_cast<std::size_t>(cone.get_ub().size()) == nf + 13);
75
76 // Checking that casted computation is the same
77 BOOST_CHECK(casted_cone.get_R().isApprox(R));
78 BOOST_CHECK(casted_cone.get_mu() == mu);
79 BOOST_CHECK(casted_cone.get_nf() == nf);
80 BOOST_CHECK(casted_cone.get_box().isApprox(box));
81 BOOST_CHECK(casted_cone.get_inner_appr() == inner_appr);
82 BOOST_CHECK(static_cast<std::size_t>(casted_cone.get_A().rows()) == nf + 13);
83 BOOST_CHECK(static_cast<std::size_t>(casted_cone.get_lb().size()) == nf + 13);
84 BOOST_CHECK(static_cast<std::size_t>(casted_cone.get_ub().size()) == nf + 13);
85
86 // Create the wrench cone from a reference
87 {
88 crocoddyl::WrenchCone cone_reference(cone);
89 casted_cone = cone_reference.cast<double>();
90
91 BOOST_CHECK(cone.get_nf() == cone_reference.get_nf());
92 BOOST_CHECK(cone.get_A().isApprox(cone_reference.get_A()));
93 for (std::size_t i = 0; i < static_cast<std::size_t>(cone.get_ub().size());
94 ++i) {
95 BOOST_CHECK(cone.get_ub()[i] == cone_reference.get_ub()[i]);
96 BOOST_CHECK(cone.get_lb()[i] == cone_reference.get_lb()[i]);
97 }
98 BOOST_CHECK(cone.get_R().isApprox(cone_reference.get_R()));
99 BOOST_CHECK(cone.get_box().isApprox(cone_reference.get_box()));
100 BOOST_CHECK(std::abs(cone.get_mu() - cone_reference.get_mu()) < 1e-9);
101 BOOST_CHECK(cone.get_inner_appr() == cone_reference.get_inner_appr());
102 BOOST_CHECK(std::abs(cone.get_min_nforce() -
103 cone_reference.get_min_nforce()) < 1e-9);
104 BOOST_CHECK(cone.get_max_nforce() == cone_reference.get_max_nforce());
105
106 // Checking that casted computation is the same
107 BOOST_CHECK(casted_cone.get_nf() == cone_reference.get_nf());
108 BOOST_CHECK(casted_cone.get_A().isApprox(cone_reference.get_A()));
109 for (std::size_t i = 0; i < static_cast<std::size_t>(cone.get_ub().size());
110 ++i) {
111 BOOST_CHECK(casted_cone.get_ub()[i] == cone_reference.get_ub()[i]);
112 BOOST_CHECK(casted_cone.get_lb()[i] == cone_reference.get_lb()[i]);
113 }
114 BOOST_CHECK(casted_cone.get_R().isApprox(cone_reference.get_R()));
115 BOOST_CHECK(casted_cone.get_box().isApprox(cone_reference.get_box()));
116 BOOST_CHECK(std::abs(casted_cone.get_mu() - cone_reference.get_mu()) <
117 1e-9);
118 BOOST_CHECK(casted_cone.get_inner_appr() ==
119 cone_reference.get_inner_appr());
120 BOOST_CHECK(std::abs(casted_cone.get_min_nforce() -
121 cone_reference.get_min_nforce()) < 1e-9);
122 BOOST_CHECK(casted_cone.get_max_nforce() ==
123 cone_reference.get_max_nforce());
124 }
125
126 // Create the wrench cone through the copy operator
127 {
128 crocoddyl::WrenchCone cone_copy;
129 cone_copy = cone;
130 casted_cone = cone_copy.cast<double>();
131
132 BOOST_CHECK(cone.get_nf() == cone_copy.get_nf());
133 BOOST_CHECK(cone.get_A().isApprox(cone_copy.get_A()));
134 for (std::size_t i = 0; i < static_cast<std::size_t>(cone.get_ub().size());
135 ++i) {
136 BOOST_CHECK(cone.get_ub()[i] == cone_copy.get_ub()[i]);
137 BOOST_CHECK(cone.get_lb()[i] == cone_copy.get_lb()[i]);
138 }
139 BOOST_CHECK(cone.get_R().isApprox(cone_copy.get_R()));
140 BOOST_CHECK(cone.get_box().isApprox(cone_copy.get_box()));
141 BOOST_CHECK(std::abs(cone.get_mu() - cone_copy.get_mu()) < 1e-9);
142 BOOST_CHECK(cone.get_inner_appr() == cone_copy.get_inner_appr());
143 BOOST_CHECK(std::abs(cone.get_min_nforce() - cone_copy.get_min_nforce()) <
144 1e-9);
145 BOOST_CHECK(cone.get_max_nforce() == cone_copy.get_max_nforce());
146
147 // Checking that casted computation is the same
148 BOOST_CHECK(casted_cone.get_nf() == cone_copy.get_nf());
149 BOOST_CHECK(casted_cone.get_A().isApprox(cone_copy.get_A()));
150 for (std::size_t i = 0; i < static_cast<std::size_t>(cone.get_ub().size());
151 ++i) {
152 BOOST_CHECK(casted_cone.get_ub()[i] == cone_copy.get_ub()[i]);
153 BOOST_CHECK(casted_cone.get_lb()[i] == cone_copy.get_lb()[i]);
154 }
155 BOOST_CHECK(casted_cone.get_R().isApprox(cone_copy.get_R()));
156 BOOST_CHECK(casted_cone.get_box().isApprox(cone_copy.get_box()));
157 BOOST_CHECK(std::abs(casted_cone.get_mu() - cone_copy.get_mu()) < 1e-9);
158 BOOST_CHECK(casted_cone.get_inner_appr() == cone_copy.get_inner_appr());
159 BOOST_CHECK(std::abs(casted_cone.get_min_nforce() -
160 cone_copy.get_min_nforce()) < 1e-9);
161 BOOST_CHECK(casted_cone.get_max_nforce() == cone_copy.get_max_nforce());
162 }
163 }
164
165 void test_against_friction_cone() {
166 // Common parameters
167 Eigen::Quaterniond q;
168 pinocchio::quaternion::uniformRandom(q);
169 Eigen::Matrix3d R = q.toRotationMatrix();
170 double mu = random_real_in_range(0.01, 1.);
171 Eigen::Vector2d box = Eigen::Vector2d(random_real_in_range(0.01, 0.1),
172 random_real_in_range(0.01, 0.1));
173 std::size_t nf = 2 * random_int_in_range(2, 16);
174 bool inner_appr = true;
175
176 // Create wrench and friction cone
177 crocoddyl::WrenchCone wrench_cone(R, mu, box, nf, inner_appr, 0., 100.);
178 crocoddyl::FrictionCone friction_cone(R, mu, nf, inner_appr, 0., 100.);
179 crocoddyl::WrenchCone casted_wrench_cone = wrench_cone.cast<double>();
180
181 BOOST_CHECK((wrench_cone.get_R() - friction_cone.get_R()).isZero(1e-9));
182 BOOST_CHECK(wrench_cone.get_mu() == friction_cone.get_mu());
183 BOOST_CHECK(wrench_cone.get_nf() == friction_cone.get_nf());
184 for (std::size_t i = 0; i < nf + 1; ++i) {
185 for (std::size_t j = 0; j < 3; ++j) {
186 BOOST_CHECK(wrench_cone.get_A().row(i)[j] ==
187 friction_cone.get_A().row(i)[j]);
188 }
189 }
190 for (std::size_t i = 0; i < nf + 1; ++i) {
191 BOOST_CHECK(wrench_cone.get_ub()[i] == friction_cone.get_ub()[i]);
192 BOOST_CHECK(wrench_cone.get_lb()[i] == friction_cone.get_lb()[i]);
193 }
194
195 // Checking that casted computation is the same
196 BOOST_CHECK(
197 (casted_wrench_cone.get_R() - friction_cone.get_R()).isZero(1e-9));
198 BOOST_CHECK(casted_wrench_cone.get_mu() == friction_cone.get_mu());
199 BOOST_CHECK(casted_wrench_cone.get_nf() == friction_cone.get_nf());
200 for (std::size_t i = 0; i < nf + 1; ++i) {
201 for (std::size_t j = 0; j < 3; ++j) {
202 BOOST_CHECK(casted_wrench_cone.get_A().row(i)[j] ==
203 friction_cone.get_A().row(i)[j]);
204 }
205 }
206 for (std::size_t i = 0; i < nf + 1; ++i) {
207 BOOST_CHECK(casted_wrench_cone.get_ub()[i] == friction_cone.get_ub()[i]);
208 BOOST_CHECK(casted_wrench_cone.get_lb()[i] == friction_cone.get_lb()[i]);
209 }
210 }
211
212 void test_against_cop_support() {
213 // Common parameters
214 Eigen::Quaterniond q;
215 pinocchio::quaternion::uniformRandom(q);
216 Eigen::Matrix3d R = q.toRotationMatrix();
217 double mu = random_real_in_range(0.01, 1.);
218 Eigen::Vector2d box = Eigen::Vector2d(random_real_in_range(0.01, 0.1),
219 random_real_in_range(0.01, 0.1));
220 std::size_t nf = 2 * random_int_in_range(2, 16);
221 bool inner_appr = true;
222
223 // Create wrench and friction cone
224 crocoddyl::WrenchCone wrench_cone(R, mu, box, nf, inner_appr, 0., 100.);
225 crocoddyl::CoPSupport cop_support(R, box);
226 crocoddyl::WrenchCone casted_wrench_cone = wrench_cone.cast<double>();
227
228 BOOST_CHECK((wrench_cone.get_R() - cop_support.get_R()).isZero(1e-9));
229 for (std::size_t i = 0; i < 4; ++i) {
230 for (std::size_t j = 0; j < 6; ++j) {
231 BOOST_CHECK(wrench_cone.get_A().row(nf + i + 1)[j] ==
232 cop_support.get_A().row(i)[j]);
233 }
234 }
235 for (std::size_t i = 0; i < 4; ++i) {
236 BOOST_CHECK(wrench_cone.get_ub()[i + nf + 1] == cop_support.get_ub()[i]);
237 BOOST_CHECK(wrench_cone.get_lb()[i + nf + 1] == cop_support.get_lb()[i]);
238 }
239
240 // Checking that casted computation is the same
241 BOOST_CHECK((casted_wrench_cone.get_R() - cop_support.get_R()).isZero(1e-9));
242 for (std::size_t i = 0; i < 4; ++i) {
243 for (std::size_t j = 0; j < 6; ++j) {
244 BOOST_CHECK(casted_wrench_cone.get_A().row(nf + i + 1)[j] ==
245 cop_support.get_A().row(i)[j]);
246 }
247 }
248 for (std::size_t i = 0; i < 4; ++i) {
249 BOOST_CHECK(casted_wrench_cone.get_ub()[i + nf + 1] ==
250 cop_support.get_ub()[i]);
251 BOOST_CHECK(casted_wrench_cone.get_lb()[i + nf + 1] ==
252 cop_support.get_lb()[i]);
253 }
254 }
255
256 void test_force_along_wrench_cone_normal() {
257 // Create the wrench cone
258 Eigen::Quaterniond q;
259 pinocchio::quaternion::uniformRandom(q);
260 Eigen::Matrix3d R = q.toRotationMatrix();
261 double mu = random_real_in_range(0.01, 1.);
262 Eigen::Vector2d cone_box = Eigen::Vector2d(random_real_in_range(0.01, 0.1),
263 random_real_in_range(0.01, 0.1));
264 crocoddyl::WrenchCone cone(R, mu, cone_box);
265 crocoddyl::WrenchCone casted_cone = cone.cast<double>();
266
267 // Create the activation for quadratic barrier
268 crocoddyl::ActivationBounds bounds(cone.get_lb(), cone.get_ub());
269 crocoddyl::ActivationModelQuadraticBarrier activation(bounds);
270 crocoddyl::ActivationModelQuadraticBarrier casted_activation =
271 activation.cast<double>();
272 const std::shared_ptr<crocoddyl::ActivationDataAbstract>& data =
273 activation.createData();
274 const std::shared_ptr<crocoddyl::ActivationDataAbstract>& casted_data =
275 casted_activation.createData();
276
277 // Compute the activation value
278 Eigen::VectorXd wrench(6);
279 wrench.setZero();
280 wrench.head<3>() = random_real_in_range(0., 100.) * R.col(2);
281 Eigen::VectorXd r = cone.get_A() * wrench;
282 activation.calc(data, r);
283
284 // The activation value has to be zero since the wrench is inside the wrench
285 // cone
286 BOOST_CHECK(data->a_value == 0.);
287
288 // Checking that casted computation is the same
289 r = casted_cone.get_A() * wrench;
290 casted_activation.calc(casted_data, r);
291 BOOST_CHECK(casted_data->a_value == 0.);
292 }
293
294 void test_negative_force_along_wrench_cone_normal() {
295 // Create the wrench cone
296 Eigen::Quaterniond q;
297 pinocchio::quaternion::uniformRandom(q);
298 Eigen::Matrix3d R = q.toRotationMatrix();
299 double mu = random_real_in_range(0.01, 1.);
300 Eigen::Vector2d cone_box = Eigen::Vector2d(random_real_in_range(0.01, 0.1),
301 random_real_in_range(0.01, 0.1));
302 crocoddyl::WrenchCone cone(R, mu, cone_box);
303 crocoddyl::WrenchCone casted_cone = cone.cast<double>();
304
305 // Create the activation for quadratic barrier
306 crocoddyl::ActivationBounds bounds(cone.get_lb(), cone.get_ub());
307 crocoddyl::ActivationModelQuadraticBarrier activation(bounds);
308 crocoddyl::ActivationModelQuadraticBarrier casted_activation =
309 activation.cast<double>();
310 const std::shared_ptr<crocoddyl::ActivationDataAbstract>& data =
311 activation.createData();
312 const std::shared_ptr<crocoddyl::ActivationDataAbstract>& casted_data =
313 casted_activation.createData();
314
315 // Compute the activation value
316 Eigen::VectorXd wrench(6);
317 wrench.setZero();
318 wrench.head<3>() = -random_real_in_range(0., 100.) * R.col(2);
319 Eigen::VectorXd r = cone.get_A() * wrench;
320 activation.calc(data, r);
321
322 // The first nf elements of the residual has to be positive since the force is
323 // outside the wrench cone. Additionally, the last value has to be equals to
324 // the force norm but with negative value since the wrench is aligned and in
325 // opposite direction to the wrench cone orientation
326 for (std::size_t i = 0; i < cone.get_nf(); ++i) {
327 BOOST_CHECK(r(i) > 0.);
328 }
329
330 // The activation value has to be positive since the wrench is outside the
331 // wrench cone
332 activation.calc(data, r);
333 BOOST_CHECK(data->a_value > 0.);
334
335 // Checking that casted computation is the same
336 r = casted_cone.get_A() * wrench;
337 casted_activation.calc(casted_data, r);
338 for (std::size_t i = 0; i < casted_cone.get_nf(); ++i) {
339 BOOST_CHECK(r(i) > 0.);
340 }
341 casted_activation.calc(casted_data, r);
342 BOOST_CHECK(casted_data->a_value > 0.);
343 }
344
345 void test_setter() {
346 // Create the wrench cone
347 Eigen::Matrix3d R = Eigen::Matrix3d::Identity();
348 double mu = random_real_in_range(0.01, 1.);
349 Eigen::Vector2d cone_box = Eigen::Vector2d(random_real_in_range(0.01, 0.1),
350 random_real_in_range(0.01, 0.1));
351 crocoddyl::WrenchCone cone(R, mu, cone_box);
352
353 mu = random_real_in_range(0.01, 1.);
354 cone.set_mu(mu);
355
356 BOOST_CHECK(cone.get_mu() == mu);
357 }
358
359 void test_force_parallel_to_wrench_cone_normal() {
360 // Create the wrench cone
361 Eigen::Matrix3d R = Eigen::Matrix3d::Identity();
362 double mu = random_real_in_range(0.01, 1.);
363 Eigen::Vector2d cone_box = Eigen::Vector2d(random_real_in_range(0.01, 0.1),
364 random_real_in_range(0.01, 0.1));
365 crocoddyl::WrenchCone cone(R, mu, cone_box);
366 crocoddyl::WrenchCone casted_cone = cone.cast<double>();
367
368 // Create the activation for quadratic barrier
369 crocoddyl::ActivationBounds bounds(cone.get_lb(), cone.get_ub());
370 crocoddyl::ActivationModelQuadraticBarrier activation(bounds);
371 crocoddyl::ActivationModelQuadraticBarrier casted_activation =
372 activation.cast<double>();
373 const std::shared_ptr<crocoddyl::ActivationDataAbstract>& data =
374 activation.createData();
375 const std::shared_ptr<crocoddyl::ActivationDataAbstract>& casted_data =
376 casted_activation.createData();
377
378 Eigen::VectorXd wrench(6);
379 wrench.setZero();
380 wrench.head<3>() = -random_real_in_range(0., 100.) * Eigen::Vector3d::UnitX();
381 Eigen::VectorXd r = cone.get_A() * wrench;
382
383 // The activation value has to be positive since the force is outside the
384 // wrench cone
385 activation.calc(data, r);
386 BOOST_CHECK(data->a_value > 0.);
387
388 // Checking that casted computation is the same
389 r = casted_cone.get_A() * wrench;
390 casted_activation.calc(casted_data, r);
391 BOOST_CHECK(casted_data->a_value > 0.);
392 }
393
394 void register_unit_tests() {
395 framework::master_test_suite().add(
396 BOOST_TEST_CASE(boost::bind(&test_constructor)));
397 framework::master_test_suite().add(
398 BOOST_TEST_CASE(boost::bind(&test_against_friction_cone)));
399 framework::master_test_suite().add(
400 BOOST_TEST_CASE(boost::bind(&test_against_cop_support)));
401 framework::master_test_suite().add(
402 BOOST_TEST_CASE(boost::bind(&test_force_along_wrench_cone_normal)));
403 framework::master_test_suite().add(BOOST_TEST_CASE(
404 boost::bind(&test_negative_force_along_wrench_cone_normal)));
405 framework::master_test_suite().add(
406 BOOST_TEST_CASE(boost::bind(&test_force_parallel_to_wrench_cone_normal)));
407 framework::master_test_suite().add(
408 BOOST_TEST_CASE(boost::bind(&test_setter)));
409 }
410
411 bool init_function() {
412 register_unit_tests();
413 return true;
414 }
415
416 int main(int argc, char* argv[]) {
417 return ::boost::unit_test::unit_test_main(&init_function, argc, argv);
418 }
419