5 #include "pinocchio/autodiff/cppad.hpp" 7 #include "pinocchio/multibody/model.hpp" 8 #include "pinocchio/multibody/data.hpp" 10 #include "pinocchio/algorithm/kinematics.hpp" 11 #include "pinocchio/algorithm/jacobian.hpp" 12 #include "pinocchio/algorithm/crba.hpp" 13 #include "pinocchio/algorithm/rnea.hpp" 14 #include "pinocchio/algorithm/aba.hpp" 15 #include "pinocchio/algorithm/joint-configuration.hpp" 17 #include "pinocchio/parsers/sample-models.hpp" 21 #include <boost/test/unit_test.hpp> 22 #include <boost/utility/binary.hpp> 24 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
29 using CppAD::NearEqual;
32 typedef AD<Scalar> ADScalar;
42 model.lowerPositionLimit.head<3>().
fill(-1.);
43 model.upperPositionLimit.head<3>().
fill(1.);
46 ADModel ad_model = model.cast<ADScalar>();
47 ADData ad_data(ad_model);
50 typedef Model::ConfigVectorType ConfigVectorType;
51 typedef Model::TangentVectorType TangentVectorType;
52 ConfigVectorType
q(model.nq);
55 TangentVectorType
v(TangentVectorType::Random(model.nv));
56 TangentVectorType
a(TangentVectorType::Random(model.nv));
58 typedef ADModel::ConfigVectorType ADConfigVectorType;
59 typedef ADModel::TangentVectorType ADTangentVectorType;
61 ADConfigVectorType ad_q = q.cast<ADScalar>();
62 ADTangentVectorType ad_v = v.cast<ADScalar>();
63 ADTangentVectorType ad_a = a.cast<ADScalar>();
65 typedef Eigen::Matrix<ADScalar,Eigen::Dynamic,1> VectorXAD;
67 data.M.triangularView<Eigen::StrictlyLower>()
68 = data.M.transpose().triangularView<Eigen::StrictlyLower>();
73 CppAD::Independent(ad_a);
76 VectorXAD Y(model.nv);
77 Eigen::Map<ADData::TangentVectorType>(Y.data(),model.nv,1) = ad_data.tau;
79 CppAD::ADFun<Scalar> ad_fun(ad_a,Y);
81 CPPAD_TESTVECTOR(Scalar)
x((
size_t)model.nv);
82 Eigen::Map<Data::TangentVectorType>(
x.data(),model.nv,1) = a;
84 CPPAD_TESTVECTOR(Scalar) tau = ad_fun.Forward(0,
x);
85 BOOST_CHECK(Eigen::Map<Data::TangentVectorType>(tau.data(),model.nv,1).isApprox(data.tau));
87 CPPAD_TESTVECTOR(Scalar)
dtau_da = ad_fun.Jacobian(
x);
88 Data::MatrixXs
M = Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Data::MatrixXs)>(dtau_da.data(),model.nv,model.nv);
89 BOOST_CHECK(M.isApprox(data.M));
93 ADTangentVectorType ad_tau = tau.cast<ADScalar>();
96 data.Minv.triangularView<Eigen::StrictlyLower>()
97 = data.Minv.transpose().triangularView<Eigen::StrictlyLower>();
101 CppAD::Independent(ad_tau);
104 VectorXAD Y(model.nv);
105 Eigen::Map<ADData::TangentVectorType>(Y.data(),model.nv,1) = ad_data.ddq;
107 CppAD::ADFun<Scalar> ad_fun(ad_tau,Y);
109 CPPAD_TESTVECTOR(Scalar)
x((
size_t)model.nv);
110 Eigen::Map<Data::TangentVectorType>(
x.data(),model.nv,1) = tau;
112 CPPAD_TESTVECTOR(Scalar) ddq = ad_fun.Forward(0,
x);
113 BOOST_CHECK(Eigen::Map<Data::TangentVectorType>(ddq.data(),model.nv,1).isApprox(a));
115 CPPAD_TESTVECTOR(Scalar) dddq_da = ad_fun.Jacobian(
x);
116 Data::MatrixXs Minv = Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Data::MatrixXs)>(dddq_da.data(),model.nv,model.nv);
117 BOOST_CHECK(Minv.isApprox(data.Minv));
126 using CppAD::NearEqual;
129 typedef AD<Scalar> ADScalar;
140 model.lowerPositionLimit.head<3>().
fill(-1.);
141 model.upperPositionLimit.head<3>().
fill(1.);
144 ADModel ad_model = model.cast<ADScalar>();
145 ADData ad_data(ad_model);
148 typedef Model::ConfigVectorType ConfigVectorType;
149 typedef Model::TangentVectorType TangentVectorType;
150 ConfigVectorType
q(model.nq);
153 TangentVectorType
v(TangentVectorType::Random(model.nv));
154 TangentVectorType
a(TangentVectorType::Random(model.nv));
156 typedef ADModel::ConfigVectorType ADConfigVectorType;
157 typedef ADModel::TangentVectorType ADTangentVectorType;
159 ADConfigVectorType ad_q = q.cast<ADScalar>();
160 ADTangentVectorType ad_v = v.cast<ADScalar>();
161 ADTangentVectorType ad_a = a.cast<ADScalar>();
170 J_local.setZero(); J_global.setZero();
172 dJ_local.setZero(); dJ_global.setZero();
182 typedef Eigen::Matrix<ADScalar,Eigen::Dynamic,1> VectorXAD;
185 CppAD::Independent(ad_v);
191 Eigen::DenseIndex current_id = 0;
192 for(Eigen::DenseIndex k = 0; k < 3; ++k)
194 Y[current_id+k+Motion::LINEAR] = v_local.linear()[k];
195 Y[current_id+k+Motion::ANGULAR] = v_local.angular()[k];
199 for(Eigen::DenseIndex k = 0; k < 3; ++k)
201 Y[current_id+k+Motion::LINEAR] = v_global.linear()[k];
202 Y[current_id+k+Motion::ANGULAR] = v_global.angular()[k];
206 for(Eigen::DenseIndex k = 0; k < 3; ++k)
208 Y[current_id+k+Motion::LINEAR] = a_local.linear()[k];
209 Y[current_id+k+Motion::ANGULAR] = a_local.angular()[k];
213 CppAD::ADFun<Scalar> vjoint(ad_v,Y);
215 CPPAD_TESTVECTOR(Scalar)
x((
size_t)model.nv);
216 for(Eigen::DenseIndex k = 0; k < model.nv; ++k)
221 CPPAD_TESTVECTOR(Scalar) y = vjoint.Forward(0,
x);
222 Scalar * y_ptr = y.data();
223 BOOST_CHECK(data.v[joint_id].isApprox(Motion(Eigen::Map<Motion::Vector6>(y_ptr))));
225 BOOST_CHECK(data.oMi[joint_id].act(data.v[joint_id]).isApprox(
Motion(Eigen::Map<Motion::Vector6>(y_ptr))));
227 BOOST_CHECK(data.a[joint_id].isApprox(Motion(Eigen::Map<Motion::Vector6>(y_ptr))));
230 CPPAD_TESTVECTOR(Scalar) dY_dv = vjoint.Jacobian(
x);
232 Scalar * dY_dv_ptr = dY_dv.data();
233 Data::Matrix6x ad_J_local = Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Data::Matrix6x)>(dY_dv_ptr,6,model.nv);
234 dY_dv_ptr += ad_J_local.size();
235 Data::Matrix6x ad_J_global = Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Data::Matrix6x)>(dY_dv_ptr,6,model.nv);
236 dY_dv_ptr += ad_J_global.size();
238 BOOST_CHECK(ad_J_local.isApprox(J_local));
239 BOOST_CHECK(ad_J_global.isApprox(J_global));
243 CppAD::Independent(ad_a);
247 Eigen::DenseIndex current_id = 0;
248 for(Eigen::DenseIndex k = 0; k < 3; ++k)
250 Y[current_id+k+Motion::LINEAR] = v_local.linear()[k];
251 Y[current_id+k+Motion::ANGULAR] = v_local.angular()[k];
255 for(Eigen::DenseIndex k = 0; k < 3; ++k)
257 Y[current_id+k+Motion::LINEAR] = a_local.linear()[k];
258 Y[current_id+k+Motion::ANGULAR] = a_local.angular()[k];
262 CppAD::ADFun<Scalar> ajoint(ad_a,Y);
264 CPPAD_TESTVECTOR(Scalar)
x((
size_t)model.nv);
265 for(Eigen::DenseIndex k = 0; k < model.nv; ++k)
270 CPPAD_TESTVECTOR(Scalar) y = ajoint.Forward(0,
x);
271 Scalar * y_ptr = y.data()+6;
272 BOOST_CHECK(data.a[joint_id].isApprox(Motion(Eigen::Map<Motion::Vector6>(y_ptr))));
275 CPPAD_TESTVECTOR(Scalar) dY_da = ajoint.Jacobian(
x);
277 Scalar * dY_da_ptr = dY_da.data();
278 Data::Matrix6x ad_dv_da = Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Data::Matrix6x)>(dY_da_ptr,6,model.nv);
279 dY_da_ptr += ad_dv_da.size();
280 Data::Matrix6x ad_J_local = Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Data::Matrix6x)>(dY_da_ptr,6,model.nv);
281 dY_da_ptr += ad_J_local.size();
283 BOOST_CHECK(ad_dv_da.isZero());
284 BOOST_CHECK(ad_J_local.isApprox(J_local));
288 BOOST_AUTO_TEST_SUITE_END()
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...
The WORLD frame convention corresponds to the frame concident with the Universe/Inertial frame but mo...
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...
const DataTpl< Scalar, Options, JointCollectionTpl >::RowMatrixXs & computeMinverse(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the inverse of the joint space inertia matrix using Articulated Body formulation.
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...
void randomConfiguration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &lowerLimits, const Eigen::MatrixBase< ConfigVectorIn2 > &upperLimits, const Eigen::MatrixBase< ReturnType > &qout)
Generate a configuration vector uniformly sampled among provided limits.
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...
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.
The LOCAL frame convention corresponds to the frame directly attached to the moving part (Joint...
MotionTpl< double, 0 > Motion
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeJointJacobiansTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the full model Jacobian variations with respect to time. It corresponds to dJ/dt which depen...
Eigen::Matrix< double, 6, Eigen::Dynamic > Matrix6x
void getJointJacobianTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6Like > &dJ)
Computes the Jacobian time variation of a specific joint frame expressed either in the world frame (r...
BOOST_AUTO_TEST_CASE(test_mass_matrix)
void humanoidRandom(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true)
Create a humanoid kinematic tree with 6-DOF limbs and random joint placements.
void fill(Eigen::Ref< MatType > mat, const typename MatType::Scalar &value)