GCC Code Coverage Report


Directory: ./
File: unittest/serialization.cpp
Date: 2025-04-30 16:14:33
Exec Total Coverage
Lines: 325 325 100.0%
Branches: 965 1978 48.8%

Line Branch Exec Source
1 //
2 // Copyright (c) 2019-2023 INRIA
3 //
4
5 #include "pinocchio/multibody/data.hpp"
6 #include "pinocchio/algorithm/joint-configuration.hpp"
7 #include "pinocchio/algorithm/kinematics.hpp"
8 #include "pinocchio/algorithm/geometry.hpp"
9
10 #include "pinocchio/serialization/fwd.hpp"
11 #include "pinocchio/serialization/archive.hpp"
12
13 #include "pinocchio/serialization/spatial.hpp"
14
15 #include "pinocchio/serialization/frame.hpp"
16
17 #include "pinocchio/serialization/joints.hpp"
18 #include "pinocchio/serialization/model.hpp"
19 #include "pinocchio/serialization/data.hpp"
20
21 #include "pinocchio/serialization/geometry.hpp"
22
23 #include "pinocchio/multibody/sample-models.hpp"
24
25 #include <iostream>
26
27 #include <boost/test/unit_test.hpp>
28 #include <boost/utility/binary.hpp>
29
30 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
31
32 template<typename T1, typename T2 = T1>
33 struct call_equality_op
34 {
35 2184 static bool run(const T1 & v1, const T2 & v2)
36 {
37 2184 return v1 == v2;
38 }
39 };
40
41 template<typename T>
42 2198 bool run_call_equality_op(const T & v1, const T & v2)
43 {
44 2198 return call_equality_op<T, T>::run(v1, v2);
45 }
46
47 // Bug fix in Eigen::Tensor
48 #ifdef PINOCCHIO_WITH_EIGEN_TENSOR_MODULE
49 template<typename Scalar, int NumIndices, int Options, typename IndexType>
50 struct call_equality_op<pinocchio::Tensor<Scalar, NumIndices, Options, IndexType>>
51 {
52 typedef pinocchio::Tensor<Scalar, NumIndices, Options, IndexType> T;
53
54 7 static bool run(const T & v1, const T & v2)
55 {
56 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options> VectorXd;
57
4/8
✓ Branch 1 taken 7 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 7 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 7 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 7 times.
✗ Branch 11 not taken.
7 Eigen::Map<const VectorXd> map1(v1.data(), v1.size(), 1);
58
4/8
✓ Branch 1 taken 7 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 7 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 7 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 7 times.
✗ Branch 11 not taken.
7 Eigen::Map<const VectorXd> map2(v2.data(), v2.size(), 1);
59
1/2
✓ Branch 1 taken 7 times.
✗ Branch 2 not taken.
14 return map1 == map2;
60 }
61 };
62 #endif
63
64 template<typename T>
65 struct empty_contructor_algo
66 {
67 2170 static T * run()
68 {
69
1/2
✓ Branch 2 taken 658 times.
✗ Branch 3 not taken.
2184 return new T();
70 }
71 };
72
73 template<>
74 struct empty_contructor_algo<pinocchio::GeometryObject>
75 {
76 14 static pinocchio::GeometryObject * run()
77 {
78
10/20
✓ Branch 2 taken 14 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 14 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 14 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 14 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 14 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 14 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 14 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 14 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 14 times.
✗ Branch 30 not taken.
✓ Branch 32 taken 14 times.
✗ Branch 33 not taken.
14 return new pinocchio::GeometryObject("", 0, 0, pinocchio::SE3::Identity(), nullptr);
79 }
80 };
81
82 template<typename T>
83 2198 T * empty_contructor()
84 {
85 2198 return empty_contructor_algo<T>::run();
86 }
87
88 template<typename T>
89 314 void generic_test(const T & object, const std::string & filename, const std::string & tag_name)
90 {
91 using namespace pinocchio::serialization;
92
93 // Load and save as TXT
94
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 const std::string txt_filename = filename + ".txt";
95
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 saveToText(object, txt_filename);
96
97 {
98
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 T & object_loaded = *empty_contructor<T>();
99
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 loadFromText(object_loaded, txt_filename);
100
101 // Check
102
7/14
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 157 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 157 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 157 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 157 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 157 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 157 times.
314 BOOST_CHECK(run_call_equality_op(object_loaded, object));
103
104
1/2
✓ Branch 0 taken 157 times.
✗ Branch 1 not taken.
314 delete &object_loaded;
105 }
106
107 // Load and save as string stream (TXT format)
108
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 std::stringstream ss_out;
109
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 saveToStringStream(object, ss_out);
110
111 {
112
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 T & object_loaded = *empty_contructor<T>();
113
2/4
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 157 times.
✗ Branch 5 not taken.
314 std::istringstream is(ss_out.str());
114
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 loadFromStringStream(object_loaded, is);
115
116 // Check
117
7/14
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 157 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 157 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 157 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 157 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 157 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 157 times.
314 BOOST_CHECK(run_call_equality_op(object_loaded, object));
118
119
1/2
✓ Branch 0 taken 157 times.
✗ Branch 1 not taken.
314 delete &object_loaded;
120 314 }
121
122 // Load and save as string
123
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 std::string str_out = saveToString(object);
124
125 {
126
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 T & object_loaded = *empty_contructor<T>();
127
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 std::string str_in(str_out);
128
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 loadFromString(object_loaded, str_in);
129
130 // Check
131
7/14
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 157 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 157 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 157 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 157 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 157 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 157 times.
314 BOOST_CHECK(run_call_equality_op(object_loaded, object));
132
133
1/2
✓ Branch 0 taken 157 times.
✗ Branch 1 not taken.
314 delete &object_loaded;
134 314 }
135 // Load and save as XML
136
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 const std::string xml_filename = filename + ".xml";
137
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 saveToXML(object, xml_filename, tag_name);
138
139 {
140
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 T & object_loaded = *empty_contructor<T>();
141
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 loadFromXML(object_loaded, xml_filename, tag_name);
142 // Check
143
7/14
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 157 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 157 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 157 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 157 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 157 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 157 times.
314 BOOST_CHECK(run_call_equality_op(object_loaded, object));
144
145
1/2
✓ Branch 0 taken 157 times.
✗ Branch 1 not taken.
314 delete &object_loaded;
146 }
147
148 // Load and save as binary
149
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 const std::string bin_filename = filename + ".bin";
150
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 saveToBinary(object, bin_filename);
151
152 {
153
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 T & object_loaded = *empty_contructor<T>();
154
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 loadFromBinary(object_loaded, bin_filename);
155
156 // Check
157
7/14
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 157 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 157 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 157 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 157 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 157 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 157 times.
314 BOOST_CHECK(run_call_equality_op(object_loaded, object));
158
159
1/2
✓ Branch 0 taken 157 times.
✗ Branch 1 not taken.
314 delete &object_loaded;
160 }
161
162 // Load and save as binary stream
163
1/2
✓ Branch 3 taken 157 times.
✗ Branch 4 not taken.
314 boost::asio::streambuf buffer;
164
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 saveToBinary(object, buffer);
165
166 {
167
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 T & object_loaded = *empty_contructor<T>();
168
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 loadFromBinary(object_loaded, buffer);
169
170 // Check
171
7/14
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 157 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 157 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 157 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 157 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 157 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 157 times.
314 BOOST_CHECK(run_call_equality_op(object_loaded, object));
172
173
1/2
✓ Branch 0 taken 157 times.
✗ Branch 1 not taken.
314 delete &object_loaded;
174 }
175
176 // Load and save as static binary stream
177
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 pinocchio::serialization::StaticBuffer static_buffer(100000000);
178
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 saveToBinary(object, static_buffer);
179
180 {
181
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 T & object_loaded = *empty_contructor<T>();
182
1/2
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
314 loadFromBinary(object_loaded, static_buffer);
183
184 // Check
185
7/14
✓ Branch 1 taken 157 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 157 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 157 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 157 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 157 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 157 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 157 times.
314 BOOST_CHECK(run_call_equality_op(object_loaded, object));
186
187
1/2
✓ Branch 0 taken 157 times.
✗ Branch 1 not taken.
314 delete &object_loaded;
188 }
189 314 }
190
191
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(test_static_buffer)
192 {
193 using namespace pinocchio::serialization;
194 2 const size_t size = 10000000;
195
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 StaticBuffer static_buffer(size);
196
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.
2 BOOST_CHECK(size == static_buffer.size());
197
198 2 const size_t new_size = 2 * size;
199
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 static_buffer.resize(new_size);
200
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.
2 BOOST_CHECK(new_size == static_buffer.size());
201
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.
2 BOOST_CHECK(static_buffer.data() != NULL);
203
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.
2 BOOST_CHECK(reinterpret_cast<const StaticBuffer &>(static_buffer).data() != NULL);
204
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 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✗ Branch 24 not taken.
✓ Branch 25 taken 1 times.
2 BOOST_CHECK(reinterpret_cast<const StaticBuffer &>(static_buffer).data() == static_buffer.data());
205 2 }
206
207
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(test_eigen_serialization)
208 {
209 using namespace pinocchio;
210
211 2 const Eigen::DenseIndex num_cols = 10;
212 2 const Eigen::DenseIndex num_rows = 20;
213
214 2 const Eigen::DenseIndex array_size = 3;
215
216
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 Eigen::MatrixXd Mat = Eigen::MatrixXd::Random(num_rows, num_cols);
217
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(Mat, TEST_SERIALIZATION_FOLDER "/eigen_matrix", "matrix");
218
219
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 Eigen::VectorXd Vec = Eigen::VectorXd::Random(num_rows * num_cols);
220
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(Vec, TEST_SERIALIZATION_FOLDER "/eigen_vector", "vector");
221
222 2 Eigen::array<Eigen::DenseIndex, array_size> array = {1, 2, 3};
223
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(array, TEST_SERIALIZATION_FOLDER "/eigen_array", "array");
224
225 2 const Eigen::DenseIndex tensor_size = 3;
226 2 const Eigen::DenseIndex x_dim = 10, y_dim = 20, z_dim = 30;
227
228 typedef pinocchio::Tensor<double, tensor_size> Tensor3x;
229
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Tensor3x tensor(x_dim, y_dim, z_dim);
230
231
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 Eigen::Map<Eigen::VectorXd>(tensor.data(), tensor.size(), 1).setRandom();
232
233
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(tensor, TEST_SERIALIZATION_FOLDER "/eigen_tensor", "tensor");
234 2 }
235
236
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(test_spatial_serialization)
237 {
238 using namespace pinocchio;
239
240
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 SE3 M(SE3::Random());
241
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(M, TEST_SERIALIZATION_FOLDER "/SE3", "SE3");
242
243
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Motion m(Motion::Random());
244
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(m, TEST_SERIALIZATION_FOLDER "/Motion", "Motion");
245
246
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Force f(Force::Random());
247
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(f, TEST_SERIALIZATION_FOLDER "/Force", "Force");
248
249
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Symmetric3 S(Symmetric3::Random());
250
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(S, TEST_SERIALIZATION_FOLDER "/Symmetric3", "Symmetric3");
251
252
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Inertia I(Inertia::Random());
253
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(I, TEST_SERIALIZATION_FOLDER "/Inertia", "Inertia");
254 2 }
255
256
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(test_multibody_serialization)
257 {
258 using namespace pinocchio;
259
260
4/8
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
4 Frame frame("frame", 0, 0, SE3::Random(), SENSOR);
261
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(frame, TEST_SERIALIZATION_FOLDER "/Frame", "Frame");
262 2 }
263
264 template<typename JointModel_>
265 struct init;
266
267 template<typename JointModel_>
268 struct init
269 {
270 116 static JointModel_ run()
271 {
272 116 JointModel_ jmodel;
273 116 jmodel.setIndexes(0, 0, 0);
274 116 return jmodel;
275 }
276 };
277
278 template<typename Scalar, int Options>
279 struct init<pinocchio::JointModelRevoluteUnalignedTpl<Scalar, Options>>
280 {
281 typedef pinocchio::JointModelRevoluteUnalignedTpl<Scalar, Options> JointModel;
282
283 4 static JointModel run()
284 {
285 typedef typename JointModel::Vector3 Vector3;
286
2/4
✓ Branch 2 taken 4 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
4 JointModel jmodel(Vector3::Random().normalized());
287
288 4 jmodel.setIndexes(0, 0, 0);
289 4 return jmodel;
290 }
291 };
292
293 template<typename Scalar, int Options>
294 struct init<pinocchio::JointModelRevoluteUnboundedUnalignedTpl<Scalar, Options>>
295 {
296 typedef pinocchio::JointModelRevoluteUnboundedUnalignedTpl<Scalar, Options> JointModel;
297
298 4 static JointModel run()
299 {
300 typedef typename JointModel::Vector3 Vector3;
301
2/4
✓ Branch 2 taken 4 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
4 JointModel jmodel(Vector3::Random().normalized());
302
303 4 jmodel.setIndexes(0, 0, 0);
304 4 return jmodel;
305 }
306 };
307
308 template<typename Scalar, int Options>
309 struct init<pinocchio::JointModelPrismaticUnalignedTpl<Scalar, Options>>
310 {
311 typedef pinocchio::JointModelPrismaticUnalignedTpl<Scalar, Options> JointModel;
312
313 4 static JointModel run()
314 {
315 typedef typename JointModel::Vector3 Vector3;
316
2/4
✓ Branch 2 taken 4 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
4 JointModel jmodel(Vector3::Random().normalized());
317
318 4 jmodel.setIndexes(0, 0, 0);
319 4 return jmodel;
320 }
321 };
322
323 template<typename Scalar, int Options>
324 struct init<pinocchio::JointModelHelicalUnalignedTpl<Scalar, Options>>
325 {
326 typedef pinocchio::JointModelHelicalUnalignedTpl<Scalar, Options> JointModel;
327
328 4 static JointModel run()
329 {
330 typedef typename JointModel::Vector3 Vector3;
331
2/4
✓ Branch 2 taken 4 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
4 JointModel jmodel(Vector3::Random().normalized());
332
333 4 jmodel.setIndexes(0, 0, 0);
334 4 return jmodel;
335 }
336 };
337
338 template<typename Scalar, int Options, int axis>
339 struct init<pinocchio::JointModelHelicalTpl<Scalar, Options, axis>>
340 {
341 typedef pinocchio::JointModelHelicalTpl<Scalar, Options, axis> JointModel;
342
343 24 static JointModel run()
344 {
345
1/2
✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
24 JointModel jmodel(static_cast<Scalar>(0.0));
346
347 24 jmodel.setIndexes(0, 0, 0);
348 24 return jmodel;
349 }
350 };
351
352 template<typename Scalar, int Options, template<typename, int> class JointCollection>
353 struct init<pinocchio::JointModelTpl<Scalar, Options, JointCollection>>
354 {
355 typedef pinocchio::JointModelTpl<Scalar, Options, JointCollection> JointModel;
356
357 static JointModel run()
358 {
359 typedef pinocchio::JointModelRevoluteTpl<Scalar, Options, 0> JointModelRX;
360 JointModel jmodel((JointModelRX()));
361
362 jmodel.setIndexes(0, 0, 0);
363 return jmodel;
364 }
365 };
366
367 template<typename Scalar, int Options>
368 struct init<pinocchio::JointModelUniversalTpl<Scalar, Options>>
369 {
370 typedef pinocchio::JointModelUniversalTpl<Scalar, Options> JointModel;
371
372 4 static JointModel run()
373 {
374
2/4
✓ Branch 2 taken 4 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
4 JointModel jmodel(pinocchio::XAxis::vector(), pinocchio::YAxis::vector());
375
376 4 jmodel.setIndexes(0, 0, 0);
377 4 return jmodel;
378 }
379 };
380
381 template<typename Scalar, int Options, template<typename, int> class JointCollection>
382 struct init<pinocchio::JointModelCompositeTpl<Scalar, Options, JointCollection>>
383 {
384 typedef pinocchio::JointModelCompositeTpl<Scalar, Options, JointCollection> JointModel;
385
386 2 static JointModel run()
387 {
388 typedef pinocchio::JointModelRevoluteTpl<Scalar, Options, 0> JointModelRX;
389 typedef pinocchio::JointModelRevoluteTpl<Scalar, Options, 1> JointModelRY;
390
2/4
✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 2 times.
✗ Branch 6 not taken.
2 JointModel jmodel((JointModelRX()));
391
3/6
✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 2 times.
✗ Branch 8 not taken.
2 jmodel.addJoint(JointModelRY());
392
393
1/2
✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
2 jmodel.setIndexes(0, 0, 0);
394 2 return jmodel;
395 }
396 };
397
398 template<typename Scalar, int Options, template<typename, int> class JointCollection>
399 struct init<pinocchio::JointModelMimicTpl<Scalar, Options, JointCollection>>
400 {
401 typedef pinocchio::JointModelMimicTpl<Scalar, Options, JointCollection> JointModel;
402
403 2 static JointModel run()
404 {
405 typedef pinocchio::JointModelRevoluteTpl<Scalar, Options, 0> JointModelRX;
406
1/2
✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
2 JointModelRX jmodel_ref = init<JointModelRX>::run();
407
408
1/2
✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
2 JointModel jmodel(jmodel_ref, 1., 0.);
409
1/2
✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
2 jmodel.setIndexes(1, 0, 0, 0);
410
411 4 return jmodel;
412 }
413 };
414
415 struct TestJointModel
416 {
417 template<typename JointModel>
418 48 void operator()(const pinocchio::JointModelBase<JointModel> &) const
419 {
420
1/2
✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
48 JointModel jmodel = init<JointModel>::run();
421
1/2
✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
48 test(jmodel);
422 48 }
423
424 template<typename JointType>
425 48 static void test(JointType & jmodel)
426 {
427
3/6
✓ Branch 2 taken 24 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 24 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 24 times.
✗ Branch 10 not taken.
48 generic_test(jmodel, TEST_SERIALIZATION_FOLDER "/Joint", "jmodel");
428 48 }
429 };
430
431
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(test_multibody_joints_model_serialization)
432 {
433 using namespace pinocchio;
434 2 boost::mpl::for_each<JointModelVariant::types>(TestJointModel());
435 2 }
436
437 struct TestJointTransform
438 {
439 template<typename JointModel>
440 44 void operator()(const pinocchio::JointModelBase<JointModel> &) const
441 {
442 typedef typename JointModel::JointDerived JointDerived;
443 typedef typename pinocchio::traits<JointDerived>::Transformation_t Transform;
444 typedef typename pinocchio::traits<JointDerived>::Constraint_t Constraint;
445 typedef typename pinocchio::traits<JointDerived>::JointDataDerived JointData;
446 typedef pinocchio::JointDataBase<JointData> JointDataBase;
447
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 JointModel jmodel = init<JointModel>::run();
448
449
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 JointData jdata = jmodel.createData();
450 44 JointDataBase & jdata_base = static_cast<JointDataBase &>(jdata);
451
452 typedef typename pinocchio::LieGroup<JointModel>::type LieGroupType;
453
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 LieGroupType lg;
454
455
3/6
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 22 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 22 times.
✗ Branch 8 not taken.
44 Eigen::VectorXd lb(Eigen::VectorXd::Constant(jmodel.nq(), -1.));
456
3/6
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 22 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 22 times.
✗ Branch 8 not taken.
44 Eigen::VectorXd ub(Eigen::VectorXd::Constant(jmodel.nq(), 1.));
457
458
2/4
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 22 times.
✗ Branch 5 not taken.
44 Eigen::VectorXd q_random = lg.randomConfiguration(lb, ub);
459
460
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 jmodel.calc(jdata, q_random);
461
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 Transform & m = jdata_base.M();
462
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 test(m);
463
464
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 Constraint & S = jdata_base.S();
465
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 test(S);
466 44 }
467
468 template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
469 1 void operator()(const pinocchio::JointModelCompositeTpl<Scalar, Options, JointCollectionTpl> &)
470 {
471 // Do nothing
472 1 }
473
474 template<typename Scalar, int Options, template<typename, int> class JointCollection>
475 1 void operator()(const pinocchio::JointModelMimicTpl<Scalar, Options, JointCollection> &)
476 {
477 // Do nothing
478 1 }
479
480 template<typename Transform>
481 88 static void test(Transform & m)
482 {
483
3/6
✓ Branch 2 taken 44 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 44 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 44 times.
✗ Branch 10 not taken.
88 generic_test(m, TEST_SERIALIZATION_FOLDER "/JointTransform", "transform");
484 88 }
485 };
486
487
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(test_multibody_joints_transform_serialization)
488 {
489 using namespace pinocchio;
490 2 boost::mpl::for_each<JointModelVariant::types>(TestJointTransform());
491 2 }
492
493 struct TestJointMotion
494 {
495 template<typename JointModel>
496 44 void operator()(const pinocchio::JointModelBase<JointModel> &) const
497 {
498 typedef typename JointModel::JointDerived JointDerived;
499 typedef typename pinocchio::traits<JointDerived>::Motion_t Motion;
500 typedef typename pinocchio::traits<JointDerived>::Bias_t Bias;
501 typedef typename pinocchio::traits<JointDerived>::JointDataDerived JointData;
502 typedef pinocchio::JointDataBase<JointData> JointDataBase;
503
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 JointModel jmodel = init<JointModel>::run();
504
505
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 JointData jdata = jmodel.createData();
506 44 JointDataBase & jdata_base = static_cast<JointDataBase &>(jdata);
507
508 typedef typename pinocchio::LieGroup<JointModel>::type LieGroupType;
509
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 LieGroupType lg;
510
511
3/6
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 22 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 22 times.
✗ Branch 8 not taken.
44 Eigen::VectorXd lb(Eigen::VectorXd::Constant(jmodel.nq(), -1.));
512
3/6
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 22 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 22 times.
✗ Branch 8 not taken.
44 Eigen::VectorXd ub(Eigen::VectorXd::Constant(jmodel.nq(), 1.));
513
514
2/4
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 22 times.
✗ Branch 5 not taken.
44 Eigen::VectorXd q_random = lg.randomConfiguration(lb, ub);
515
3/6
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 22 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 22 times.
✗ Branch 8 not taken.
44 Eigen::VectorXd v_random = Eigen::VectorXd::Random(jmodel.nv());
516
517
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 jmodel.calc(jdata, q_random, v_random);
518
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 Motion & m = jdata_base.v();
519
520
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 test(m);
521
522
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 Bias & b = jdata_base.c();
523
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 test(b);
524 44 }
525
526 template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
527 1 void operator()(const pinocchio::JointModelCompositeTpl<Scalar, Options, JointCollectionTpl> &)
528 {
529 // Do nothing
530 1 }
531
532 template<typename Scalar, int Options, template<typename, int> class JointCollection>
533 1 void operator()(const pinocchio::JointModelMimicTpl<Scalar, Options, JointCollection> &)
534 {
535 // Do nothing
536 1 }
537
538 template<typename Motion>
539 88 static void test(Motion & m)
540 {
541
3/6
✓ Branch 2 taken 44 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 44 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 44 times.
✗ Branch 10 not taken.
88 generic_test(m, TEST_SERIALIZATION_FOLDER "/JointMotion", "motion");
542 88 }
543 };
544
545
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(test_multibody_joints_motion_serialization)
546 {
547 using namespace pinocchio;
548 2 boost::mpl::for_each<JointModelVariant::types>(TestJointMotion());
549 2 }
550
551 struct TestJointData
552 {
553 template<typename JointModel>
554 44 void operator()(const pinocchio::JointModelBase<JointModel> &) const
555 {
556 typedef typename JointModel::JointDerived JointDerived;
557 typedef typename pinocchio::traits<JointDerived>::JointDataDerived JointData;
558
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 JointModel jmodel = init<JointModel>::run();
559
560
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 JointData jdata = jmodel.createData();
561
562 typedef typename pinocchio::LieGroup<JointModel>::type LieGroupType;
563
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 LieGroupType lg;
564
565
3/6
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 22 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 22 times.
✗ Branch 8 not taken.
44 Eigen::VectorXd lb(Eigen::VectorXd::Constant(jmodel.nq(), -1.));
566
3/6
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 22 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 22 times.
✗ Branch 8 not taken.
44 Eigen::VectorXd ub(Eigen::VectorXd::Constant(jmodel.nq(), 1.));
567
568
2/4
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 22 times.
✗ Branch 5 not taken.
44 Eigen::VectorXd q_random = lg.randomConfiguration(lb, ub);
569
3/6
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 22 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 22 times.
✗ Branch 8 not taken.
44 Eigen::VectorXd v_random = Eigen::VectorXd::Random(jmodel.nv());
570
571
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 jmodel.calc(jdata, q_random, v_random);
572
2/4
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 22 times.
✗ Branch 5 not taken.
44 pinocchio::Inertia::Matrix6 I(pinocchio::Inertia::Matrix6::Identity());
573
3/6
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 22 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 22 times.
✗ Branch 8 not taken.
44 jmodel.calc_aba(jdata, Eigen::VectorXd::Zero(jmodel.nv()), I, false);
574
1/2
✓ Branch 1 taken 22 times.
✗ Branch 2 not taken.
44 test(jdata);
575 44 }
576
577 template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
578 1 void operator()(const pinocchio::JointModelCompositeTpl<Scalar, Options, JointCollectionTpl> &)
579 {
580 typedef pinocchio::JointModelCompositeTpl<Scalar, Options, JointCollectionTpl> JointModel;
581 typedef typename JointModel::JointDerived JointDerived;
582 typedef typename pinocchio::traits<JointDerived>::JointDataDerived JointData;
583
584
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 JointModel jmodel_build = init<JointModel>::run();
585
586
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 pinocchio::Model model;
587
4/8
✓ 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.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
1 model.addJoint(0, jmodel_build, pinocchio::SE3::Random(), "model");
588
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 model.lowerPositionLimit.fill(-1.);
589
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 model.upperPositionLimit.fill(1.);
590
591
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
1 JointModel & jmodel = boost::get<JointModel>(model.joints[1]);
592
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 Eigen::VectorXd q_random = pinocchio::randomConfiguration(model);
593
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
1 Eigen::VectorXd v_random = Eigen::VectorXd::Random(model.nv);
594
595
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 pinocchio::Data data(model);
596
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
1 JointData & jdata = boost::get<JointData>(data.joints[1]);
597
598
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 jmodel.calc(jdata, q_random, v_random);
599
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
1 pinocchio::Inertia::Matrix6 I(pinocchio::Inertia::Matrix6::Identity());
600
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 jmodel.calc_aba(jdata, Eigen::VectorXd::Zero(jmodel.nv()), I, false);
601
602
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 test(jdata);
603 1 }
604
605 template<typename Scalar, int Options, template<typename, int> class JointCollection>
606 1 void operator()(const pinocchio::JointModelMimicTpl<Scalar, Options, JointCollection> &)
607 {
608 typedef pinocchio::JointModelMimicTpl<Scalar, Options, JointCollection> JointModel;
609 typedef typename JointModel::JointDerived JointDerived;
610 typedef typename pinocchio::traits<JointDerived>::JointDataDerived JointData;
611
612
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 JointModel jmodel = init<JointModel>::run();
613
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 JointData jdata = jmodel.createData();
614
615
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 Eigen::VectorXd q_random = Eigen::VectorXd::Random(jmodel.jmodel().nq());
616
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 Eigen::VectorXd v_random = Eigen::VectorXd::Random(jmodel.jmodel().nv());
617
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 jmodel.calc(jdata, q_random, v_random);
618
619
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 test(jdata);
620 1 }
621
622 template<typename JointData>
623 48 static void test(JointData & joint_data)
624 {
625
3/6
✓ Branch 2 taken 24 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 24 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 24 times.
✗ Branch 10 not taken.
48 generic_test(joint_data, TEST_SERIALIZATION_FOLDER "/JointData", "data");
626 48 }
627 };
628
629
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(test_multibody_joints_data_serialization)
630 {
631 using namespace pinocchio;
632 2 boost::mpl::for_each<JointModelVariant::types>(TestJointData());
633 2 }
634
635
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(test_model_serialization)
636 {
637 using namespace pinocchio;
638
639
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model model;
640
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 buildModels::humanoidRandom(model);
641
642
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(model, TEST_SERIALIZATION_FOLDER "/Model", "Model");
643 2 }
644
645
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(test_throw_extension)
646 {
647 using namespace pinocchio;
648
649
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model model;
650
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 buildModels::humanoidRandom(model);
651
652
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 const std::string & fake_filename = "this_is_a_fake_filename";
653
654 {
655
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 const std::string complete_filename = fake_filename + ".txt";
656
11/34
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✗ Branch 8 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 11 not taken.
✗ Branch 12 not taken.
✗ Branch 15 not taken.
✗ Branch 16 not taken.
✗ Branch 20 not taken.
✗ Branch 21 not taken.
✗ Branch 23 not taken.
✗ Branch 24 not taken.
✗ Branch 26 not taken.
✗ Branch 27 not taken.
✗ Branch 31 not taken.
✗ Branch 32 not taken.
✗ Branch 34 not taken.
✓ Branch 35 taken 1 times.
✗ Branch 38 not taken.
✓ Branch 39 taken 1 times.
✓ Branch 42 taken 1 times.
✗ Branch 43 not taken.
✓ Branch 46 taken 1 times.
✗ Branch 47 not taken.
✓ Branch 51 taken 1 times.
✗ Branch 52 not taken.
✓ Branch 54 taken 1 times.
✗ Branch 55 not taken.
✓ Branch 57 taken 1 times.
✗ Branch 58 not taken.
✗ Branch 62 not taken.
✓ Branch 63 taken 1 times.
4 BOOST_REQUIRE_THROW(loadFromText(model, complete_filename), std::invalid_argument);
657 2 }
658
659
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 saveToText(model, TEST_SERIALIZATION_FOLDER "/model.txt");
660
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 saveToXML(model, TEST_SERIALIZATION_FOLDER "/model.xml", "model");
661
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 saveToBinary(model, TEST_SERIALIZATION_FOLDER "/model.bin");
662
663 {
664
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 const std::string complete_filename = fake_filename + ".txte";
665
666
11/34
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✗ Branch 8 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 11 not taken.
✗ Branch 12 not taken.
✗ Branch 15 not taken.
✗ Branch 16 not taken.
✗ Branch 20 not taken.
✗ Branch 21 not taken.
✗ Branch 23 not taken.
✗ Branch 24 not taken.
✗ Branch 26 not taken.
✗ Branch 27 not taken.
✗ Branch 31 not taken.
✗ Branch 32 not taken.
✗ Branch 34 not taken.
✓ Branch 35 taken 1 times.
✗ Branch 38 not taken.
✓ Branch 39 taken 1 times.
✓ Branch 42 taken 1 times.
✗ Branch 43 not taken.
✓ Branch 46 taken 1 times.
✗ Branch 47 not taken.
✓ Branch 51 taken 1 times.
✗ Branch 52 not taken.
✓ Branch 54 taken 1 times.
✗ Branch 55 not taken.
✓ Branch 57 taken 1 times.
✗ Branch 58 not taken.
✗ Branch 62 not taken.
✓ Branch 63 taken 1 times.
4 BOOST_REQUIRE_THROW(loadFromText(model, complete_filename), std::invalid_argument);
667 2 }
668
669 {
670
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 const std::string complete_filename = fake_filename + ".xmle";
671
12/36
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✗ Branch 12 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 17 not taken.
✗ Branch 18 not taken.
✗ Branch 21 not taken.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✗ Branch 27 not taken.
✗ Branch 29 not taken.
✗ Branch 30 not taken.
✗ Branch 32 not taken.
✗ Branch 33 not taken.
✗ Branch 37 not taken.
✗ Branch 38 not taken.
✗ Branch 40 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 47 taken 1 times.
✓ Branch 50 taken 1 times.
✗ Branch 51 not taken.
✓ Branch 54 taken 1 times.
✗ Branch 55 not taken.
✓ Branch 59 taken 1 times.
✗ Branch 60 not taken.
✓ Branch 62 taken 1 times.
✗ Branch 63 not taken.
✓ Branch 65 taken 1 times.
✗ Branch 66 not taken.
✗ Branch 70 not taken.
✓ Branch 71 taken 1 times.
8 BOOST_REQUIRE_THROW(loadFromXML(model, complete_filename, "model"), std::invalid_argument);
672 2 }
673
674 {
675
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 const std::string complete_filename = fake_filename + ".bine";
676
11/34
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✗ Branch 8 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 11 not taken.
✗ Branch 12 not taken.
✗ Branch 15 not taken.
✗ Branch 16 not taken.
✗ Branch 20 not taken.
✗ Branch 21 not taken.
✗ Branch 23 not taken.
✗ Branch 24 not taken.
✗ Branch 26 not taken.
✗ Branch 27 not taken.
✗ Branch 31 not taken.
✗ Branch 32 not taken.
✗ Branch 34 not taken.
✓ Branch 35 taken 1 times.
✗ Branch 38 not taken.
✓ Branch 39 taken 1 times.
✓ Branch 42 taken 1 times.
✗ Branch 43 not taken.
✓ Branch 46 taken 1 times.
✗ Branch 47 not taken.
✓ Branch 51 taken 1 times.
✗ Branch 52 not taken.
✓ Branch 54 taken 1 times.
✗ Branch 55 not taken.
✓ Branch 57 taken 1 times.
✗ Branch 58 not taken.
✗ Branch 62 not taken.
✓ Branch 63 taken 1 times.
4 BOOST_REQUIRE_THROW(loadFromBinary(model, complete_filename), std::invalid_argument);
677 2 }
678 2 }
679
680
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(test_data_serialization)
681 {
682 using namespace pinocchio;
683
684
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model model;
685
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 buildModels::humanoidRandom(model);
686
687
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data(model);
688
689
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(data, TEST_SERIALIZATION_FOLDER "/Data", "Data");
690 2 }
691
692
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(test_collision_pair)
693 {
694 using namespace pinocchio;
695
696
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 CollisionPair collision_pair(1, 2);
697
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(collision_pair, TEST_SERIALIZATION_FOLDER "/CollisionPair", "CollisionPair");
698 2 }
699
700
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(test_model_item)
701 {
702 using namespace pinocchio;
703
704 typedef GeometryObject::Base GeometryObject_ModelItem;
705
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
4 GeometryObject_ModelItem model_item("pinocchio", 1, 2, SE3::Random());
706
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(model_item, TEST_SERIALIZATION_FOLDER "/ModelItem", "ModelItem");
707 2 }
708
709
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(test_geometry_object)
710 {
711 using namespace pinocchio;
712
713 {
714
9/18
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 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 22 taken 1 times.
✗ Branch 23 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 1 times.
✗ Branch 30 not taken.
4 GeometryObject geometry_object("nullptr", 1, 2, SE3::Random(), nullptr);
715
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(geometry_object, TEST_SERIALIZATION_FOLDER "/GeometryObject", "GeometryObject");
716 2 }
717
718 #ifdef PINOCCHIO_WITH_HPP_FCL
719 {
720
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 hpp::fcl::Box box(1., 2., 3.);
721
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(box, TEST_SERIALIZATION_FOLDER "/Box", "Box");
722 2 }
723
724 #if HPP_FCL_VERSION_AT_LEAST(3, 0, 0)
725 {
726 typedef GeometryObject::CollisionGeometryPtr CollisionGeometryPtr;
727
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.
2 CollisionGeometryPtr box_ptr = CollisionGeometryPtr(new hpp::fcl::Box(1., 2., 3.));
728
9/18
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 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 25 taken 1 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 1 times.
✗ Branch 29 not taken.
4 GeometryObject geometry_object("box", 1, 2, SE3::Random(), box_ptr);
729
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(geometry_object, TEST_SERIALIZATION_FOLDER "/GeometryObject", "GeometryObject");
730 2 }
731 #endif // hpp-fcl >= 3.0.0
732 #endif
733 2 }
734
735
33/66
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
4 BOOST_AUTO_TEST_CASE(test_geometry_model_and_data_serialization)
736 {
737 using namespace pinocchio;
738
739
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model model;
740
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 buildModels::humanoid(model);
741
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data(model);
742
743 // Empty structures
744 {
745
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 GeometryModel geom_model;
746
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(geom_model, TEST_SERIALIZATION_FOLDER "/GeometryModel", "GeometryModel");
747
748
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 GeometryData geom_data(geom_model);
749
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(geom_data, TEST_SERIALIZATION_FOLDER "/GeometryData", "GeometryData");
750 2 }
751
752 #ifdef PINOCCHIO_WITH_HPP_FCL
753 #if HPP_FCL_VERSION_AT_LEAST(3, 0, 0)
754 {
755
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::GeometryModel geom_model;
756
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::buildModels::humanoidGeometries(model, geom_model);
757 // Append new objects
758 {
759 using namespace hpp::fcl;
760
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 BVHModel<OBBRSS> * bvh_ptr = new BVHModel<OBBRSS>();
761 // bvh_ptr->beginModel();
762 // bvh_ptr->addSubModel(p1, t1);
763 // bvh_ptr->endModel();
764
765 GeometryObject obj_bvh(
766
10/20
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 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 28 taken 1 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 1 times.
✗ Branch 32 not taken.
4 "bvh", 0, 0, SE3::Identity(), GeometryObject::CollisionGeometryPtr(bvh_ptr));
767
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 geom_model.addGeometryObject(obj_bvh);
768
769 2 const double min_altitude = -1.;
770 2 const double x_dim = 1., y_dim = 2.;
771 2 const Eigen::DenseIndex nx = 100, ny = 200;
772
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 const Eigen::MatrixXd heights = Eigen::MatrixXd::Random(ny, nx);
773
774 HeightField<OBBRSS> * hfield_ptr =
775
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 new HeightField<OBBRSS>(x_dim, y_dim, heights, min_altitude);
776
777 GeometryObject obj_hfield(
778
10/20
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 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 28 taken 1 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 1 times.
✗ Branch 32 not taken.
4 "hfield", 0, 0, SE3::Identity(), GeometryObject::CollisionGeometryPtr(hfield_ptr));
779
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 geom_model.addGeometryObject(obj_hfield);
780 2 }
781
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(geom_model, TEST_SERIALIZATION_FOLDER "/GeometryModel", "GeometryModel");
782
783
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::GeometryData geom_data(geom_model);
784
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 const Eigen::VectorXd q = pinocchio::neutral(model);
785
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::forwardKinematics(model, data, q);
786
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::updateGeometryPlacements(model, data, geom_model, geom_data, q);
787
788
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 generic_test(geom_data, TEST_SERIALIZATION_FOLDER "/GeometryData", "GeometryData");
789 2 }
790 #endif // hpp-fcl >= 3.0.0
791 #endif // PINOCCHIO_WITH_HPP_FCL
792 2 }
793
794 BOOST_AUTO_TEST_SUITE_END()
795