centroidal-derivatives.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018-2019 INRIA
3 //
4 
5 #include "pinocchio/multibody/model.hpp"
6 #include "pinocchio/multibody/data.hpp"
7 #include "pinocchio/multibody/joint/joint-spherical.hpp"
8 #include "pinocchio/algorithm/crba.hpp"
9 #include "pinocchio/algorithm/centroidal.hpp"
10 #include "pinocchio/algorithm/centroidal-derivatives.hpp"
11 #include "pinocchio/algorithm/rnea-derivatives.hpp"
12 #include "pinocchio/algorithm/jacobian.hpp"
13 #include "pinocchio/algorithm/center-of-mass.hpp"
14 #include "pinocchio/algorithm/joint-configuration.hpp"
15 #include "pinocchio/parsers/sample-models.hpp"
16 #include "pinocchio/utils/timer.hpp"
17 
18 #include <iostream>
19 
20 #include <boost/test/unit_test.hpp>
21 #include <boost/utility/binary.hpp>
22 
23 template<typename JointModel>
26  const std::string & parent_name,
27  const std::string & name,
29  bool setRandomLimits = true)
30 {
31  using namespace pinocchio;
32  typedef typename JointModel::ConfigVector_t CV;
33  typedef typename JointModel::TangentVector_t TV;
34 
36 
37  if (setRandomLimits)
38  idx = model.addJoint(model.getJointId(parent_name),joint,
39  SE3::Random(),
40  name + "_joint",
41  TV::Random() + TV::Constant(1),
42  TV::Random() + TV::Constant(1),
43  CV::Random() - CV::Constant(1),
44  CV::Random() + CV::Constant(1)
45  );
46  else
47  idx = model.addJoint(model.getJointId(parent_name),joint,
48  placement, name + "_joint");
49 
50  model.addJointFrame(idx);
51 
53  model.addBodyFrame(name + "_body", idx);
54 }
55 
56 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
57 
58 BOOST_AUTO_TEST_CASE(test_centroidal_derivatives)
59 {
62  const std::string parent_name = model.names.back();
63  const std::string joint_name = "ee_spherical_joint";
64  addJointAndBody(model, pinocchio::JointModelSpherical(), parent_name , joint_name);
65 
66  pinocchio::Data data(model), data_ref(model);
67 
68  model.lowerPositionLimit.head<7>().fill(-1.);
69  model.upperPositionLimit.head<7>().fill( 1.);
70 
72  Eigen::VectorXd v = Eigen::VectorXd::Random(model.nv);
73  Eigen::VectorXd a = Eigen::VectorXd::Random(model.nv);
74 
76  dh_dq(6,model.nv),dhdot_dq(6,model.nv), dhdot_dv(6,model.nv), dhdot_da(6,model.nv);
78  dh_dq,dhdot_dq,dhdot_dv,dhdot_da);
79  pinocchio::ccrba(model,data_ref,q,v);
80 
81  for(size_t k = 0; k < (size_t)model.njoints; ++k)
82  {
83  BOOST_CHECK(data.oMi[k].isApprox(data_ref.oMi[k]));
84  BOOST_CHECK(data.oYcrb[k].isApprox(data_ref.oYcrb[k]));
85  }
86  BOOST_CHECK(dhdot_da.isApprox(data_ref.Ag));
87 
89  for(size_t k = 1; k < (size_t)model.njoints; ++k)
90  {
91  BOOST_CHECK(data.v[k].isApprox(data_ref.v[k]));
92  BOOST_CHECK(data.ov[k].isApprox(data.oMi[k].act(data_ref.v[k])));
93  BOOST_CHECK(data.oa[k].isApprox(data.oMi[k].act(data_ref.a[k])));
94  BOOST_CHECK(data.oh[k].isApprox(data.oMi[k].act(data_ref.h[k])));
95  }
96 
97  BOOST_CHECK(data.mass[0] == data_ref.mass[0]);
98  BOOST_CHECK(data.com[0].isApprox(data_ref.com[0]));
99 
100  BOOST_CHECK(data.oh[0].isApprox(data_ref.h[0]));
101  BOOST_CHECK(data.of[0].isApprox(data_ref.f[0]));
102 
103  BOOST_CHECK(data.hg.isApprox(data_ref.hg));
104  BOOST_CHECK(data.dhg.isApprox(data_ref.dhg));
105 
106  pinocchio::Data data_fd(model);
107 
108  const double eps = 1e-8;
110  const pinocchio::Force hg = data_fd.hg;
111  BOOST_CHECK(data.hg.isApprox(data_ref.hg));
112 
113  // Check dhdot_dq and dh_dq with finite differences
114  Eigen::VectorXd q_plus(model.nq,1);
115  Eigen::VectorXd v_eps(model.nv,1); v_eps.setZero();
116  pinocchio::Data::Matrix6x dhdot_dq_fd(6,model.nv);
117  pinocchio::Data::Matrix6x dh_dq_fd(6,model.nv);
118 
119  for(Eigen::DenseIndex k = 0; k < model.nv; ++k)
120  {
121  v_eps[k] = eps;
122  q_plus = pinocchio::integrate(model,q,v_eps);
123 
124  const pinocchio::Force & dhg_plus
125  = pinocchio::computeCentroidalMomentumTimeVariation(model,data_fd,q_plus,v,a);
126  const pinocchio::Force hg_plus = data_fd.hg;
127 
128  dhdot_dq_fd.col(k) = (dhg_plus - dhg).toVector()/eps;
129  dh_dq_fd.col(k) = (hg_plus - hg).toVector()/eps;
130  v_eps[k] = 0.;
131  }
132 
133  BOOST_CHECK(dhdot_dq.isApprox(dhdot_dq_fd,sqrt(eps)));
134  BOOST_CHECK(dh_dq.isApprox(dh_dq_fd,sqrt(eps)));
135  // Check dhdot_dv with finite differences
136  Eigen::VectorXd v_plus(v);
137  pinocchio::Data::Matrix6x dhdot_dv_fd(6,model.nv);
138 
139  for(Eigen::DenseIndex k = 0; k < model.nv; ++k)
140  {
141  v_plus[k] += eps;
142 
143  const pinocchio::Force & dhg_plus
144  = pinocchio::computeCentroidalMomentumTimeVariation(model,data_fd,q,v_plus,a);
145  dhdot_dv_fd.col(k) = (dhg_plus - dhg).toVector()/eps;
146 
147  v_plus[k] -= eps;
148  }
149 
150  BOOST_CHECK(dhdot_dv.isApprox(dhdot_dv_fd,sqrt(eps)));
151 
152  // Check dhdot_da with finite differences
153  Eigen::VectorXd a_plus(a);
154  pinocchio::Data::Matrix6x dhdot_da_fd(6,model.nv);
155 
156  for(Eigen::DenseIndex k = 0; k < model.nv; ++k)
157  {
158  a_plus[k] += eps;
159 
160  const pinocchio::Force & dhg_plus
161  = pinocchio::computeCentroidalMomentumTimeVariation(model,data_fd,q,v,a_plus);
162  dhdot_da_fd.col(k) = (dhg_plus - dhg).toVector()/eps;
163 
164  a_plus[k] -= eps;
165  }
166 
167  BOOST_CHECK(dhdot_da.isApprox(dhdot_da_fd,sqrt(eps)));
168 
169  pinocchio::computeRNEADerivatives(model,data_ref,q,v,a);
170  BOOST_CHECK(data.dAdv.isApprox(data_ref.dAdv));
171  BOOST_CHECK(data.dAdq.isApprox(data_ref.dAdq));
172  BOOST_CHECK(data.J.isApprox(data_ref.J));
173  BOOST_CHECK(data.dJ.isApprox(data_ref.dJ));
174  BOOST_CHECK(data.dVdq.isApprox(data_ref.dVdq));
175 }
176 
177 BOOST_AUTO_TEST_CASE(test_retrieve_centroidal_derivatives)
178 {
181  pinocchio::Data data(model), data_ref(model);
182 
183  model.lowerPositionLimit.head<7>().fill(-1.);
184  model.upperPositionLimit.head<7>().fill( 1.);
185 
187  Eigen::VectorXd v = Eigen::VectorXd::Random(model.nv);
188  Eigen::VectorXd a = Eigen::VectorXd::Random(model.nv);
189 
191  dh_dq(6,model.nv), dhdot_dq(6,model.nv), dhdot_dv(6,model.nv), dhdot_da(6,model.nv);
193  dh_dq_ref(6,model.nv), dhdot_dq_ref(6,model.nv), dhdot_dv_ref(6,model.nv), dhdot_da_ref(6,model.nv);
194 
196  dh_dq_ref, dhdot_dq_ref,dhdot_dv_ref,dhdot_da_ref);
197 
200  dh_dq, dhdot_dq,dhdot_dv,dhdot_da);
201 
202  BOOST_CHECK(data.J.isApprox(data_ref.J));
203 
205  {
206  BOOST_CHECK(data.oYcrb[k].isApprox(data_ref.oYcrb[k]));
207  pinocchio::Force force_ref = data_ref.of[k];
208  pinocchio::Force gravity_contribution = data.oYcrb[k] * (-model.gravity);
209  pinocchio::Force force = data.of[k] - gravity_contribution;
210  BOOST_CHECK(force.isApprox(force_ref));
211  }
212 
213  BOOST_CHECK(data.com[0].isApprox(data_ref.com[0]));
214 
215  BOOST_CHECK(data.hg.isApprox(data_ref.hg));
216  BOOST_CHECK(data.dhg.isApprox(data_ref.dhg));
217 
218  BOOST_CHECK(data.Fcrb[0].isApprox(data_ref.dFdq));
219  BOOST_CHECK(data.dFdv.isApprox(data_ref.dFdv));
220  BOOST_CHECK(data.dFda.isApprox(data_ref.dFda));
221  BOOST_CHECK(dh_dq.isApprox(dh_dq_ref));
222  BOOST_CHECK(dhdot_dq.isApprox(dhdot_dq_ref));
223  BOOST_CHECK(dhdot_dv.isApprox(dhdot_dv_ref));
224  BOOST_CHECK(dhdot_da.isApprox(dhdot_da_ref));
225 
226 }
227 
228 BOOST_AUTO_TEST_SUITE_END()
Matrix6x dJ
Derivative of the Jacobian with respect to the time.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
bool isApprox(const ForceDense< M2 > &f, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
void addJointAndBody(Model &model, const JointModelBase< D > &jmodel, const Model::JointIndex parent_id, const SE3 &joint_placement, const std::string &name, const Inertia &Y)
void computeCentroidalDynamicsDerivatives(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, const Eigen::MatrixBase< Matrix6xLike0 > &dh_dq, const Eigen::MatrixBase< Matrix6xLike1 > &dhdot_dq, const Eigen::MatrixBase< Matrix6xLike2 > &dhdot_dv, const Eigen::MatrixBase< Matrix6xLike3 > &dhdot_da)
Computes the analytical derivatives of the centroidal dynamics with respect to the joint configuratio...
FrameIndex addJointFrame(const JointIndex &joint_index, int previous_frame_index=-1)
Add a joint to the frame tree.
Matrix6x J
Jacobian of joint placements.
Matrix6x dAdv
Variation of the spatial acceleration set with respect to the joint velocity.
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...
static InertiaTpl Random()
int eps
Definition: dcrba.py:384
int njoints
Number of joints.
Matrix6x dFda
Variation of the forceset with respect to the joint acceleration.
std::vector< std::string > names
Name of joint i
ConfigVectorType lowerPositionLimit
Lower joint configuration limit.
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.
fill
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
const DataTpl< Scalar, Options, JointCollectionTpl >::Force & computeCentroidalMomentumTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Computes the Centroidal momemtum and its time derivatives, a.k.a. the total momenta of the system and...
void computeRNEADerivatives(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, const Eigen::MatrixBase< MatrixType1 > &rnea_partial_dq, const Eigen::MatrixBase< MatrixType2 > &rnea_partial_dv, const Eigen::MatrixBase< MatrixType3 > &rnea_partial_da)
Computes the partial derivatives of the Recursive Newton Euler Algorithms with respect to the joint c...
void getCentroidalDynamicsDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Matrix6xLike1 > &dh_dq, const Eigen::MatrixBase< Matrix6xLike1 > &dhdot_dq, const Eigen::MatrixBase< Matrix6xLike2 > &dhdot_dv, const Eigen::MatrixBase< Matrix6xLike3 > &dhdot_da)
Retrive the analytical derivatives of the centroidal dynamics from the RNEA derivatives. pinocchio::computeRNEADerivatives should have been called first.
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & ccrba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the Centroidal Momentum Matrix, the Composite Ridig Body Inertia as well as the centroidal m...
Matrix6x dFdq
Variation of the forceset with respect to the joint configuration.
JointIndex addJoint(const JointIndex parent, const JointModel &joint_model, const SE3 &joint_placement, const std::string &joint_name)
Add a joint to the kinematic tree with infinite bounds.
Matrix6x dAdq
Variation of the spatial acceleration set with respect to the joint configuration.
pinocchio::JointIndex JointIndex
static void addJointAndBody(pinocchio::Model &model, const pinocchio::JointModelBase< JointModel > &joint, const std::string &parent_name, const std::string &name, const pinocchio::SE3 placement=pinocchio::SE3::Random(), bool setRandomLimits=true)
Motion gravity
Spatial gravity of the model.
BOOST_AUTO_TEST_CASE(test_centroidal_derivatives)
Vec3f a
#define BOOST_TEST_MODULE
Matrix6x dFdv
Variation of the forceset with respect to the joint velocity.
Force dhg
Centroidal momentum time derivative.
Main pinocchio namespace.
Definition: timings.cpp:28
JointIndex getJointId(const std::string &name) const
Return the index of a joint given by its name.
Matrix6x Ag
Centroidal Momentum Matrix.
int nv
Dimension of the velocity vector space.
ConfigVectorType upperPositionLimit
Upper joint configuration limit.
void appendBodyToJoint(const JointIndex joint_index, const Inertia &Y, const SE3 &body_placement=SE3::Identity())
Append a body to a given joint of the kinematic tree.
Force hg
Centroidal momentum quantity.
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
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
JointCollectionTpl & model
int nq
Dimension of the configuration vector representation.
std::vector< Scalar > mass
Vector of subtree mass. In other words, mass[j] is the mass of the subtree supported by joint ...
Matrix6x dVdq
Variation of the spatial velocity set with respect to the joint configuration.
FrameIndex addBodyFrame(const std::string &body_name, const JointIndex &parentJoint, const SE3 &body_placement=SE3::Identity(), int previousFrame=-1)
Add a body to the frame tree.


pinocchio
Author(s):
autogenerated on Fri Jun 23 2023 02:38:29