compute-all-terms.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2021 CNRS INRIA
3 //
4 
5 #include "pinocchio/spatial/fwd.hpp"
6 #include "pinocchio/spatial/se3.hpp"
7 #include "pinocchio/multibody/visitor.hpp"
8 #include "pinocchio/multibody/model.hpp"
9 #include "pinocchio/multibody/data.hpp"
10 #include "pinocchio/algorithm/crba.hpp"
11 #include "pinocchio/algorithm/centroidal.hpp"
12 #include "pinocchio/algorithm/rnea.hpp"
13 #include "pinocchio/algorithm/jacobian.hpp"
14 #include "pinocchio/algorithm/compute-all-terms.hpp"
15 #include "pinocchio/parsers/sample-models.hpp"
16 #include "pinocchio/utils/timer.hpp"
17 
18 #include <boost/test/unit_test.hpp>
19 
20 using namespace pinocchio;
21 
22 BOOST_AUTO_TEST_SUITE( BOOST_TEST_MODULE )
23 
24 void run_test(const Model & model, const Eigen::VectorXd & q, const Eigen::VectorXd & v)
25 {
26  pinocchio::Data data(model);
27  pinocchio::Data data_other(model);
28 
29  computeAllTerms(model,data,q,v);
30 
31  nonLinearEffects(model,data_other,q,v);
32  crba(model,data_other,q);
33  getJacobianComFromCrba(model, data_other);
34  computeJointJacobiansTimeVariation(model,data_other,q,v);
35  centerOfMass(model, data_other, q, v, true);
36  computeKineticEnergy(model, data_other, q, v);
37  computePotentialEnergy(model, data_other, q);
38  dccrba(model, data_other, q, v);
39  computeGeneralizedGravity(model, data_other, q);
40 
41  BOOST_CHECK(data.nle.isApprox(data_other.nle));
42  BOOST_CHECK(Eigen::MatrixXd(data.M.triangularView<Eigen::Upper>())
43  .isApprox(Eigen::MatrixXd(data_other.M.triangularView<Eigen::Upper>())));
44  BOOST_CHECK(data.J.isApprox(data_other.J));
45  BOOST_CHECK(data.dJ.isApprox(data_other.dJ));
46  BOOST_CHECK(data.Jcom.isApprox(data_other.Jcom));
47  BOOST_CHECK(data.Ag.isApprox(data_other.Ag));
48  BOOST_CHECK(data.dAg.isApprox(data_other.dAg));
49  BOOST_CHECK(data.hg.isApprox(data_other.hg));
50  BOOST_CHECK(data.Ig.isApprox(data_other.Ig));
51  BOOST_CHECK(data.g.isApprox(data_other.g));
52 
53  for(int k=0; k<model.njoints; ++k)
54  {
55  BOOST_CHECK(data.com[(size_t)k].isApprox(data_other.com[(size_t)k]));
56  BOOST_CHECK(data.vcom[(size_t)k].isApprox(data_other.vcom[(size_t)k]));
57  BOOST_CHECK_CLOSE(data.mass[(size_t)k], data_other.mass[(size_t)k], 1e-12);
58  }
59 
60  BOOST_CHECK_CLOSE(data.kinetic_energy, data_other.kinetic_energy, 1e-12);
61  BOOST_CHECK_CLOSE(data.potential_energy, data_other.potential_energy, 1e-12);
62 }
63 
64 BOOST_AUTO_TEST_CASE( test_against_algo )
65 {
66  using namespace Eigen;
67 
69 
70  VectorXd q(VectorXd::Random(model.nq));
71  VectorXd v(VectorXd::Random(model.nv));
72 
73  // -------
74  q.setZero();
75  v.setZero();
76 
77  run_test(model,q,v);
78 
79  // -------
80  q.setZero();
81  v.setOnes();
82 
83  run_test(model,q,v);
84 
85  // -------
86  q.setOnes();
87  q.segment<4>(3).normalize();
88  v.setOnes();
89 
90  run_test(model,q,v);
91 
92  // -------
93  q.setRandom();
94  q.segment<4>(3).normalize();
95  v.setRandom();
96 
97  run_test(model,q,v);
98 }
99 
100 BOOST_AUTO_TEST_SUITE_END()
Matrix6x dJ
Derivative of the Jacobian with respect to the time.
Scalar computePotentialEnergy(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Computes the potential energy of the system, i.e. the potential energy linked to the gravity field...
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix3x & getJacobianComFromCrba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Extracts both the jacobian of the center of mass (CoM), the total mass of the system and the CoM posi...
void computeAllTerms(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes efficiently all the terms needed for dynamic simulation. It is equivalent to the call at the...
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...
VectorXs g
Vector of generalized gravity (dim model.nv).
Matrix6x J
Jacobian of joint placements.
bool isApprox(const ForceDense< M2 > &f, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
data
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
bool isApprox(const Derived &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
VectorXs nle
Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis...
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & dccrba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the time derivative of the Centroidal Momentum Matrix according to the current configuration...
Matrix3x Jcom
Jacobian of center of mass.
MatrixXs M
The joint space inertia matrix (a square matrix of dim model.nv).
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeJointJacobiansTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the full model Jacobian variations with respect to time. It corresponds to dJ/dt which depen...
Matrix6x dAg
Centroidal Momentum Matrix Time Variation.
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & computeGeneralizedGravity(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the generalized gravity contribution of the Lagrangian dynamics:
void run_test(const Model &model, const Eigen::VectorXd &q, const Eigen::VectorXd &v)
Scalar kinetic_energy
Kinetic energy of the model.
Main pinocchio namespace.
Definition: timings.cpp:30
Scalar computeKineticEnergy(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Computes the kinetic energy of the system. The result is accessible through data.kinetic_energy.
Matrix6x Ag
Centroidal Momentum Matrix.
int nv
Dimension of the velocity vector space.
BOOST_AUTO_TEST_CASE(test_against_algo)
Inertia Ig
Centroidal Composite Rigid Body Inertia.
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & centerOfMass(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const bool computeSubtreeComs=true)
Computes the center of mass position of a given model according to a particular joint configuration...
void normalize(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &qout)
Normalize a configuration vector.
Scalar potential_energy
Potential energy of the model.
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & nonLinearEffects(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the non-linear effects (Corriolis, centrifual and gravitationnal effects), also called the bias terms of the Lagrangian dynamics:
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
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 ...


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