timings-derivatives.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018-2020 CNRS INRIA
3 //
4 
5 #include "pinocchio/algorithm/joint-configuration.hpp"
6 #include "pinocchio/algorithm/kinematics.hpp"
7 #include "pinocchio/algorithm/kinematics-derivatives.hpp"
8 #include "pinocchio/algorithm/rnea-derivatives.hpp"
9 #include "pinocchio/algorithm/aba-derivatives.hpp"
10 #include "pinocchio/algorithm/aba.hpp"
11 #include "pinocchio/algorithm/rnea.hpp"
12 #include "pinocchio/algorithm/crba.hpp"
13 #include "pinocchio/algorithm/cholesky.hpp"
14 #include "pinocchio/parsers/urdf.hpp"
15 #include "pinocchio/parsers/sample-models.hpp"
16 #include "pinocchio/container/aligned-vector.hpp"
17 
18 #include <iostream>
19 
20 #include "pinocchio/utils/timer.hpp"
21 
22 template<typename Matrix1, typename Matrix2, typename Matrix3>
24  const Eigen::VectorXd & q,
25  const Eigen::VectorXd & v,
26  const Eigen::VectorXd & a,
27  const Eigen::MatrixBase<Matrix1> & _drnea_dq,
28  const Eigen::MatrixBase<Matrix2> & _drnea_dv,
29  const Eigen::MatrixBase<Matrix3> & _drnea_da)
30 {
31  Matrix1 & drnea_dq = PINOCCHIO_EIGEN_CONST_CAST(Matrix1,_drnea_dq);
32  Matrix2 & drnea_dv = PINOCCHIO_EIGEN_CONST_CAST(Matrix2,_drnea_dv);
33  Matrix3 & drnea_da = PINOCCHIO_EIGEN_CONST_CAST(Matrix3,_drnea_da);
34 
35  using namespace Eigen;
36  VectorXd v_eps(VectorXd::Zero(model.nv));
37  VectorXd q_plus(model.nq);
38  VectorXd tau_plus(model.nv);
39  const double alpha = 1e-8;
40 
41  VectorXd tau0 = rnea(model,data_fd,q,v,a);
42 
43  // dRNEA/dq
44  for(int k = 0; k < model.nv; ++k)
45  {
46  v_eps[k] += alpha;
47  q_plus = integrate(model,q,v_eps);
48  tau_plus = rnea(model,data_fd,q_plus,v,a);
49 
50  drnea_dq.col(k) = (tau_plus - tau0)/alpha;
51  v_eps[k] -= alpha;
52  }
53 
54  // dRNEA/dv
55  VectorXd v_plus(v);
56  for(int k = 0; k < model.nv; ++k)
57  {
58  v_plus[k] += alpha;
59  tau_plus = rnea(model,data_fd,q,v_plus,a);
60 
61  drnea_dv.col(k) = (tau_plus - tau0)/alpha;
62  v_plus[k] -= alpha;
63  }
64 
65  // dRNEA/da
66  drnea_da = crba(model,data_fd,q);
67  drnea_da.template triangularView<Eigen::StrictlyLower>()
68  = drnea_da.transpose().template triangularView<Eigen::StrictlyLower>();
69 
70 }
71 
72 void aba_fd(const pinocchio::Model & model, pinocchio::Data & data_fd,
73  const Eigen::VectorXd & q,
74  const Eigen::VectorXd & v,
75  const Eigen::VectorXd & tau,
76  Eigen::MatrixXd & daba_dq,
77  Eigen::MatrixXd & daba_dv,
78  pinocchio::Data::RowMatrixXs & daba_dtau)
79 {
80  using namespace Eigen;
81  VectorXd v_eps(VectorXd::Zero(model.nv));
82  VectorXd q_plus(model.nq);
83  VectorXd a_plus(model.nv);
84  const double alpha = 1e-8;
85 
86  VectorXd a0 = aba(model,data_fd,q,v,tau);
87 
88  // dABA/dq
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  daba_dq.col(k) = (a_plus - a0)/alpha;
96  v_eps[k] -= alpha;
97  }
98 
99  // dABA/dv
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  daba_dv.col(k) = (a_plus - a0)/alpha;
107  v_plus[k] -= alpha;
108  }
109 
110  // dABA/dtau
111  daba_dtau = computeMinverse(model,data_fd,q);
112 }
113 
114 int main(int argc, const char ** argv)
115 {
116  using namespace Eigen;
117  using namespace pinocchio;
118 
120  #ifdef NDEBUG
121  const int NBT = 1000*100;
122  #else
123  const int NBT = 1;
124  std::cout << "(the time score in debug mode is not relevant) " << std::endl;
125  #endif
126 
127  Model model;
128 
129  std::string filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.urdf");
130  if(argc>1) filename = argv[1];
131  bool with_ff = true;
132 
133  if(argc>2)
134  {
135  const std::string ff_option = argv[2];
136  if(ff_option == "-no-ff")
137  with_ff = false;
138  }
139 
140  if( filename == "HS")
141  buildModels::humanoidRandom(model,true);
142  else
143  if(with_ff)
145 // pinocchio::urdf::buildModel(filename,JointModelRX(),model);
146  else
147  pinocchio::urdf::buildModel(filename,model);
148  std::cout << "nq = " << model.nq << std::endl;
149  std::cout << "nv = " << model.nv << std::endl;
150 
151  Data data(model);
152  VectorXd qmax = Eigen::VectorXd::Ones(model.nq);
153 
158 
159  for(size_t i=0;i<NBT;++i)
160  {
161  qs[i] = randomConfiguration(model,-qmax,qmax);
162  qdots[i] = Eigen::VectorXd::Random(model.nv);
163  qddots[i] = Eigen::VectorXd::Random(model.nv);
164  taus[i] = Eigen::VectorXd::Random(model.nv);
165  }
166 
167  PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(MatrixXd) drnea_dq(MatrixXd::Zero(model.nv,model.nv));
168  PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(MatrixXd) drnea_dv(MatrixXd::Zero(model.nv,model.nv));
169  MatrixXd drnea_da(MatrixXd::Zero(model.nv,model.nv));
170 
171  MatrixXd daba_dq(MatrixXd::Zero(model.nv,model.nv));
172  MatrixXd daba_dv(MatrixXd::Zero(model.nv,model.nv));
173  Data::RowMatrixXs daba_dtau(Data::RowMatrixXs::Zero(model.nv,model.nv));
174 
175  timer.tic();
176  SMOOTH(NBT)
177  {
178  forwardKinematics(model,data,qs[_smooth],qdots[_smooth],qddots[_smooth]);
179  }
180  std::cout << "FK= \t\t"; timer.toc(std::cout,NBT);
181 
182  timer.tic();
183  SMOOTH(NBT)
184  {
185  computeForwardKinematicsDerivatives(model,data,qs[_smooth],qdots[_smooth],qddots[_smooth]);
186  }
187  std::cout << "FK derivatives= \t\t"; timer.toc(std::cout,NBT);
188 
189  timer.tic();
190  SMOOTH(NBT)
191  {
192  rnea(model,data,qs[_smooth],qdots[_smooth],qddots[_smooth]);
193  }
194  std::cout << "RNEA= \t\t"; timer.toc(std::cout,NBT);
195 
196  timer.tic();
197  SMOOTH(NBT)
198  {
199  computeRNEADerivatives(model,data,qs[_smooth],qdots[_smooth],qddots[_smooth],
200  drnea_dq,drnea_dv,drnea_da);
201  }
202  std::cout << "RNEA derivatives= \t\t"; timer.toc(std::cout,NBT);
203 
204  timer.tic();
205  SMOOTH(NBT/100)
206  {
207  rnea_fd(model,data,qs[_smooth],qdots[_smooth],qddots[_smooth],
208  drnea_dq,drnea_dv,drnea_da);
209  }
210  std::cout << "RNEA finite differences= \t\t"; timer.toc(std::cout,NBT/100);
211 
212  timer.tic();
213  SMOOTH(NBT)
214  {
215  aba(model,data,qs[_smooth],qdots[_smooth],taus[_smooth]);
216  }
217  std::cout << "ABA= \t\t"; timer.toc(std::cout,NBT);
218 
219  timer.tic();
220  SMOOTH(NBT)
221  {
222  computeABADerivatives(model,data,qs[_smooth],qdots[_smooth],taus[_smooth],
223  daba_dq,daba_dv,daba_dtau);
224  }
225  std::cout << "ABA derivatives= \t\t"; timer.toc(std::cout,NBT);
226 
227  timer.tic();
228  SMOOTH(NBT)
229  {
230  aba_fd(model,data,qs[_smooth],qdots[_smooth],taus[_smooth],
231  daba_dq,daba_dv,daba_dtau);
232  }
233  std::cout << "ABA finite differences= \t\t"; timer.toc(std::cout,NBT);
234 
235  timer.tic();
236  SMOOTH(NBT)
237  {
238  computeMinverse(model,data,qs[_smooth]);
239  }
240  std::cout << "M.inverse() from ABA = \t\t"; timer.toc(std::cout,NBT);
241 
242  MatrixXd Minv(model.nv,model.nv); Minv.setZero();
243  timer.tic();
244  SMOOTH(NBT)
245  {
246  crba(model,data,qs[_smooth]);
247  cholesky::decompose(model,data);
248  cholesky::computeMinv(model,data,Minv);
249  }
250  std::cout << "Minv from Cholesky = \t\t"; timer.toc(std::cout,NBT);
251 
252  std::cout << "--" << std::endl;
253  return 0;
254 }
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...
double toc()
Definition: timer.hpp:68
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & crba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the upper triangular part of the joint space inertia matrix M by using the Composite Rigid B...
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor|Options > RowMatrixXs
Mat & computeMinv(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Mat > &Minv)
Computes the inverse of the joint space inertia matrix M from its Cholesky factorization.
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.
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...
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & decompose(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Compute the Cholesky decomposition of the joint space inertia matrix M contained in data...
int main(int argc, const char **argv)
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.
data
#define PINOCCHIO_MODEL_DIR
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
void tic()
Definition: timer.hpp:63
void forwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Update the joint placements according to the current 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)
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...
#define SMOOTH(s)
Definition: timer.hpp:38
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
Build the model from a URDF file with a particular joint as root of the model tree inside the model g...
void aba_fd(const pinocchio::Model &model, pinocchio::Data &data_fd, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &tau, Eigen::MatrixXd &daba_dq, Eigen::MatrixXd &daba_dv, pinocchio::Data::RowMatrixXs &daba_dtau)
Main pinocchio namespace.
Definition: timings.cpp:30
#define PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(D)
Similar to macro PINOCCHIO_EIGEN_PLAIN_TYPE but with guaranty to provite a row major type...
int nv
Dimension of the velocity vector space.
void rnea_fd(const pinocchio::Model &model, pinocchio::Data &data_fd, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &a, const Eigen::MatrixBase< Matrix1 > &_drnea_dq, const Eigen::MatrixBase< Matrix2 > &_drnea_dv, const Eigen::MatrixBase< Matrix3 > &_drnea_da)
JointModelFreeFlyerTpl< double > JointModelFreeFlyer
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.


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