aba-derivatives.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018-2020 CNRS INRIA
3 //
4 
5 #include "pinocchio/multibody/model.hpp"
6 #include "pinocchio/multibody/data.hpp"
7 #include "pinocchio/algorithm/jacobian.hpp"
8 #include "pinocchio/algorithm/joint-configuration.hpp"
9 #include "pinocchio/algorithm/kinematics.hpp"
10 #include "pinocchio/algorithm/kinematics-derivatives.hpp"
11 #include "pinocchio/algorithm/rnea.hpp"
12 #include "pinocchio/algorithm/rnea-derivatives.hpp"
13 #include "pinocchio/algorithm/aba.hpp"
14 #include "pinocchio/algorithm/aba-derivatives.hpp"
15 #include "pinocchio/algorithm/crba.hpp"
16 #include "pinocchio/parsers/sample-models.hpp"
17 
18 #include <iostream>
19 
20 #include <boost/test/unit_test.hpp>
21 #include <boost/utility/binary.hpp>
22 
23 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
24 
25 BOOST_AUTO_TEST_CASE(test_aba_derivatives)
26 {
27  using namespace Eigen;
28  using namespace pinocchio;
29 
30  Model model;
32 
33  Data data(model), data_ref(model);
34 
35  model.lowerPositionLimit.head<3>().fill(-1.);
36  model.upperPositionLimit.head<3>().fill(1.);
38  VectorXd v(VectorXd::Random(model.nv));
39  VectorXd tau(VectorXd::Random(model.nv));
40  VectorXd a(aba(model,data_ref,q,v,tau));
41 
42  MatrixXd aba_partial_dq(model.nv,model.nv); aba_partial_dq.setZero();
43  MatrixXd aba_partial_dv(model.nv,model.nv); aba_partial_dv.setZero();
44  Data::RowMatrixXs aba_partial_dtau(model.nv,model.nv); aba_partial_dtau.setZero();
45 
46  computeABADerivatives(model, data, q, v, tau, aba_partial_dq, aba_partial_dv, aba_partial_dtau);
47  computeRNEADerivatives(model,data_ref,q,v,a);
48  for(Model::JointIndex k = 1; k < (Model::JointIndex)model.njoints; ++k)
49  {
50  BOOST_CHECK(data.oMi[k].isApprox(data_ref.oMi[k]));
51  BOOST_CHECK(data.v[k].isApprox(data_ref.v[k]));
52  BOOST_CHECK(data.ov[k].isApprox(data_ref.ov[k]));
53  BOOST_CHECK(data.oa_gf[k].isApprox(data_ref.oa_gf[k]));
54  BOOST_CHECK(data.of[k].isApprox(data_ref.of[k]));
55  BOOST_CHECK(data.oYcrb[k].isApprox(data_ref.oYcrb[k]));
56  BOOST_CHECK(data.doYcrb[k].isApprox(data_ref.doYcrb[k]));
57  }
58 
59  computeJointJacobians(model,data_ref,q);
60  BOOST_CHECK(data.J.isApprox(data_ref.J));
61 
62  aba(model,data_ref,q,v,tau);
63  BOOST_CHECK(data.ddq.isApprox(data_ref.ddq));
64 
65  computeMinverse(model,data_ref,q);
66  data_ref.Minv.triangularView<Eigen::StrictlyLower>()
67  = data_ref.Minv.transpose().triangularView<Eigen::StrictlyLower>();
68 
69  BOOST_CHECK(aba_partial_dtau.isApprox(data_ref.Minv));
70 
71  BOOST_CHECK(data.J.isApprox(data_ref.J));
72  BOOST_CHECK(data.dJ.isApprox(data_ref.dJ));
73  BOOST_CHECK(data.dVdq.isApprox(data_ref.dVdq));
74  BOOST_CHECK(data.dAdq.isApprox(data_ref.dAdq));
75  BOOST_CHECK(data.dAdv.isApprox(data_ref.dAdv));
76  BOOST_CHECK(data.dtau_dq.isApprox(data_ref.dtau_dq));
77  BOOST_CHECK(data.dtau_dv.isApprox(data_ref.dtau_dv));
78 
79  MatrixXd aba_partial_dq_fd(model.nv,model.nv); aba_partial_dq_fd.setZero();
80  MatrixXd aba_partial_dv_fd(model.nv,model.nv); aba_partial_dv_fd.setZero();
81  MatrixXd aba_partial_dtau_fd(model.nv,model.nv); aba_partial_dtau_fd.setZero();
82 
83  Data data_fd(model);
84  VectorXd a0 = aba(model,data_fd,q,v,tau);
85  VectorXd v_eps(VectorXd::Zero(model.nv));
86  VectorXd q_plus(model.nq);
87  VectorXd a_plus(model.nv);
88  const double alpha = 1e-8;
89  for(int k = 0; k < model.nv; ++k)
90  {
91  v_eps[k] += alpha;
92  q_plus = integrate(model,q,v_eps);
93  a_plus = aba(model,data_fd,q_plus,v,tau);
94 
95  aba_partial_dq_fd.col(k) = (a_plus - a0)/alpha;
96  v_eps[k] -= alpha;
97  }
98  BOOST_CHECK(aba_partial_dq.isApprox(aba_partial_dq_fd,sqrt(alpha)));
99 
100  VectorXd v_plus(v);
101  for(int k = 0; k < model.nv; ++k)
102  {
103  v_plus[k] += alpha;
104  a_plus = aba(model,data_fd,q,v_plus,tau);
105 
106  aba_partial_dv_fd.col(k) = (a_plus - a0)/alpha;
107  v_plus[k] -= alpha;
108  }
109  BOOST_CHECK(aba_partial_dv.isApprox(aba_partial_dv_fd,sqrt(alpha)));
110 
111  VectorXd tau_plus(tau);
112  for(int k = 0; k < model.nv; ++k)
113  {
114  tau_plus[k] += alpha;
115  a_plus = aba(model,data_fd,q,v,tau_plus);
116 
117  aba_partial_dtau_fd.col(k) = (a_plus - a0)/alpha;
118  tau_plus[k] -= alpha;
119  }
120  BOOST_CHECK(aba_partial_dtau.isApprox(aba_partial_dtau_fd,sqrt(alpha)));
121 }
122 
123 BOOST_AUTO_TEST_CASE(test_aba_minimal_argument)
124 {
125  using namespace Eigen;
126  using namespace pinocchio;
127 
128  Model model;
130 
131  Data data(model), data_ref(model);
132 
133  model.lowerPositionLimit.head<3>().fill(-1.);
134  model.upperPositionLimit.head<3>().fill(1.);
135  VectorXd q = randomConfiguration(model);
136  VectorXd v(VectorXd::Random(model.nv));
137  VectorXd tau(VectorXd::Random(model.nv));
138  VectorXd a(aba(model,data_ref,q,v,tau));
139 
140  MatrixXd aba_partial_dq(model.nv,model.nv); aba_partial_dq.setZero();
141  MatrixXd aba_partial_dv(model.nv,model.nv); aba_partial_dv.setZero();
142  Data::RowMatrixXs aba_partial_dtau(model.nv,model.nv); aba_partial_dtau.setZero();
143 
144  computeABADerivatives(model, data_ref, q, v, tau, aba_partial_dq, aba_partial_dv, aba_partial_dtau);
145 
146  computeABADerivatives(model, data, q, v, tau);
147 
148  BOOST_CHECK(data.J.isApprox(data_ref.J));
149  BOOST_CHECK(data.dJ.isApprox(data_ref.dJ));
150  BOOST_CHECK(data.dVdq.isApprox(data_ref.dVdq));
151  BOOST_CHECK(data.dAdq.isApprox(data_ref.dAdq));
152  BOOST_CHECK(data.dAdv.isApprox(data_ref.dAdv));
153  BOOST_CHECK(data.dtau_dq.isApprox(data_ref.dtau_dq));
154  BOOST_CHECK(data.dtau_dv.isApprox(data_ref.dtau_dv));
155  BOOST_CHECK(data.Minv.isApprox(aba_partial_dtau));
156  BOOST_CHECK(data.ddq_dq.isApprox(aba_partial_dq));
157  BOOST_CHECK(data.ddq_dv.isApprox(aba_partial_dv));
158 }
159 
160 BOOST_AUTO_TEST_CASE(test_aba_derivatives_fext)
161 {
162  using namespace Eigen;
163  using namespace pinocchio;
164 
165  Model model;
167 
168  Data data(model), data_ref(model);
169 
170  model.lowerPositionLimit.head<3>().fill(-1.);
171  model.upperPositionLimit.head<3>().fill(1.);
172  VectorXd q = randomConfiguration(model);
173  VectorXd v(VectorXd::Random(model.nv));
174  VectorXd tau(VectorXd::Random(model.nv));
175  VectorXd a(aba(model,data_ref,q,v,tau));
176 
177  typedef PINOCCHIO_ALIGNED_STD_VECTOR(Force) ForceVector;
178  ForceVector fext((size_t)model.njoints);
179  for(ForceVector::iterator it = fext.begin(); it != fext.end(); ++it)
180  (*it).setRandom();
181 
182  MatrixXd aba_partial_dq(model.nv,model.nv); aba_partial_dq.setZero();
183  MatrixXd aba_partial_dv(model.nv,model.nv); aba_partial_dv.setZero();
184  Data::RowMatrixXs aba_partial_dtau(model.nv,model.nv); aba_partial_dtau.setZero();
185 
186  computeABADerivatives(model, data, q, v, tau, fext,
187  aba_partial_dq, aba_partial_dv, aba_partial_dtau);
188 
189  aba(model,data_ref,q,v,tau,fext);
190 // updateGlobalPlacements(model, data_ref);
191 // for(size_t k =1; k < (size_t)model.njoints; ++k)
192 // {
193 // BOOST_CHECK(data.oMi[k].isApprox(data_ref.oMi[k]));
194 // BOOST_CHECK(daita.of[k].isApprox(data_ref.oMi[k].act(data.f[k])));
195 //
196 // }
197  BOOST_CHECK(data.ddq.isApprox(data_ref.ddq));
198 
199  computeABADerivatives(model,data_ref,q,v,tau);
200  BOOST_CHECK(aba_partial_dv.isApprox(data_ref.ddq_dv));
201  BOOST_CHECK(aba_partial_dtau.isApprox(data_ref.Minv));
202 
203  MatrixXd aba_partial_dq_fd(model.nv,model.nv); aba_partial_dq_fd.setZero();
204  MatrixXd aba_partial_dv_fd(model.nv,model.nv); aba_partial_dv_fd.setZero();
205  MatrixXd aba_partial_dtau_fd(model.nv,model.nv); aba_partial_dtau_fd.setZero();
206 
207  Data data_fd(model);
208  const VectorXd a0 = aba(model,data_fd,q,v,tau,fext);
209  VectorXd v_eps(VectorXd::Zero(model.nv));
210  VectorXd q_plus(model.nq);
211  VectorXd a_plus(model.nv);
212  const double alpha = 1e-8;
213  for(int k = 0; k < model.nv; ++k)
214  {
215  v_eps[k] += alpha;
216  q_plus = integrate(model,q,v_eps);
217  a_plus = aba(model,data_fd,q_plus,v,tau,fext);
218 
219  aba_partial_dq_fd.col(k) = (a_plus - a0)/alpha;
220  v_eps[k] -= alpha;
221  }
222  BOOST_CHECK(aba_partial_dq.isApprox(aba_partial_dq_fd,sqrt(alpha)));
223 
224  VectorXd v_plus(v);
225  for(int k = 0; k < model.nv; ++k)
226  {
227  v_plus[k] += alpha;
228  a_plus = aba(model,data_fd,q,v_plus,tau,fext);
229 
230  aba_partial_dv_fd.col(k) = (a_plus - a0)/alpha;
231  v_plus[k] -= alpha;
232  }
233  BOOST_CHECK(aba_partial_dv.isApprox(aba_partial_dv_fd,sqrt(alpha)));
234 
235  VectorXd tau_plus(tau);
236  for(int k = 0; k < model.nv; ++k)
237  {
238  tau_plus[k] += alpha;
239  a_plus = aba(model,data_fd,q,v,tau_plus,fext);
240 
241  aba_partial_dtau_fd.col(k) = (a_plus - a0)/alpha;
242  tau_plus[k] -= alpha;
243  }
244  BOOST_CHECK(aba_partial_dtau.isApprox(aba_partial_dtau_fd,sqrt(alpha)));
245 
246  // test the shortcut
247  Data data_shortcut(model);
248  computeABADerivatives(model,data_shortcut,q,v,tau,fext);
249  BOOST_CHECK(data_shortcut.ddq_dq.isApprox(aba_partial_dq));
250  BOOST_CHECK(data_shortcut.ddq_dv.isApprox(aba_partial_dv));
251  BOOST_CHECK(data_shortcut.Minv.isApprox(aba_partial_dtau));
252 }
253 
254 BOOST_AUTO_TEST_CASE(test_multiple_calls)
255 {
256  using namespace Eigen;
257  using namespace pinocchio;
258 
259  Model model;
261 
262  Data data1(model), data2(model);
263 
264  model.lowerPositionLimit.head<3>().fill(-1.);
265  model.upperPositionLimit.head<3>().fill(1.);
266  VectorXd q = randomConfiguration(model);
267  VectorXd v(VectorXd::Random(model.nv));
268  VectorXd tau(VectorXd::Random(model.nv));
269 
270  computeABADerivatives(model,data1,q,v,tau);
271  data2 = data1;
272 
273  for(int k = 0; k < 20; ++k)
274  {
275  computeABADerivatives(model,data1,q,v,tau);
276  }
277 
278  BOOST_CHECK(data1.J.isApprox(data2.J));
279  BOOST_CHECK(data1.dJ.isApprox(data2.dJ));
280  BOOST_CHECK(data1.dVdq.isApprox(data2.dVdq));
281  BOOST_CHECK(data1.dAdq.isApprox(data2.dAdq));
282  BOOST_CHECK(data1.dAdv.isApprox(data2.dAdv));
283 
284  BOOST_CHECK(data1.dFdq.isApprox(data2.dFdq));
285  BOOST_CHECK(data1.dFdv.isApprox(data2.dFdv));
286 
287  BOOST_CHECK(data1.dtau_dq.isApprox(data2.dtau_dq));
288  BOOST_CHECK(data1.dtau_dv.isApprox(data2.dtau_dv));
289 
290  BOOST_CHECK(data1.ddq_dq.isApprox(data2.ddq_dq));
291  BOOST_CHECK(data1.ddq_dv.isApprox(data2.ddq_dv));
292  BOOST_CHECK(data1.Minv.isApprox(data2.Minv));
293 }
294 
295 BOOST_AUTO_TEST_CASE(test_aba_derivatives_vs_kinematics_derivatives)
296 {
297  using namespace Eigen;
298  using namespace pinocchio;
299 
300  Model model;
302 
303  Data data(model), data_ref(model);
304 
305  model.lowerPositionLimit.head<3>().fill(-1.);
306  model.upperPositionLimit.head<3>().fill(1.);
307  VectorXd q = randomConfiguration(model);
308  VectorXd v(VectorXd::Random(model.nv));
309  VectorXd a(VectorXd::Random(model.nv));
310 
311  VectorXd tau = rnea(model,data_ref,q,v,a);
312 
314  MatrixXd aba_partial_dq(model.nv,model.nv); aba_partial_dq.setZero();
315  MatrixXd aba_partial_dv(model.nv,model.nv); aba_partial_dv.setZero();
316  MatrixXd aba_partial_dtau(model.nv,model.nv); aba_partial_dtau.setZero();
317 
318  computeABADerivatives(model,data,q,v,tau,aba_partial_dq,aba_partial_dv,aba_partial_dtau);
319  computeForwardKinematicsDerivatives(model,data_ref,q,v,a);
320 
321  BOOST_CHECK(data.J.isApprox(data_ref.J));
322  BOOST_CHECK(data.dJ.isApprox(data_ref.dJ));
323 
324  for(size_t k = 1; k < (size_t)model.njoints; ++k)
325  {
326  BOOST_CHECK(data.oMi[k].isApprox(data_ref.oMi[k]));
327  BOOST_CHECK(data.ov[k].isApprox(data_ref.ov[k]));
328  BOOST_CHECK(data.oa[k].isApprox(data_ref.oa[k]));
329  }
330 }
331 
332 BOOST_AUTO_TEST_SUITE_END()
Matrix6x dJ
Derivative of the Jacobian with respect to the time.
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & aba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &tau)
The Articulated-Body algorithm. It computes the forward dynamics, aka the joint accelerations given t...
q
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor|Options > RowMatrixXs
Matrix6x J
Jacobian of joint placements.
const DataTpl< Scalar, Options, JointCollectionTpl >::RowMatrixXs & computeMinverse(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the inverse of the joint space inertia matrix using Articulated Body formulation.
MatrixXs dtau_dv
Partial derivative of the joint torque vector with respect to the joint velocity. ...
Matrix6x dAdv
Variation of the spatial acceleration set with respect to the joint velocity.
void rnea(const int num_threads, ModelPoolTpl< Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< TangentVectorPool1 > &v, const Eigen::MatrixBase< TangentVectorPool2 > &a, const Eigen::MatrixBase< TangentVectorPool3 > &tau)
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques accordi...
void integrate(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const Eigen::MatrixBase< ReturnType > &qout)
Integrate a configuration vector for the specified model for a tangent vector during one unit time...
int njoints
Number of joints.
ConfigVectorType lowerPositionLimit
Lower joint configuration limit.
v
void randomConfiguration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &lowerLimits, const Eigen::MatrixBase< ConfigVectorIn2 > &upperLimits, const Eigen::MatrixBase< ReturnType > &qout)
Generate a configuration vector uniformly sampled among provided limits.
MatrixXs dtau_dq
Partial derivative of the joint torque vector with respect to the joint configuration.
data
RowMatrixXs Minv
The inverse of the joint space inertia matrix (a square matrix of dim model.nv).
MatrixXs ddq_dq
Partial derivative of the joint acceleration vector with respect to the joint configuration.
Matrix6x dFdq
Variation of the forceset with respect to the joint configuration.
Matrix6x dAdq
Variation of the spatial acceleration set with respect to the joint configuration.
bp::tuple computeRNEADerivatives(const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &a)
#define PINOCCHIO_ALIGNED_STD_VECTOR(Type)
pinocchio::JointIndex JointIndex
void computeForwardKinematicsDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a)
Computes all the terms required to compute the derivatives of the placement, spatial velocity and acc...
TangentVectorType ddq
The joint accelerations computed from ABA.
Matrix6x dFdv
Variation of the forceset with respect to the joint velocity.
BOOST_AUTO_TEST_CASE(test_aba_derivatives)
MatrixXs ddq_dv
Partial derivative of the joint acceleration vector with respect to the joint velocity.
Main pinocchio namespace.
Definition: timings.cpp:30
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeJointJacobians(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the full model Jacobian, i.e. the stack of all motion subspace expressed in the world frame...
int nv
Dimension of the velocity vector space.
list a
ConfigVectorType upperPositionLimit
Upper joint configuration limit.
void computeABADerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &tau, const Eigen::MatrixBase< MatrixType1 > &aba_partial_dq, const Eigen::MatrixBase< MatrixType2 > &aba_partial_dv, const Eigen::MatrixBase< MatrixType3 > &aba_partial_dtau)
The derivatives of the Articulated-Body algorithm.
void humanoidRandom(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true)
Create a humanoid kinematic tree with 6-DOF limbs and random joint placements.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
Definition: conversions.cpp:14
int nq
Dimension of the configuration vector representation.
Matrix6x dVdq
Variation of the spatial velocity set with respect to the joint configuration.
void fill(Eigen::Ref< MatType > mat, const typename MatType::Scalar &value)


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:02