GCC Code Coverage Report


Directory: ./
File: unittest/centroidal-derivatives.cpp
Date: 2024-08-27 18:20:05
Exec Total Coverage
Lines: 0 159 0.0%
Branches: 0 1354 0.0%

Line Branch Exec Source
1 //
2 // Copyright (c) 2018-2021 INRIA
3 //
4
5 #include "pinocchio/algorithm/crba.hpp"
6 #include "pinocchio/algorithm/rnea.hpp"
7 #include "pinocchio/algorithm/centroidal.hpp"
8 #include "pinocchio/algorithm/centroidal-derivatives.hpp"
9 #include "pinocchio/algorithm/rnea-derivatives.hpp"
10 #include "pinocchio/algorithm/aba-derivatives.hpp"
11 #include "pinocchio/algorithm/jacobian.hpp"
12 #include "pinocchio/algorithm/center-of-mass.hpp"
13 #include "pinocchio/algorithm/joint-configuration.hpp"
14 #include "pinocchio/multibody/sample-models.hpp"
15
16 #include <iostream>
17
18 #include <boost/test/unit_test.hpp>
19 #include <boost/utility/binary.hpp>
20
21 template<typename JointModel>
22 static void addJointAndBody(
23 pinocchio::Model & model,
24 const pinocchio::JointModelBase<JointModel> & joint,
25 const std::string & parent_name,
26 const std::string & name,
27 const pinocchio::SE3 placement = pinocchio::SE3::Random(),
28 bool setRandomLimits = true)
29 {
30 using namespace pinocchio;
31 typedef typename JointModel::ConfigVector_t CV;
32 typedef typename JointModel::TangentVector_t TV;
33
34 Model::JointIndex idx;
35
36 if (setRandomLimits)
37 idx = model.addJoint(
38 model.getJointId(parent_name), joint, SE3::Random(), name + "_joint",
39 TV::Random() + TV::Constant(1), TV::Random() + TV::Constant(1),
40 CV::Random() - CV::Constant(1), CV::Random() + CV::Constant(1));
41 else
42 idx = model.addJoint(model.getJointId(parent_name), joint, placement, name + "_joint");
43
44 model.addJointFrame(idx);
45
46 model.appendBodyToJoint(idx, Inertia::Random(), SE3::Identity());
47 model.addBodyFrame(name + "_body", idx);
48 }
49
50 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
51
52 BOOST_AUTO_TEST_CASE(test_centroidal_derivatives)
53 {
54 pinocchio::Model model;
55 pinocchio::buildModels::humanoidRandom(model);
56 const std::string parent_name = model.names.back();
57 const std::string joint_name = "ee_spherical_joint";
58 addJointAndBody(model, pinocchio::JointModelSpherical(), parent_name, joint_name);
59
60 pinocchio::Data data(model), data_ref(model);
61
62 model.lowerPositionLimit.head<7>().fill(-1.);
63 model.upperPositionLimit.head<7>().fill(1.);
64
65 Eigen::VectorXd q = pinocchio::randomConfiguration(model);
66 Eigen::VectorXd v = Eigen::VectorXd::Random(model.nv);
67 Eigen::VectorXd a = Eigen::VectorXd::Random(model.nv);
68
69 pinocchio::Data::Matrix6x dh_dq(6, model.nv), dhdot_dq(6, model.nv), dhdot_dv(6, model.nv),
70 dhdot_da(6, model.nv);
71 pinocchio::computeCentroidalDynamicsDerivatives(
72 model, data, q, v, a, dh_dq, dhdot_dq, dhdot_dv, dhdot_da);
73 pinocchio::ccrba(model, data_ref, q, v);
74
75 for (size_t k = 0; k < (size_t)model.njoints; ++k)
76 {
77 BOOST_CHECK(data.oMi[k].isApprox(data_ref.oMi[k]));
78 BOOST_CHECK(data.oYcrb[k].isApprox(data_ref.oYcrb[k]));
79 }
80 BOOST_CHECK(dhdot_da.isApprox(data_ref.Ag));
81
82 pinocchio::computeCentroidalMomentumTimeVariation(model, data_ref, q, v, a);
83 for (size_t k = 1; k < (size_t)model.njoints; ++k)
84 {
85 BOOST_CHECK(data.v[k].isApprox(data_ref.v[k]));
86 BOOST_CHECK(data.ov[k].isApprox(data.oMi[k].act(data_ref.v[k])));
87 BOOST_CHECK(data.oa[k].isApprox(data.oMi[k].act(data_ref.a[k])));
88 BOOST_CHECK(data.oh[k].isApprox(data.oMi[k].act(data_ref.h[k])));
89 }
90
91 BOOST_CHECK(data.mass[0] == data_ref.mass[0]);
92 BOOST_CHECK(data.com[0].isApprox(data_ref.com[0]));
93
94 BOOST_CHECK(data.oh[0].isApprox(data_ref.h[0]));
95 BOOST_CHECK(data.of[0].isApprox(data_ref.f[0]));
96
97 BOOST_CHECK(data.hg.isApprox(data_ref.hg));
98 BOOST_CHECK(data.dhg.isApprox(data_ref.dhg));
99 BOOST_CHECK(data.Ag.isApprox(data_ref.Ag));
100
101 pinocchio::Data data_fd(model);
102
103 const double eps = 1e-8;
104 const pinocchio::Force dhg =
105 pinocchio::computeCentroidalMomentumTimeVariation(model, data_fd, q, v, a);
106 const pinocchio::Force hg = data_fd.hg;
107 BOOST_CHECK(data.hg.isApprox(data_ref.hg));
108
109 // Check dhdot_dq and dh_dq with finite differences
110 Eigen::VectorXd q_plus(model.nq, 1);
111 Eigen::VectorXd v_eps(model.nv, 1);
112 v_eps.setZero();
113 pinocchio::Data::Matrix6x dhdot_dq_fd(6, model.nv);
114 pinocchio::Data::Matrix6x dh_dq_fd(6, model.nv);
115
116 for (Eigen::DenseIndex k = 0; k < model.nv; ++k)
117 {
118 v_eps[k] = eps;
119 q_plus = pinocchio::integrate(model, q, v_eps);
120
121 const pinocchio::Force & dhg_plus =
122 pinocchio::computeCentroidalMomentumTimeVariation(model, data_fd, q_plus, v, a);
123 const pinocchio::Force hg_plus = data_fd.hg;
124 dhdot_dq_fd.col(k) = (dhg_plus - dhg).toVector() / eps;
125 dh_dq_fd.col(k) = (hg_plus - hg).toVector() / eps;
126 v_eps[k] = 0.;
127 }
128
129 BOOST_CHECK(dhdot_dq.isApprox(dhdot_dq_fd, sqrt(eps)));
130 BOOST_CHECK(dh_dq.isApprox(dh_dq_fd, sqrt(eps)));
131 // Check dhdot_dv with finite differences
132 Eigen::VectorXd v_plus(v);
133 pinocchio::Data::Matrix6x dhdot_dv_fd(6, model.nv);
134
135 for (Eigen::DenseIndex k = 0; k < model.nv; ++k)
136 {
137 v_plus[k] += eps;
138
139 const pinocchio::Force & dhg_plus =
140 pinocchio::computeCentroidalMomentumTimeVariation(model, data_fd, q, v_plus, a);
141 dhdot_dv_fd.col(k) = (dhg_plus - dhg).toVector() / eps;
142
143 v_plus[k] -= eps;
144 }
145
146 BOOST_CHECK(dhdot_dv.isApprox(dhdot_dv_fd, sqrt(eps)));
147
148 // Check dhdot_da with finite differences
149 Eigen::VectorXd a_plus(a);
150 pinocchio::Data::Matrix6x dhdot_da_fd(6, model.nv);
151
152 for (Eigen::DenseIndex k = 0; k < model.nv; ++k)
153 {
154 a_plus[k] += eps;
155
156 const pinocchio::Force & dhg_plus =
157 pinocchio::computeCentroidalMomentumTimeVariation(model, data_fd, q, v, a_plus);
158 dhdot_da_fd.col(k) = (dhg_plus - dhg).toVector() / eps;
159
160 a_plus[k] -= eps;
161 }
162
163 BOOST_CHECK(dhdot_da.isApprox(dhdot_da_fd, sqrt(eps)));
164
165 pinocchio::computeRNEADerivatives(model, data_ref, q, v, a);
166 BOOST_CHECK(data.dAdv.isApprox(data_ref.dAdv));
167 BOOST_CHECK(data.dAdq.isApprox(data_ref.dAdq));
168 BOOST_CHECK(data.J.isApprox(data_ref.J));
169 BOOST_CHECK(data.dJ.isApprox(data_ref.dJ));
170 BOOST_CHECK(data.dVdq.isApprox(data_ref.dVdq));
171
172 pinocchio::computeCentroidalMap(model, data_ref, q);
173 BOOST_CHECK(data.Ag.isApprox(data_ref.Ag));
174 }
175
176 BOOST_AUTO_TEST_CASE(test_retrieve_centroidal_derivatives_fromRNEA)
177 {
178 pinocchio::Model model;
179 pinocchio::buildModels::humanoidRandom(model);
180 pinocchio::Data data(model), data_ref(model);
181
182 model.lowerPositionLimit.head<7>().fill(-1.);
183 model.upperPositionLimit.head<7>().fill(1.);
184
185 Eigen::VectorXd q = pinocchio::randomConfiguration(model);
186 Eigen::VectorXd v = Eigen::VectorXd::Random(model.nv);
187 Eigen::VectorXd a = Eigen::VectorXd::Random(model.nv);
188
189 pinocchio::Data::Matrix6x dh_dq(6, model.nv), dhdot_dq(6, model.nv), dhdot_dv(6, model.nv),
190 dhdot_da(6, model.nv);
191 pinocchio::Data::Matrix6x dh_dq_ref(6, model.nv), dhdot_dq_ref(6, model.nv),
192 dhdot_dv_ref(6, model.nv), dhdot_da_ref(6, model.nv);
193
194 pinocchio::computeCentroidalDynamicsDerivatives(
195 model, data_ref, q, v, a, dh_dq_ref, dhdot_dq_ref, dhdot_dv_ref, dhdot_da_ref);
196
197 pinocchio::computeRNEADerivatives(model, data, q, v, a);
198 pinocchio::getCentroidalDynamicsDerivatives(model, data, dh_dq, dhdot_dq, dhdot_dv, dhdot_da);
199
200 BOOST_CHECK(data.J.isApprox(data_ref.J));
201
202 for (pinocchio::Model::JointIndex k = 1; k < (pinocchio::Model::JointIndex)model.njoints; ++k)
203 {
204 BOOST_CHECK(data.oYcrb[k].isApprox(data_ref.oYcrb[k]));
205 pinocchio::Force force_ref = data_ref.of[k];
206 pinocchio::Force gravity_contribution = data.oYcrb[k] * (-model.gravity);
207 pinocchio::Force force = data.of[k] - gravity_contribution;
208 BOOST_CHECK(force.isApprox(force_ref));
209 }
210
211 BOOST_CHECK(data.com[0].isApprox(data_ref.com[0]));
212
213 BOOST_CHECK(data.hg.isApprox(data_ref.hg));
214 BOOST_CHECK(data.dhg.isApprox(data_ref.dhg));
215
216 BOOST_CHECK(data.Fcrb[0].isApprox(data_ref.dFdq));
217 BOOST_CHECK(data.dFdv.isApprox(data_ref.dFdv));
218 BOOST_CHECK(data.dFda.isApprox(data_ref.dFda));
219 BOOST_CHECK(dh_dq.isApprox(dh_dq_ref));
220 BOOST_CHECK(dhdot_dq.isApprox(dhdot_dq_ref));
221 BOOST_CHECK(dhdot_dv.isApprox(dhdot_dv_ref));
222 BOOST_CHECK(dhdot_da.isApprox(dhdot_da_ref));
223 }
224
225 BOOST_AUTO_TEST_CASE(test_retrieve_centroidal_derivatives_fromABA)
226 {
227 pinocchio::Model model;
228 pinocchio::buildModels::humanoidRandom(model);
229 pinocchio::Data data(model), data_ref(model), data_rnea(model);
230
231 model.lowerPositionLimit.head<7>().fill(-1.);
232 model.upperPositionLimit.head<7>().fill(1.);
233
234 Eigen::VectorXd q = pinocchio::randomConfiguration(model);
235 Eigen::VectorXd v = Eigen::VectorXd::Random(model.nv);
236 Eigen::VectorXd a = Eigen::VectorXd::Random(model.nv);
237
238 pinocchio::Data::Matrix6x dh_dq(6, model.nv), dhdot_dq(6, model.nv), dhdot_dv(6, model.nv),
239 dhdot_da(6, model.nv);
240 pinocchio::Data::Matrix6x dh_dq_ref(6, model.nv), dhdot_dq_ref(6, model.nv),
241 dhdot_dv_ref(6, model.nv), dhdot_da_ref(6, model.nv);
242
243 pinocchio::computeCentroidalDynamicsDerivatives(
244 model, data_ref, q, v, a, dh_dq_ref, dhdot_dq_ref, dhdot_dv_ref, dhdot_da_ref);
245
246 Eigen::VectorXd tau = rnea(model, data_rnea, q, v, a);
247 pinocchio::computeABADerivatives(model, data, q, v, tau);
248 pinocchio::computeRNEADerivatives(model, data_rnea, q, v, a);
249 pinocchio::getCentroidalDynamicsDerivatives(model, data, dh_dq, dhdot_dq, dhdot_dv, dhdot_da);
250
251 BOOST_CHECK(data.J.isApprox(data_ref.J));
252 BOOST_CHECK(data.dVdq.isApprox(data_rnea.dVdq));
253 BOOST_CHECK(data.dAdq.isApprox(data_rnea.dAdq));
254 BOOST_CHECK(data.dAdv.isApprox(data_rnea.dAdv));
255 BOOST_CHECK(data.dFdq.isApprox(data_rnea.dFdq));
256 BOOST_CHECK(data.dFdv.isApprox(data_rnea.dFdv));
257 BOOST_CHECK(data.dFda.isApprox(data_rnea.dFda));
258
259 for (pinocchio::Model::JointIndex k = 1; k < (pinocchio::Model::JointIndex)model.njoints; ++k)
260 {
261 BOOST_CHECK(data.oYcrb[k].isApprox(data_ref.oYcrb[k]));
262 BOOST_CHECK(data.oh[k].isApprox(data_ref.oh[k]));
263 const pinocchio::Force & force_ref = data_ref.of[k];
264 const pinocchio::Force gravity_contribution = data.oYcrb[k] * (-model.gravity);
265 const pinocchio::Force force = data.of[k] - gravity_contribution;
266 BOOST_CHECK(force.isApprox(force_ref));
267 }
268
269 BOOST_CHECK(data.com[0].isApprox(data_ref.com[0]));
270
271 BOOST_CHECK(data.hg.isApprox(data_ref.hg));
272 BOOST_CHECK(data.dhg.isApprox(data_ref.dhg));
273
274 BOOST_CHECK(data.Fcrb[0].isApprox(data_ref.dFdq));
275 BOOST_CHECK(data.dFdv.isApprox(data_ref.dFdv));
276 BOOST_CHECK(data.dFda.isApprox(data_ref.dFda));
277 BOOST_CHECK(dh_dq.isApprox(dh_dq_ref));
278 BOOST_CHECK(dhdot_dq.isApprox(dhdot_dq_ref));
279 BOOST_CHECK(dhdot_dv.isApprox(dhdot_dv_ref));
280 BOOST_CHECK(dhdot_da.isApprox(dhdot_da_ref));
281 }
282
283 BOOST_AUTO_TEST_SUITE_END()
284