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( JointPrismatic )
43 const double displacement = 0.2;
46 TransformX Mx(displacement);
48 BOOST_CHECK(Mplain.
translation().isApprox(Vector3(displacement,0,0)));
49 BOOST_CHECK(Mplain.
rotation().isIdentity());
50 BOOST_CHECK((Mrand*Mplain).isApprox(Mrand*Mx));
52 TransformY My(displacement);
54 BOOST_CHECK(Mplain.
translation().isApprox(Vector3(0,displacement,0)));
55 BOOST_CHECK(Mplain.
rotation().isIdentity());
56 BOOST_CHECK((Mrand*Mplain).isApprox(Mrand*My));
58 TransformZ Mz(displacement);
60 BOOST_CHECK(Mplain.
translation().isApprox(Vector3(0,0,displacement)));
61 BOOST_CHECK(Mplain.
rotation().isIdentity());
62 BOOST_CHECK((Mrand*Mplain).isApprox(Mrand*Mz));
70 BOOST_CHECK(M.
act(mp_x).isApprox(M.
act(mp_dense_x)));
71 BOOST_CHECK(M.
actInv(mp_x).isApprox(M.
actInv(mp_dense_x)));
73 BOOST_CHECK(v.
cross(mp_x).isApprox(v.
cross(mp_dense_x)));
78 BOOST_CHECK(M.
act(mp_y).isApprox(M.
act(mp_dense_y)));
79 BOOST_CHECK(M.
actInv(mp_y).isApprox(M.
actInv(mp_dense_y)));
81 BOOST_CHECK(v.
cross(mp_y).isApprox(v.
cross(mp_dense_y)));
86 BOOST_CHECK(M.
act(mp_z).isApprox(M.
act(mp_dense_z)));
87 BOOST_CHECK(M.
actInv(mp_z).isApprox(M.
actInv(mp_dense_z)));
89 BOOST_CHECK(v.
cross(mp_z).isApprox(v.
cross(mp_dense_z)));
114 joint_model.
calc(joint_data, q, q_dot);
116 BOOST_CHECK(expected_configuration.
rotation().isApprox(joint_data.
M.rotation(), 1e-12));
117 BOOST_CHECK(expected_configuration.
translation().isApprox(joint_data.
M.translation(), 1e-12));
118 BOOST_CHECK(expected_v_J.
toVector().isApprox(((
Motion) joint_data.
v).toVector(), 1e-12));
125 joint_model.
calc(joint_data, q, q_dot);
129 expected_v_J.
linear() << 1., 0., 0.;
131 BOOST_CHECK(expected_configuration.
rotation().isApprox(joint_data.
M.rotation(), 1e-12));
132 BOOST_CHECK(expected_configuration.
translation().isApprox(joint_data.
M.translation(), 1e-12));
133 BOOST_CHECK(expected_v_J.
toVector().isApprox(((
Motion) joint_data.
v).toVector(), 1e-12));
144 Inertia inertia(1., Vector3(0.5, 0., 0.0), Matrix3::Identity());
154 rnea(model, data, q, v, a);
159 BOOST_CHECK(tau_expected.isApprox(data.tau, 1e-14));
162 q = Eigen::VectorXd::Ones(model.
nq);
163 v = Eigen::VectorXd::Ones(model.
nv);
164 a = Eigen::VectorXd::Ones(model.
nv);
166 rnea(model, data, q, v, a);
169 BOOST_CHECK(tau_expected.isApprox(data.tau, 1e-12));
172 v = Eigen::VectorXd::Ones(model.
nv);
173 a = Eigen::VectorXd::Ones(model.
nv);
175 rnea(model, data, q, v, a);
178 BOOST_CHECK(tau_expected.isApprox(data.tau, 1e-12));
189 Inertia inertia(1., Vector3(0.5, 0., 0.0), Matrix3::Identity());
196 Eigen::MatrixXd M_expected(model.
nv,model.
nv);
198 crba(model, data, q);
201 BOOST_CHECK(M_expected.isApprox(data.M, 1e-14));
203 q = Eigen::VectorXd::Ones(model.
nq);
205 crba(model, data, q);
207 BOOST_CHECK(M_expected.isApprox(data.M, 1e-12));
211 crba(model, data, q);
213 BOOST_CHECK(M_expected.isApprox(data.M, 1e-10));
216 BOOST_AUTO_TEST_SUITE_END()
218 BOOST_AUTO_TEST_SUITE(JointPrismaticUnaligned)
228 BOOST_CHECK(M.
act(mp).isApprox(M.
act(mp_dense)));
231 BOOST_CHECK(v.
cross(mp).isApprox(v.
cross(mp_dense)));
240 Eigen::Vector3d
axis;
241 axis << 1.0, 0.0, 0.0;
243 Model modelPX, modelPrismaticUnaligned;
245 Inertia inertia(1., Vector3(0.5, 0., 0.0), Matrix3::Identity());
251 addJointAndBody(modelPrismaticUnaligned,joint_model_PU,0,pos,
"prismatic-unaligned",inertia);
253 Data dataPX(modelPX);
254 Data dataPrismaticUnaligned(modelPrismaticUnaligned);
259 Eigen::VectorXd tauPrismaticUnaligned = Eigen::VectorXd::Ones(modelPrismaticUnaligned.
nv);
267 computeAllTerms(modelPrismaticUnaligned, dataPrismaticUnaligned, q, v);
269 BOOST_CHECK(dataPrismaticUnaligned.oMi[1].isApprox(dataPX.oMi[1]));
270 BOOST_CHECK(dataPrismaticUnaligned.liMi[1].isApprox(dataPX.liMi[1]));
271 BOOST_CHECK(dataPrismaticUnaligned.Ycrb[1].matrix().isApprox(dataPX.Ycrb[1].matrix()));
272 BOOST_CHECK(dataPrismaticUnaligned.f[1].toVector().isApprox(dataPX.f[1].toVector()));
274 BOOST_CHECK(dataPrismaticUnaligned.
nle.isApprox(dataPX.
nle));
275 BOOST_CHECK(dataPrismaticUnaligned.com[0].isApprox(dataPX.com[0]));
278 tauPX =
rnea(modelPX, dataPX, q, v, aPX);
279 tauPrismaticUnaligned =
rnea(modelPrismaticUnaligned, dataPrismaticUnaligned, q, v, aPrismaticUnaligned);
281 BOOST_CHECK(tauPX.isApprox(tauPrismaticUnaligned));
285 Eigen::VectorXd aAbaPrismaticUnaligned =
aba(modelPrismaticUnaligned,dataPrismaticUnaligned, q, v, tauPrismaticUnaligned);
287 BOOST_CHECK(aAbaPX.isApprox(aAbaPrismaticUnaligned));
290 crba(modelPX, dataPX,q);
291 crba(modelPrismaticUnaligned, dataPrismaticUnaligned, q);
293 BOOST_CHECK(dataPX.
M.isApprox(dataPrismaticUnaligned.
M));
296 Eigen::Matrix<double, 6, Eigen::Dynamic> jacobianPX;jacobianPX.resize(6,1); jacobianPX.setZero();
297 Eigen::Matrix<double, 6, Eigen::Dynamic> jacobianPrismaticUnaligned;jacobianPrismaticUnaligned.resize(6,1);jacobianPrismaticUnaligned.setZero();
301 getJointJacobian(modelPrismaticUnaligned, dataPrismaticUnaligned, 1,
LOCAL, jacobianPrismaticUnaligned);
303 BOOST_CHECK(jacobianPX.isApprox(jacobianPrismaticUnaligned));
306 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...
JointModelPrismaticTpl< double, 0, 0 > JointModelPX
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 setIndexes(JointIndex id, int q, int v)
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
BOOST_AUTO_TEST_CASE(spatial)
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)
bool isApprox(const MotionDense< M2 > &m2, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
ConstLinearType linear() const
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
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
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...
ToVectorConstReturnType toVector() const
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.
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