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(JointRevoluteUnaligned)
42 axis << 1.0, 0.0, 0.0;
44 Model modelRX, modelRevoluteUnaligned;
46 Inertia inertia (1., Vector3 (0.5, 0., 0.0), Matrix3::Identity ());
52 addJointAndBody(modelRevoluteUnaligned,joint_model_RU,0,pos,
"revolute-unaligned",inertia);
55 Data dataRevoluteUnaligned(modelRevoluteUnaligned);
60 Eigen::VectorXd tauRevoluteUnaligned = Eigen::VectorXd::Ones (modelRevoluteUnaligned.
nv);
70 BOOST_CHECK(dataRevoluteUnaligned.oMi[1].isApprox(dataRX.oMi[1]));
71 BOOST_CHECK(dataRevoluteUnaligned.liMi[1].isApprox(dataRX.liMi[1]));
72 BOOST_CHECK(dataRevoluteUnaligned.Ycrb[1].matrix().isApprox(dataRX.Ycrb[1].matrix()));
73 BOOST_CHECK(dataRevoluteUnaligned.f[1].toVector().isApprox(dataRX.f[1].toVector()));
75 BOOST_CHECK(dataRevoluteUnaligned.
nle.isApprox(dataRX.
nle));
76 BOOST_CHECK(dataRevoluteUnaligned.com[0].isApprox(dataRX.com[0]));
79 tauRX =
rnea(modelRX, dataRX,
q,
v, aRX);
80 tauRevoluteUnaligned =
rnea(modelRevoluteUnaligned, dataRevoluteUnaligned,
q,
v, aRevoluteUnaligned);
82 BOOST_CHECK(tauRX.isApprox(tauRevoluteUnaligned));
86 Eigen::VectorXd aAbaRevoluteUnaligned =
aba(modelRevoluteUnaligned,dataRevoluteUnaligned,
q,
v, tauRevoluteUnaligned);
88 BOOST_CHECK(aAbaRX.isApprox(aAbaRevoluteUnaligned));
91 crba(modelRX, dataRX,
q);
92 crba(modelRevoluteUnaligned, dataRevoluteUnaligned,
q);
94 BOOST_CHECK(dataRX.
M.isApprox(dataRevoluteUnaligned.
M));
97 Eigen::Matrix<double, 6, Eigen::Dynamic> jacobianRX;jacobianRX.resize(6,1); jacobianRX.setZero();
98 Eigen::Matrix<double, 6, Eigen::Dynamic> jacobianRevoluteUnaligned;jacobianRevoluteUnaligned.resize(6,1);jacobianRevoluteUnaligned.setZero();
102 getJointJacobian(modelRevoluteUnaligned, dataRevoluteUnaligned, 1,
LOCAL, jacobianRevoluteUnaligned);
105 BOOST_CHECK(jacobianRX.isApprox(jacobianRevoluteUnaligned));
107 BOOST_AUTO_TEST_SUITE_END()
109 BOOST_AUTO_TEST_SUITE(JointRevoluteUnboundedUnaligned)
118 axis << 1.0, 0.0, 0.0;
120 Model modelRUX, modelRevoluteUboundedUnaligned;
122 Inertia inertia (1., Vector3 (0.5, 0., 0.0), Matrix3::Identity ());
129 addJointAndBody(modelRevoluteUboundedUnaligned,joint_model_RUU,0,pos,
"revolute-unbounded-unaligned",inertia);
131 Data dataRUX(modelRUX);
132 Data dataRevoluteUnboundedUnaligned(modelRevoluteUboundedUnaligned);
136 TangentVector
v = TangentVector::Ones (modelRUX.
nv);
138 Eigen::VectorXd tauRevoluteUnaligned = Eigen::VectorXd::Ones (modelRevoluteUboundedUnaligned.
nv);
146 computeAllTerms(modelRevoluteUboundedUnaligned, dataRevoluteUnboundedUnaligned,
q,
v);
148 BOOST_CHECK(dataRevoluteUnboundedUnaligned.oMi[1].isApprox(dataRUX.oMi[1]));
149 BOOST_CHECK(dataRevoluteUnboundedUnaligned.liMi[1].isApprox(dataRUX.liMi[1]));
150 BOOST_CHECK(dataRevoluteUnboundedUnaligned.Ycrb[1].matrix().isApprox(dataRUX.Ycrb[1].matrix()));
151 BOOST_CHECK(dataRevoluteUnboundedUnaligned.f[1].toVector().isApprox(dataRUX.f[1].toVector()));
153 BOOST_CHECK(dataRevoluteUnboundedUnaligned.
nle.isApprox(dataRUX.
nle));
154 BOOST_CHECK(dataRevoluteUnboundedUnaligned.com[0].isApprox(dataRUX.com[0]));
157 tauRX =
rnea(modelRUX, dataRUX,
q,
v, aRX);
158 tauRevoluteUnaligned =
rnea(modelRevoluteUboundedUnaligned, dataRevoluteUnboundedUnaligned,
q,
v, aRevoluteUnaligned);
160 BOOST_CHECK(tauRX.isApprox(tauRevoluteUnaligned));
164 Eigen::VectorXd aAbaRevoluteUnaligned =
aba(modelRevoluteUboundedUnaligned,dataRevoluteUnboundedUnaligned,
q,
v, tauRevoluteUnaligned);
166 BOOST_CHECK(aAbaRX.isApprox(aAbaRevoluteUnaligned));
169 crba(modelRUX, dataRUX,
q);
170 crba(modelRevoluteUboundedUnaligned, dataRevoluteUnboundedUnaligned,
q);
172 BOOST_CHECK(dataRUX.
M.isApprox(dataRevoluteUnboundedUnaligned.
M));
175 Data::Matrix6x jacobianRUX;jacobianRUX.resize(6,1); jacobianRUX.setZero();
177 jacobianRevoluteUnboundedUnaligned.resize(6,1); jacobianRevoluteUnboundedUnaligned.setZero();
182 getJointJacobian(modelRevoluteUboundedUnaligned, dataRevoluteUnboundedUnaligned, 1,
LOCAL, jacobianRevoluteUnboundedUnaligned);
184 BOOST_CHECK(jacobianRUX.isApprox(jacobianRevoluteUnboundedUnaligned));
187 BOOST_AUTO_TEST_SUITE_END()
189 BOOST_AUTO_TEST_SUITE(JointRevoluteUnbounded)
199 BOOST_CHECK(M.
act(mp_x).isApprox(M.
act(mp_dense_x)));
200 BOOST_CHECK(M.
actInv(mp_x).isApprox(M.
actInv(mp_dense_x)));
202 BOOST_CHECK(v.
cross(mp_x).isApprox(v.
cross(mp_dense_x)));
207 BOOST_CHECK(M.
act(mp_y).isApprox(M.
act(mp_dense_y)));
208 BOOST_CHECK(M.
actInv(mp_y).isApprox(M.
actInv(mp_dense_y)));
210 BOOST_CHECK(v.
cross(mp_y).isApprox(v.
cross(mp_dense_y)));
215 BOOST_CHECK(M.
act(mp_z).isApprox(M.
act(mp_dense_z)));
216 BOOST_CHECK(M.
actInv(mp_z).isApprox(M.
actInv(mp_dense_z)));
218 BOOST_CHECK(v.
cross(mp_z).isApprox(v.
cross(mp_dense_z)));
226 Model modelRX, modelRevoluteUnbounded;
228 Inertia inertia(1., Vector3(0.5, 0., 0.0), Matrix3::Identity());
235 Data dataRX(modelRX);
236 Data dataRevoluteUnbounded(modelRevoluteUnbounded);
240 double ca, sa;
double alpha = q_rx(0);
SINCOS(alpha, &sa, &ca);
246 Eigen::VectorXd tauRevoluteUnbounded = Eigen::VectorXd::Ones(modelRevoluteUnbounded.
nv);
251 forwardKinematics(modelRevoluteUnbounded, dataRevoluteUnbounded, q_rubx, v_rubx);
254 computeAllTerms(modelRevoluteUnbounded, dataRevoluteUnbounded, q_rubx, v_rubx);
256 BOOST_CHECK(dataRevoluteUnbounded.oMi[1].isApprox(dataRX.oMi[1]));
257 BOOST_CHECK(dataRevoluteUnbounded.liMi[1].isApprox(dataRX.liMi[1]));
258 BOOST_CHECK(dataRevoluteUnbounded.Ycrb[1].matrix().isApprox(dataRX.Ycrb[1].matrix()));
259 BOOST_CHECK(dataRevoluteUnbounded.f[1].toVector().isApprox(dataRX.f[1].toVector()));
261 BOOST_CHECK(dataRevoluteUnbounded.
nle.isApprox(dataRX.
nle));
262 BOOST_CHECK(dataRevoluteUnbounded.com[0].isApprox(dataRX.com[0]));
265 tauRX =
rnea(modelRX, dataRX, q_rx, v_rx, aRX);
266 tauRevoluteUnbounded =
rnea(modelRevoluteUnbounded, dataRevoluteUnbounded, q_rubx, v_rubx, aRevoluteUnbounded);
268 BOOST_CHECK(tauRX.isApprox(tauRevoluteUnbounded));
272 Eigen::VectorXd aAbaRevoluteUnbounded =
aba(modelRevoluteUnbounded,dataRevoluteUnbounded, q_rubx, v_rubx, tauRevoluteUnbounded);
274 BOOST_CHECK(aAbaRX.isApprox(aAbaRevoluteUnbounded));
277 crba(modelRX, dataRX,q_rx);
278 crba(modelRevoluteUnbounded, dataRevoluteUnbounded, q_rubx);
280 BOOST_CHECK(dataRX.
M.isApprox(dataRevoluteUnbounded.
M));
283 Eigen::Matrix<double, 6, Eigen::Dynamic> jacobianPX;jacobianPX.resize(6,1); jacobianPX.setZero();
284 Eigen::Matrix<double, 6, Eigen::Dynamic> jacobianPrismaticUnaligned;jacobianPrismaticUnaligned.resize(6,1);jacobianPrismaticUnaligned.setZero();
288 getJointJacobian(modelRevoluteUnbounded, dataRevoluteUnbounded, 1,
LOCAL, jacobianPrismaticUnaligned);
290 BOOST_CHECK(jacobianPX.isApprox(jacobianPrismaticUnaligned));
293 BOOST_AUTO_TEST_SUITE_END()
295 BOOST_AUTO_TEST_SUITE(JointRevolute)
305 const double alpha = 0.2;
306 double sin_alpha, cos_alpha;
SINCOS(alpha,&sin_alpha,&cos_alpha);
309 TransformX Mx(sin_alpha,cos_alpha);
313 BOOST_CHECK((Mrand*Mplain).isApprox(Mrand*Mx));
315 TransformY My(sin_alpha,cos_alpha);
317 BOOST_CHECK(Mplain.translation().isZero());
318 BOOST_CHECK(Mplain.rotation().isApprox(Eigen::AngleAxisd(alpha,Vector3::UnitY()).
toRotationMatrix()));
319 BOOST_CHECK((Mrand*Mplain).isApprox(Mrand*My));
321 TransformZ Mz(sin_alpha,cos_alpha);
323 BOOST_CHECK(Mplain.translation().isZero());
324 BOOST_CHECK(Mplain.rotation().isApprox(Eigen::AngleAxisd(alpha,Vector3::UnitZ()).
toRotationMatrix()));
325 BOOST_CHECK((Mrand*Mplain).isApprox(Mrand*Mz));
333 BOOST_CHECK(M.
act(mp_x).isApprox(M.
act(mp_dense_x)));
334 BOOST_CHECK(M.
actInv(mp_x).isApprox(M.
actInv(mp_dense_x)));
336 BOOST_CHECK(v.
cross(mp_x).isApprox(v.
cross(mp_dense_x)));
341 BOOST_CHECK(M.
act(mp_y).isApprox(M.
act(mp_dense_y)));
342 BOOST_CHECK(M.
actInv(mp_y).isApprox(M.
actInv(mp_dense_y)));
344 BOOST_CHECK(v.
cross(mp_y).isApprox(v.
cross(mp_dense_y)));
349 BOOST_CHECK(M.
act(mp_z).isApprox(M.
act(mp_dense_z)));
350 BOOST_CHECK(M.
actInv(mp_z).isApprox(M.
actInv(mp_dense_z)));
352 BOOST_CHECK(v.
cross(mp_z).isApprox(v.
cross(mp_dense_z)));
355 BOOST_AUTO_TEST_SUITE_END()
357 BOOST_AUTO_TEST_SUITE(JointRevoluteUnaligned)
367 BOOST_CHECK(M.
act(mp).isApprox(M.
act(mp_dense)));
370 BOOST_CHECK(v.
cross(mp).isApprox(v.
cross(mp_dense)));
373 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
BOOST_AUTO_TEST_CASE(vsRX)
ConstLinearRef translation() const
SE3GroupAction< D >::ReturnType act(const D &d) const
ay = aXb.act(by)
void SINCOS(const S1 &a, S2 *sa, S3 *ca)
Computes sin/cos values of a given input scalar.
traits< SE3Tpl >::Vector3 Vector3
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.
Common traits structure to fully define base classes for CRTP.
void toRotationMatrix(const Eigen::MatrixBase< Vector3 > &axis, const Scalar &cos_value, const Scalar &sin_value, const Eigen::MatrixBase< Matrix3 > &res)
Computes a rotation matrix from a vector and values of sin and cos orientations values.
traits< SE3Tpl >::Matrix3 Matrix3
static MotionTpl Random()
JointModelRevoluteUnboundedTpl< double, 0, 0 > JointModelRUBX
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
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
JointModelRevoluteTpl< double, 0, 0 > JointModelRX
JointCollectionTpl & model
int nq
Dimension of the configuration vector representation.
ConstAngularRef rotation() const