energy.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2016-2020 CNRS INRIA
3 //
4 
5 #include "pinocchio/algorithm/energy.hpp"
6 #include "pinocchio/algorithm/crba.hpp"
7 #include "pinocchio/algorithm/joint-configuration.hpp"
8 #include "pinocchio/algorithm/center-of-mass.hpp"
9 
10 #include "pinocchio/parsers/sample-models.hpp"
11 
12 #include <boost/test/unit_test.hpp>
13 #include <boost/utility/binary.hpp>
14 #include <boost/test/floating_point_comparison.hpp>
15 
16 BOOST_AUTO_TEST_SUITE ( BOOST_TEST_MODULE )
17 
18 BOOST_AUTO_TEST_CASE(test_kinetic_energy)
19 {
20  using namespace Eigen;
21  using namespace pinocchio;
22 
25  pinocchio::Data data(model);
26 
27  const VectorXd qmax = VectorXd::Ones(model.nq);
28  VectorXd q = randomConfiguration(model,-qmax,qmax);
29  VectorXd v = VectorXd::Ones(model.nv);
30 
31  data.M.fill(0); crba(model,data,q);
32  data.M.triangularView<Eigen::StrictlyLower>()
33  = data.M.transpose().triangularView<Eigen::StrictlyLower>();
34 
35  double kinetic_energy_ref = 0.5 * v.transpose() * data.M * v;
36  double kinetic_energy = computeKineticEnergy(model, data, q, v);
37 
38  BOOST_CHECK_SMALL(kinetic_energy_ref - kinetic_energy, 1e-12);
39 }
40 
41 BOOST_AUTO_TEST_CASE(test_potential_energy)
42 {
43  using namespace Eigen;
44  using namespace pinocchio;
45 
48  pinocchio::Data data(model), data_ref(model);
49 
50  const VectorXd qmax = VectorXd::Ones(model.nq);
51  VectorXd q = randomConfiguration(model,-qmax,qmax);
52 
53  double potential_energy = computePotentialEnergy(model, data, q);
54  centerOfMass(model,data_ref,q);
55 
56  double potential_energy_ref = -data_ref.mass[0] * (data_ref.com[0].dot(model.gravity.linear()));
57 
58  BOOST_CHECK_SMALL(potential_energy_ref - potential_energy, 1e-12);
59 }
60 
61 BOOST_AUTO_TEST_SUITE_END()
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...
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...
q
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.
data
ConstLinearType linear() const
Definition: motion-base.hpp:22
MatrixXs M
The joint space inertia matrix (a square matrix of dim model.nv).
Motion gravity
Spatial gravity 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.
int nv
Dimension of the velocity vector space.
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...
BOOST_AUTO_TEST_CASE(test_kinetic_energy)
Definition: energy.cpp:18
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.
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