joint-planar.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2020 CNRS INRIA
3 // Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 
6 #include "pinocchio/math/fwd.hpp"
13 
14 #include <boost/test/unit_test.hpp>
15 #include <iostream>
16 
17 using namespace pinocchio;
18 
19 template<typename D>
21  Model & model,
22  const JointModelBase<D> & jmodel,
24  const SE3 & joint_placement,
25  const std::string & joint_name,
26  const Inertia & Y)
27 {
29 
30  idx = model.addJoint(parent_id, jmodel, joint_placement, joint_name);
31  model.appendBodyToJoint(idx, Y);
32 }
33 
34 BOOST_AUTO_TEST_SUITE(JointPlanar)
35 
37 {
38  SE3 M(SE3::Random());
40 
41  MotionPlanar mp(1., 2., 3.);
42  Motion mp_dense(mp);
43 
44  BOOST_CHECK(M.act(mp).isApprox(M.act(mp_dense)));
45  BOOST_CHECK(M.actInv(mp).isApprox(M.actInv(mp_dense)));
46 
47  BOOST_CHECK(v.cross(mp).isApprox(v.cross(mp_dense)));
48 }
49 
51 {
52  using namespace pinocchio;
53  typedef SE3::Vector3 Vector3;
54  typedef Eigen::Matrix<double, 6, 1> Vector6;
55  typedef Eigen::Matrix<double, 4, 1> VectorPl;
56  typedef Eigen::Matrix<double, 7, 1> VectorFF;
57  typedef SE3::Matrix3 Matrix3;
58 
59  Model modelPlanar, modelFreeflyer;
60 
61  Inertia inertia(1., Vector3(0.5, 0., 0.0), Matrix3::Identity());
62  SE3 pos(1);
63  pos.translation() = SE3::LinearType(1., 0., 0.);
64 
65  addJointAndBody(modelPlanar, JointModelPlanar(), 0, SE3::Identity(), "planar", inertia);
66  addJointAndBody(modelFreeflyer, JointModelFreeFlyer(), 0, SE3::Identity(), "free-flyer", inertia);
67 
68  Data dataPlanar(modelPlanar);
69  Data dataFreeFlyer(modelFreeflyer);
70 
71  VectorPl q;
72  q << 1, 1, 0, 1; // Angle is PI /2;
73  VectorFF qff;
74  qff << 1, 1, 0, 0, 0, sqrt(2) / 2, sqrt(2) / 2;
75  Eigen::VectorXd v = Eigen::VectorXd::Ones(modelPlanar.nv);
76  Vector6 vff;
77  vff << 1, 1, 0, 0, 0, 1;
78  Eigen::VectorXd tauPlanar = Eigen::VectorXd::Ones(modelPlanar.nv);
79  Eigen::VectorXd tauff = Eigen::VectorXd::Ones(modelFreeflyer.nv);
80  Eigen::VectorXd aPlanar = Eigen::VectorXd::Ones(modelPlanar.nv);
81  Eigen::VectorXd aff(vff);
82 
83  forwardKinematics(modelPlanar, dataPlanar, q, v);
84  forwardKinematics(modelFreeflyer, dataFreeFlyer, qff, vff);
85 
86  computeAllTerms(modelPlanar, dataPlanar, q, v);
87  computeAllTerms(modelFreeflyer, dataFreeFlyer, qff, vff);
88 
89  BOOST_CHECK(dataFreeFlyer.oMi[1].isApprox(dataPlanar.oMi[1]));
90  BOOST_CHECK(dataFreeFlyer.liMi[1].isApprox(dataPlanar.liMi[1]));
91  BOOST_CHECK(dataFreeFlyer.Ycrb[1].matrix().isApprox(dataPlanar.Ycrb[1].matrix()));
92  BOOST_CHECK(dataFreeFlyer.f[1].toVector().isApprox(dataPlanar.f[1].toVector()));
93 
94  Eigen::VectorXd nle_expected_ff(3);
95  nle_expected_ff << dataFreeFlyer.nle[0], dataFreeFlyer.nle[1], dataFreeFlyer.nle[5];
96  BOOST_CHECK(nle_expected_ff.isApprox(dataPlanar.nle));
97  BOOST_CHECK(dataFreeFlyer.com[0].isApprox(dataPlanar.com[0]));
98 
99  // InverseDynamics == rnea
100  tauPlanar = rnea(modelPlanar, dataPlanar, q, v, aPlanar);
101  tauff = rnea(modelFreeflyer, dataFreeFlyer, qff, vff, aff);
102 
103  Vector3 tau_expected;
104  tau_expected << tauff(0), tauff(1), tauff(5);
105  BOOST_CHECK(tauPlanar.isApprox(tau_expected));
106 
107  // ForwardDynamics == aba
108  Eigen::VectorXd aAbaPlanar = aba(modelPlanar, dataPlanar, q, v, tauPlanar, Convention::WORLD);
109  Eigen::VectorXd aAbaFreeFlyer =
110  aba(modelFreeflyer, dataFreeFlyer, qff, vff, tauff, Convention::WORLD);
111  Vector3 a_expected;
112  a_expected << aAbaFreeFlyer[0], aAbaFreeFlyer[1], aAbaFreeFlyer[5];
113  BOOST_CHECK(aAbaPlanar.isApprox(a_expected));
114 
115  // crba
116  crba(modelPlanar, dataPlanar, q, Convention::WORLD);
117  crba(modelFreeflyer, dataFreeFlyer, qff, Convention::WORLD);
118 
119  Eigen::Matrix<double, 3, 3> M_expected;
120  M_expected.block<2, 2>(0, 0) = dataFreeFlyer.M.block<2, 2>(0, 0);
121  M_expected.block<1, 2>(2, 0) = dataFreeFlyer.M.block<1, 2>(5, 0);
122  M_expected.block<2, 1>(0, 2) = dataFreeFlyer.M.col(5).head<2>();
123  M_expected.block<1, 1>(2, 2) = dataFreeFlyer.M.col(5).tail<1>();
124 
125  BOOST_CHECK(dataPlanar.M.isApprox(M_expected));
126 
127  // Jacobian
128  Eigen::Matrix<double, 6, Eigen::Dynamic> jacobian_planar;
129  jacobian_planar.resize(6, 3);
130  jacobian_planar.setZero();
131  Eigen::Matrix<double, 6, Eigen::Dynamic> jacobian_ff;
132  jacobian_ff.resize(6, 6);
133  jacobian_ff.setZero();
134  computeJointJacobians(modelPlanar, dataPlanar, q);
135  computeJointJacobians(modelFreeflyer, dataFreeFlyer, qff);
136  getJointJacobian(modelPlanar, dataPlanar, 1, LOCAL, jacobian_planar);
137  getJointJacobian(modelFreeflyer, dataFreeFlyer, 1, LOCAL, jacobian_ff);
138 
139  Eigen::Matrix<double, 6, 3> jacobian_expected;
140  jacobian_expected << jacobian_ff.col(0), jacobian_ff.col(1), jacobian_ff.col(5);
141 
142  BOOST_CHECK(jacobian_planar.isApprox(jacobian_expected));
143 }
144 
145 BOOST_AUTO_TEST_SUITE_END()
pinocchio::InertiaTpl
Definition: spatial/fwd.hpp:58
pinocchio::DataTpl::M
MatrixXs M
The joint space inertia matrix (a square matrix of dim model.nv).
Definition: multibody/data.hpp:199
pinocchio::addJointAndBody
void addJointAndBody(Model &model, const JointModelBase< D > &jmodel, const Model::JointIndex parent_id, const SE3 &joint_placement, const std::string &name, const Inertia &Y)
Definition: model-generator.hpp:11
pinocchio::SE3Tpl< context::Scalar, context::Options >::Vector3
traits< SE3Tpl >::Vector3 Vector3
Definition: spatial/se3-tpl.hpp:55
pinocchio::JointModelFreeFlyer
JointModelFreeFlyerTpl< context::Scalar > JointModelFreeFlyer
Definition: multibody/joint/fwd.hpp:110
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio::forwardKinematics
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.
compute-all-terms.hpp
pinocchio::JointModelBase
Definition: joint-model-base.hpp:75
pinocchio::SE3Tpl< context::Scalar, context::Options >
pinocchio::Convention::WORLD
@ WORLD
pinocchio::crba
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & crba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Convention convention=Convention::LOCAL)
Computes the upper triangular part of the joint space inertia matrix M by using the Composite Rigid B...
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(spatial)
Definition: joint-planar.cpp:36
pinocchio::aba
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, const Convention convention=Convention::LOCAL)
The Articulated-Body algorithm. It computes the forward dynamics, aka the joint accelerations given t...
pinocchio::computeJointJacobians
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....
rnea.hpp
aba.hpp
pinocchio::JointModelPlanar
JointModelPlanarTpl< context::Scalar > JointModelPlanar
Definition: multibody/joint/fwd.hpp:118
pinocchio::SE3Tpl< context::Scalar, context::Options >::Matrix3
traits< SE3Tpl >::Matrix3 Matrix3
Definition: spatial/se3-tpl.hpp:56
pinocchio::ModelTpl::JointIndex
pinocchio::JointIndex JointIndex
Definition: multibody/model.hpp:68
append-urdf-model-with-another-model.parent_id
int parent_id
Definition: append-urdf-model-with-another-model.py:28
pinocchio::getJointJacobian
void getJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6Like > &J)
Computes the Jacobian of a specific joint frame expressed in one of the pinocchio::ReferenceFrame opt...
pinocchio::MotionPlanarTpl
Definition: joint-planar.hpp:20
fwd.hpp
pos
pos
M
M
pinocchio::context::Vector3
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Definition: context/generic.hpp:53
pinocchio::MotionTpl::Random
static MotionTpl Random()
Definition: motion-tpl.hpp:140
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1117
pinocchio::v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Definition: joint-configuration.hpp:1118
append-urdf-model-with-another-model.joint_name
string joint_name
Definition: append-urdf-model-with-another-model.py:33
pinocchio::SE3Tpl< context::Scalar, context::Options >::Random
static SE3Tpl Random()
Definition: spatial/se3-tpl.hpp:154
append-urdf-model-with-another-model.joint_placement
joint_placement
Definition: append-urdf-model-with-another-model.py:29
pinocchio::rnea
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & rnea(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)
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques accordi...
pinocchio::ModelTpl::nv
int nv
Dimension of the velocity vector space.
Definition: multibody/model.hpp:102
pinocchio::SE3Tpl< context::Scalar, context::Options >::Identity
static SE3Tpl Identity()
Definition: spatial/se3-tpl.hpp:136
Y
Y
joints.hpp
pinocchio::MotionTpl
Definition: context/casadi.hpp:27
jacobian.hpp
pinocchio::ModelTpl
Definition: context/generic.hpp:20
crba.hpp
pinocchio::computeAllTerms
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...
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::DataTpl::nle
VectorXs nle
Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis,...
Definition: multibody/data.hpp:179
BOOST_CHECK
#define BOOST_CHECK(check)
Definition: overview-urdf.cpp:34
pinocchio::LOCAL
@ LOCAL
Definition: multibody/fwd.hpp:50


pinocchio
Author(s):
autogenerated on Sat Jun 22 2024 02:41:48