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(JointSpherical)
43 BOOST_CHECK(M.
act(mp).isApprox(M.
act(mp_dense)));
46 BOOST_CHECK(v.
cross(mp).isApprox(v.
cross(mp_dense)));
53 typedef Eigen::Matrix <double, 6, 1> Vector6;
54 typedef Eigen::Matrix <double, 7, 1> VectorFF;
57 Model modelSpherical, modelFreeflyer;
59 Inertia inertia(1., Vector3(0.5, 0., 0.0), Matrix3::Identity());
65 Data dataSpherical(modelSpherical);
66 Data dataFreeFlyer(modelFreeflyer);
69 VectorFF qff; qff << 0, 0, 0, q[0], q[1], q[2], q[3];
71 Vector6 vff; vff << 0, 0, 0, 1, 1, 1;
83 BOOST_CHECK(dataFreeFlyer.oMi[1].isApprox(dataSpherical.oMi[1]));
84 BOOST_CHECK(dataFreeFlyer.liMi[1].isApprox(dataSpherical.liMi[1]));
85 BOOST_CHECK(dataFreeFlyer.Ycrb[1].matrix().isApprox(dataSpherical.Ycrb[1].matrix()));
86 BOOST_CHECK(dataFreeFlyer.f[1].toVector().isApprox(dataSpherical.f[1].toVector()));
92 BOOST_CHECK(nle_expected_ff.isApprox(dataSpherical.
nle));
93 BOOST_CHECK(dataFreeFlyer.com[0].isApprox(dataSpherical.com[0]));
96 tauSpherical =
rnea(modelSpherical, dataSpherical, q, v, aSpherical);
97 tauff =
rnea(modelFreeflyer, dataFreeFlyer, qff, vff, aff);
99 Vector3 tau_expected; tau_expected << tauff(3), tauff(4), tauff(5);
100 BOOST_CHECK(tauSpherical.isApprox(tau_expected));
103 Eigen::VectorXd aAbaSpherical =
aba(modelSpherical,dataSpherical, q, v, tauSpherical);
105 Vector3 a_expected; a_expected << aAbaFreeFlyer[3],
109 BOOST_CHECK(aAbaSpherical.isApprox(a_expected));
112 crba(modelSpherical, dataSpherical,q);
113 crba(modelFreeflyer, dataFreeFlyer, qff);
115 Eigen::Matrix<double, 3, 3> M_expected(dataFreeFlyer.
M.bottomRightCorner<3,3>());
117 BOOST_CHECK(dataSpherical.
M.isApprox(M_expected));
120 Eigen::Matrix<double, 6, Eigen::Dynamic> jacobian_planar;jacobian_planar.resize(6,3); jacobian_planar.setZero();
121 Eigen::Matrix<double, 6, Eigen::Dynamic> jacobian_ff;jacobian_ff.resize(6,6);jacobian_ff.setZero();
128 Eigen::Matrix<double, 6, 3> jacobian_expected; jacobian_expected << jacobian_ff.col(3),
133 BOOST_CHECK(jacobian_planar.isApprox(jacobian_expected));
136 BOOST_AUTO_TEST_SUITE_END()
138 BOOST_AUTO_TEST_SUITE(JointSphericalZYX)
148 BOOST_CHECK(M.
act(mp).isApprox(M.
act(mp_dense)));
151 BOOST_CHECK(v.
cross(mp).isApprox(v.
cross(mp_dense)));
160 typedef Eigen::Matrix <double, 6, 1> Vector6;
161 typedef Eigen::Matrix <double, 7, 1> VectorFF;
164 Model modelSphericalZYX, modelFreeflyer;
166 Inertia inertia(1., Vector3(0.5, 0., 0.0), Matrix3::Identity());
172 Data dataSphericalZYX(modelSphericalZYX);
173 Data dataFreeFlyer(modelFreeflyer);
175 Eigen::AngleAxisd rollAngle(1, Eigen::Vector3d::UnitZ());
176 Eigen::AngleAxisd yawAngle(1, Eigen::Vector3d::UnitY());
177 Eigen::AngleAxisd pitchAngle(1, Eigen::Vector3d::UnitX());
178 Eigen::Quaterniond q_sph = rollAngle * yawAngle * pitchAngle;
181 VectorFF qff; qff << 0, 0, 0, q_sph.x(), q_sph.y(), q_sph.z(), q_sph.w();
183 Vector6 vff; vff << 0, 0, 0, 1, 1, 1;
195 BOOST_CHECK(dataFreeFlyer.oMi[1].isApprox(dataSphericalZYX.oMi[1]));
196 BOOST_CHECK(dataFreeFlyer.liMi[1].isApprox(dataSphericalZYX.liMi[1]));
197 BOOST_CHECK(dataFreeFlyer.Ycrb[1].matrix().isApprox(dataSphericalZYX.Ycrb[1].matrix()));
199 BOOST_CHECK(dataFreeFlyer.com[0].isApprox(dataSphericalZYX.com[0]));
209 Inertia inertia(1., Vector3(0.5, 0., 0.0), Matrix3::Identity());
219 rnea(model, data, q, v, a);
220 Vector3 tau_expected(0., -4.905, 0.);
222 BOOST_CHECK(tau_expected.isApprox(data.tau, 1e-14));
224 q = Eigen::VectorXd::Ones(model.
nq);
225 v = Eigen::VectorXd::Ones(model.
nv);
226 a = Eigen::VectorXd::Ones(model.
nv);
228 rnea(model, data, q, v, a);
229 tau_expected << -0.53611600195085, -0.74621832606188, -0.38177329067604;
231 BOOST_CHECK(tau_expected.isApprox(data.tau, 1e-12));
234 v = Eigen::VectorXd::Ones(model.
nv);
235 a = Eigen::VectorXd::Ones(model.
nv);
237 rnea(model, data, q, v, a);
238 tau_expected << 0.73934458094049, 2.7804530848031, 0.50684940972146;
240 BOOST_CHECK(tau_expected.isApprox(data.tau, 1e-12));
251 Inertia inertia(1., Vector3(0.5, 0., 0.0), Matrix3::Identity());
258 Eigen::MatrixXd M_expected(model.
nv,model.
nv);
260 crba(model, data, q);
266 BOOST_CHECK(M_expected.isApprox(data.M, 1e-14));
268 q = Eigen::VectorXd::Ones(model.
nq);
270 crba(model, data, q);
272 1.0729816454316, -5.5511151231258e-17, -0.8414709848079,
273 -5.5511151231258e-17, 1.25, 0,
274 -0.8414709848079, 0, 1;
276 BOOST_CHECK(M_expected.isApprox(data.M, 1e-12));
280 crba(model, data, q);
282 1.043294547392, 2.7755575615629e-17, -0.90929742682568,
284 -0.90929742682568, 0, 1;
286 BOOST_CHECK(M_expected.isApprox(data.M, 1e-10));
289 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.
JointModelSphericalZYXTpl< double > JointModelSphericalZYX
BOOST_AUTO_TEST_CASE(spatial)
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
Main pinocchio namespace.
JointModelSphericalTpl< double > JointModelSpherical
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.
JointIndex getJointId(const std::string &name) const
Return the index of a joint given by its name.
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.