6 #include "pinocchio/math/fwd.hpp" 7 #include "pinocchio/multibody/joint/joints.hpp" 8 #include "pinocchio/algorithm/rnea.hpp" 9 #include "pinocchio/algorithm/aba.hpp" 10 #include "pinocchio/algorithm/crba.hpp" 11 #include "pinocchio/algorithm/jacobian.hpp" 12 #include "pinocchio/algorithm/compute-all-terms.hpp" 14 #include <boost/test/unit_test.hpp> 29 idx = model.
addJoint(parent_id,jmodel,joint_placement,joint_name);
33 BOOST_AUTO_TEST_SUITE(JointTranslation)
40 const Vector3 displacement(Vector3::Random());
43 TransformTranslation Mtrans(displacement);
45 BOOST_CHECK(Mplain.
translation().isApprox(displacement));
46 BOOST_CHECK(Mplain.
rotation().isIdentity());
47 BOOST_CHECK((Mrand*Mplain).isApprox(Mrand*Mtrans));
55 BOOST_CHECK(M.
act(mp).isApprox(M.
act(mp_dense)));
58 BOOST_CHECK(v.
cross(mp).isApprox(v.
cross(mp_dense)));
65 typedef Eigen::Matrix <double, 6, 1> Vector6;
66 typedef Eigen::Matrix <double, 7, 1> VectorFF;
69 Model modelTranslation, modelFreeflyer;
71 Inertia inertia(1., Vector3(0.5, 0., 0.0), Matrix3::Identity());
77 Data dataTranslation(modelTranslation);
78 Data dataFreeFlyer(modelFreeflyer);
81 VectorFF qff; qff << 1, 1, 1, 0, 0, 0, 1 ;
83 Vector6 vff; vff << 1, 1, 1, 0, 0, 0;
95 BOOST_CHECK(dataFreeFlyer.oMi[1].isApprox(dataTranslation.oMi[1]));
96 BOOST_CHECK(dataFreeFlyer.liMi[1].isApprox(dataTranslation.liMi[1]));
97 BOOST_CHECK(dataFreeFlyer.Ycrb[1].matrix().isApprox(dataTranslation.Ycrb[1].matrix()));
98 BOOST_CHECK(dataFreeFlyer.f[1].toVector().isApprox(dataTranslation.f[1].toVector()));
101 dataFreeFlyer.
nle[1],
104 BOOST_CHECK(nle_expected_ff.isApprox(dataTranslation.
nle));
105 BOOST_CHECK(dataFreeFlyer.com[0].isApprox(dataTranslation.com[0]));
108 tauTranslation =
rnea(modelTranslation, dataTranslation, q, v, aTranslation);
109 tauff =
rnea(modelFreeflyer, dataFreeFlyer, qff, vff, aff);
111 Vector3 tau_expected; tau_expected << tauff(0), tauff(1), tauff(2);
112 BOOST_CHECK(tauTranslation.isApprox(tau_expected));
115 Eigen::VectorXd aAbaTranslation =
aba(modelTranslation,dataTranslation, q, v, tauTranslation);
117 Vector3 a_expected; a_expected << aAbaFreeFlyer[0],
121 BOOST_CHECK(aAbaTranslation.isApprox(a_expected));
124 crba(modelTranslation, dataTranslation,q);
125 crba(modelFreeflyer, dataFreeFlyer, qff);
127 Eigen::Matrix<double, 3, 3> M_expected(dataFreeFlyer.
M.topLeftCorner<3,3>());
129 BOOST_CHECK(dataTranslation.
M.isApprox(M_expected));
132 Eigen::Matrix<double, 6, Eigen::Dynamic> jacobian_translation;jacobian_translation.resize(6,3); jacobian_translation.setZero();
133 Eigen::Matrix<double, 6, Eigen::Dynamic> jacobian_ff;jacobian_ff.resize(6,6);jacobian_ff.setZero();
139 Eigen::Matrix<double, 6, 3> jacobian_expected; jacobian_expected << jacobian_ff.col(0),
143 BOOST_CHECK(jacobian_translation.isApprox(jacobian_expected));
146 BOOST_AUTO_TEST_SUITE_END()
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
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...
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...
void addJointAndBody(Model &model, const JointModelBase< D > &jmodel, const Model::JointIndex parent_id, const SE3 &joint_placement, const std::string &name, const Inertia &Y)
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...
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...
MotionAlgebraAction< OtherSpatialType, Derived >::ReturnType cross(const OtherSpatialType &d) const
void getJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6Like > &J)
Computes the Jacobian of a specific joint frame expressed either in the world (rf = WORLD) frame or i...
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
VectorXs nle
Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis...
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.
SE3GroupAction< D >::ReturnType actInv(const D &d) const
by = aXb.actInv(ay)
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.
The LOCAL frame convention corresponds to the frame directly attached to the moving part (Joint...
MatrixXs M
The joint space inertia matrix (a square matrix of dim model.nv).
pinocchio::JointIndex JointIndex
ConstLinearRef translation() const
SE3GroupAction< D >::ReturnType act(const D &d) const
ay = aXb.act(by)
traits< SE3Tpl >::Vector3 Vector3
JointModelTranslationTpl< double > JointModelTranslation
Main pinocchio namespace.
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...
int nv
Dimension of the velocity vector space.
BOOST_AUTO_TEST_CASE(spatial)
JointModelFreeFlyerTpl< double > JointModelFreeFlyer
traits< SE3Tpl >::Matrix3 Matrix3
static MotionTpl Random()
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.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
JointCollectionTpl & model
int nq
Dimension of the configuration vector representation.
ConstAngularRef rotation() const