GCC Code Coverage Report


Directory: ./
File: unittest/test_cop_support.cpp
Date: 2025-03-26 19:23:43
Exec Total Coverage
Lines: 132 135 97.8%
Branches: 523 1034 50.6%

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 "unittest_common.hpp"
18
19 using namespace boost::unit_test;
20 using namespace crocoddyl::unittest;
21
22 1 void test_constructor() {
23 // Common parameters
24 Eigen::Vector2d box = Eigen::Vector2d(random_real_in_range(0.01, 0.1),
25
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
1 random_real_in_range(0.01, 0.1));
26
27 // No rotation
28
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
1 Eigen::Matrix3d R = Eigen::Matrix3d::Identity();
29
30 // Create the CoP support support
31
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 crocoddyl::CoPSupport support(R, box);
32
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 crocoddyl::CoPSupport casted_support = support.cast<double>();
33
34
8/16
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
1 BOOST_CHECK(support.get_R().isApprox(R));
35
8/16
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
1 BOOST_CHECK(support.get_box().isApprox(box));
36
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
1 BOOST_CHECK(static_cast<std::size_t>(support.get_A().rows()) == 4);
37
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
1 BOOST_CHECK(static_cast<std::size_t>(support.get_lb().size()) == 4);
38
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
1 BOOST_CHECK(static_cast<std::size_t>(support.get_ub().size()) == 4);
39
40 // Checking that casted computation is the same
41
8/16
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
1 BOOST_CHECK(casted_support.get_R().isApprox(R));
42
8/16
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
1 BOOST_CHECK(casted_support.get_box().isApprox(box));
43
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
1 BOOST_CHECK(static_cast<std::size_t>(casted_support.get_A().rows()) == 4);
44
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
1 BOOST_CHECK(static_cast<std::size_t>(casted_support.get_lb().size()) == 4);
45
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
1 BOOST_CHECK(static_cast<std::size_t>(casted_support.get_ub().size()) == 4);
46
47 // With rotation
48
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 Eigen::Quaterniond q;
49
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 pinocchio::quaternion::uniformRandom(q);
50
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 R = q.toRotationMatrix();
51
52 // Create the wrench support
53
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
1 support = crocoddyl::CoPSupport(R, box);
54
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
1 casted_support = support.cast<double>();
55
56
8/16
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
1 BOOST_CHECK(support.get_R().isApprox(R));
57
8/16
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
1 BOOST_CHECK(support.get_box().isApprox(box));
58
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
1 BOOST_CHECK(static_cast<std::size_t>(support.get_A().rows()) == 4);
59
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
1 BOOST_CHECK(static_cast<std::size_t>(support.get_lb().size()) == 4);
60
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
1 BOOST_CHECK(static_cast<std::size_t>(support.get_ub().size()) == 4);
61
62 // Checking that casted computation is the same
63
8/16
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
1 BOOST_CHECK(casted_support.get_R().isApprox(R));
64
8/16
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
1 BOOST_CHECK(casted_support.get_box().isApprox(box));
65
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
1 BOOST_CHECK(static_cast<std::size_t>(casted_support.get_A().rows()) == 4);
66
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
1 BOOST_CHECK(static_cast<std::size_t>(casted_support.get_lb().size()) == 4);
67
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
1 BOOST_CHECK(static_cast<std::size_t>(casted_support.get_ub().size()) == 4);
68
69 // Create the wrench support from a reference
70 {
71
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 crocoddyl::CoPSupport support_from_reference(support);
72
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
1 casted_support = support_from_reference.cast<double>();
73
74
9/18
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
1 BOOST_CHECK(support.get_R().isApprox(support_from_reference.get_R()));
75
9/18
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
1 BOOST_CHECK(support.get_box().isApprox(support_from_reference.get_box()));
76
9/18
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
1 BOOST_CHECK(support.get_A().isApprox(support_from_reference.get_A()));
77 5 for (std::size_t i = 0;
78
3/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 4 times.
✓ Branch 5 taken 1 times.
5 i < static_cast<std::size_t>(support.get_ub().size()); ++i) {
79
10/20
✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 4 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 4 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 4 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 4 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 4 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 4 times.
✗ Branch 30 not taken.
✗ Branch 34 not taken.
✓ Branch 35 taken 4 times.
4 BOOST_CHECK(support.get_ub()[i] == support_from_reference.get_ub()[i]);
80
10/20
✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 4 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 4 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 4 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 4 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 4 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 4 times.
✗ Branch 30 not taken.
✗ Branch 34 not taken.
✓ Branch 35 taken 4 times.
4 BOOST_CHECK(support.get_lb()[i] == support_from_reference.get_lb()[i]);
81 }
82
83 // Checking that casted computation is the same
84
9/18
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
1 BOOST_CHECK(
85 casted_support.get_R().isApprox(support_from_reference.get_R()));
86
9/18
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
1 BOOST_CHECK(
87 casted_support.get_box().isApprox(support_from_reference.get_box()));
88
9/18
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
1 BOOST_CHECK(
89 casted_support.get_A().isApprox(support_from_reference.get_A()));
90 5 for (std::size_t i = 0;
91
3/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 4 times.
✓ Branch 5 taken 1 times.
5 i < static_cast<std::size_t>(casted_support.get_ub().size()); ++i) {
92
10/20
✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 4 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 4 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 4 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 4 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 4 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 4 times.
✗ Branch 30 not taken.
✗ Branch 34 not taken.
✓ Branch 35 taken 4 times.
4 BOOST_CHECK(casted_support.get_ub()[i] ==
93 support_from_reference.get_ub()[i]);
94
10/20
✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 4 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 4 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 4 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 4 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 4 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 4 times.
✗ Branch 30 not taken.
✗ Branch 34 not taken.
✓ Branch 35 taken 4 times.
4 BOOST_CHECK(casted_support.get_lb()[i] ==
95 support_from_reference.get_lb()[i]);
96 }
97 1 }
98
99 // Create the wrench support through the copy operator
100 {
101
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 crocoddyl::CoPSupport support_from_copy;
102
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 support_from_copy = support;
103
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
1 casted_support = support_from_copy.cast<double>();
104
105
9/18
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
1 BOOST_CHECK(support.get_R().isApprox(support_from_copy.get_R()));
106
9/18
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
1 BOOST_CHECK(support.get_box().isApprox(support_from_copy.get_box()));
107
9/18
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
1 BOOST_CHECK(support.get_A().isApprox(support_from_copy.get_A()));
108 5 for (std::size_t i = 0;
109
3/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 4 times.
✓ Branch 5 taken 1 times.
5 i < static_cast<std::size_t>(support.get_ub().size()); ++i) {
110
10/20
✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 4 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 4 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 4 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 4 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 4 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 4 times.
✗ Branch 30 not taken.
✗ Branch 34 not taken.
✓ Branch 35 taken 4 times.
4 BOOST_CHECK(support.get_ub()[i] == support_from_copy.get_ub()[i]);
111
10/20
✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 4 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 4 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 4 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 4 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 4 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 4 times.
✗ Branch 30 not taken.
✗ Branch 34 not taken.
✓ Branch 35 taken 4 times.
4 BOOST_CHECK(support.get_lb()[i] == support_from_copy.get_lb()[i]);
112 }
113
114 // Checking that casted computation is the same
115
9/18
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
1 BOOST_CHECK(casted_support.get_R().isApprox(support_from_copy.get_R()));
116
9/18
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
1 BOOST_CHECK(casted_support.get_box().isApprox(support_from_copy.get_box()));
117
9/18
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
1 BOOST_CHECK(casted_support.get_A().isApprox(support_from_copy.get_A()));
118 5 for (std::size_t i = 0;
119
3/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 4 times.
✓ Branch 5 taken 1 times.
5 i < static_cast<std::size_t>(support.get_ub().size()); ++i) {
120
10/20
✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 4 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 4 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 4 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 4 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 4 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 4 times.
✗ Branch 30 not taken.
✗ Branch 34 not taken.
✓ Branch 35 taken 4 times.
4 BOOST_CHECK(casted_support.get_ub()[i] == support_from_copy.get_ub()[i]);
121
10/20
✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 4 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 4 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 4 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 4 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 4 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 4 times.
✗ Branch 30 not taken.
✗ Branch 34 not taken.
✓ Branch 35 taken 4 times.
4 BOOST_CHECK(casted_support.get_lb()[i] == support_from_copy.get_lb()[i]);
122 }
123 1 }
124 1 }
125
126 1 void test_A_matrix_with_rotation_change() {
127 // Common parameters
128 Eigen::Vector2d box = Eigen::Vector2d(random_real_in_range(0.01, 0.1),
129
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
1 random_real_in_range(0.01, 0.1));
130
131 // No rotation
132
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
1 Eigen::Matrix3d R = Eigen::Matrix3d::Identity();
133
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 crocoddyl::CoPSupport support_1(R, box);
134
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 crocoddyl::CoPSupport casted_support_1 = support_1.cast<double>();
135
136 // With rotation
137
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 Eigen::Quaterniond q;
138
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 pinocchio::quaternion::uniformRandom(q);
139
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 R = q.toRotationMatrix();
140
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 crocoddyl::CoPSupport support_2(R, box);
141
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 crocoddyl::CoPSupport casted_support_2 = support_2.cast<double>();
142
143
2/2
✓ Branch 0 taken 4 times.
✓ Branch 1 taken 1 times.
5 for (std::size_t i = 0; i < 4; ++i) {
144
15/30
✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 4 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 4 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 4 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 4 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 4 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 4 times.
✗ Branch 30 not taken.
✓ Branch 32 taken 4 times.
✗ Branch 33 not taken.
✓ Branch 35 taken 4 times.
✗ Branch 36 not taken.
✓ Branch 38 taken 4 times.
✗ Branch 39 not taken.
✓ Branch 41 taken 4 times.
✗ Branch 42 not taken.
✓ Branch 44 taken 4 times.
✗ Branch 45 not taken.
✗ Branch 49 not taken.
✓ Branch 50 taken 4 times.
4 BOOST_CHECK((support_1.get_A().row(i).head<3>() -
145 support_2.get_A().row(i).head<3>() * R)
146 .isZero(1e-9));
147 }
148
149 // Checking that casted computation is the same
150
2/2
✓ Branch 0 taken 4 times.
✓ Branch 1 taken 1 times.
5 for (std::size_t i = 0; i < 4; ++i) {
151
15/30
✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 4 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 4 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 4 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 4 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 4 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 4 times.
✗ Branch 30 not taken.
✓ Branch 32 taken 4 times.
✗ Branch 33 not taken.
✓ Branch 35 taken 4 times.
✗ Branch 36 not taken.
✓ Branch 38 taken 4 times.
✗ Branch 39 not taken.
✓ Branch 41 taken 4 times.
✗ Branch 42 not taken.
✓ Branch 44 taken 4 times.
✗ Branch 45 not taken.
✗ Branch 49 not taken.
✓ Branch 50 taken 4 times.
4 BOOST_CHECK((casted_support_1.get_A().row(i).head<3>() -
152 casted_support_2.get_A().row(i).head<3>() * R)
153 .isZero(1e-9));
154 }
155 1 }
156
157 1 void test_cop_within_the_support_region() {
158 // Create the CoP support with a random orientation
159
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 Eigen::Quaterniond q;
160
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 pinocchio::quaternion::uniformRandom(q);
161
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 Eigen::Matrix3d R = q.toRotationMatrix();
162 Eigen::Vector2d box = Eigen::Vector2d(random_real_in_range(0.01, 0.1),
163
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
1 random_real_in_range(0.01, 0.1));
164
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 crocoddyl::CoPSupport support(R, box);
165
166 // Create the activation for quadratic barrier
167
5/10
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
2 crocoddyl::ActivationBounds bounds(support.get_lb(), support.get_ub());
168
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 crocoddyl::ActivationModelQuadraticBarrier activation(bounds);
169 crocoddyl::ActivationModelQuadraticBarrier casted_activation =
170
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 activation.cast<double>();
171 const std::shared_ptr<crocoddyl::ActivationDataAbstract>& data =
172
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 activation.createData();
173 const std::shared_ptr<crocoddyl::ActivationDataAbstract>& casted_data =
174
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 casted_activation.createData();
175
176 // Compute the activation value with a force along the contact normal
177
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 Eigen::VectorXd wrench(6);
178
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 wrench.setZero();
179
5/10
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
1 wrench.template head<3>() = random_real_in_range(0., 100.) * R.col(2);
180
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
1 Eigen::VectorXd r = support.get_A() * wrench;
181
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
1 activation.calc(data, r);
182
6/12
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 1 times.
1 BOOST_CHECK(data->a_value == 0.);
183
184 // Checking that casted computation is the same
185
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
1 casted_activation.calc(casted_data, r);
186
6/12
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 1 times.
1 BOOST_CHECK(casted_data->a_value == 0.);
187
188 // Create the CoP support with no rotation
189
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
1 R = Eigen::Matrix3d::Identity();
190
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
1 support = crocoddyl::CoPSupport(R, box);
191
192 // Compute the activation value with a small enough torque in X
193
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 wrench.setZero();
194
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
1 wrench(5) = random_real_in_range(0., 100.);
195
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
1 wrench(0) = (box(0) - 1e-9) * wrench(5) / 2.;
196
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
1 r = support.get_A() * wrench;
197
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
1 activation.calc(data, r);
198
6/12
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 1 times.
1 BOOST_CHECK(data->a_value == 0.);
199
200 // Checking that casted computation is the same
201
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
1 casted_activation.calc(casted_data, r);
202
6/12
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 1 times.
1 BOOST_CHECK(casted_data->a_value == 0.);
203
204 // Compute the activation value with a small enough torque in Y
205
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 wrench.setZero();
206
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
1 wrench(5) = random_real_in_range(0., 100.);
207
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
1 wrench(1) = (box(1) - 1e-9) * wrench(5) / 2.;
208
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
1 r = support.get_A() * wrench;
209
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
1 activation.calc(data, r);
210
6/12
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 1 times.
1 BOOST_CHECK(data->a_value == 0.);
211
212 // Checking that casted computation is the same
213
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
1 casted_activation.calc(casted_data, r);
214
6/12
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 1 times.
1 BOOST_CHECK(casted_data->a_value == 0.);
215 1 }
216
217 1 void register_unit_tests() {
218 1 framework::master_test_suite().add(
219
4/8
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
1 BOOST_TEST_CASE(boost::bind(&test_constructor)));
220 1 framework::master_test_suite().add(
221
4/8
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
1 BOOST_TEST_CASE(boost::bind(&test_A_matrix_with_rotation_change)));
222 1 framework::master_test_suite().add(
223
4/8
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
1 BOOST_TEST_CASE(boost::bind(&test_cop_within_the_support_region)));
224 1 }
225
226 1 bool init_function() {
227 1 register_unit_tests();
228 1 return true;
229 }
230
231 1 int main(int argc, char* argv[]) {
232 1 return ::boost::unit_test::unit_test_main(&init_function, argc, argv);
233 }
234