5 #include "pinocchio/multibody/model.hpp" 6 #include "pinocchio/multibody/data.hpp" 7 #include "pinocchio/algorithm/jacobian.hpp" 8 #include "pinocchio/algorithm/joint-configuration.hpp" 9 #include "pinocchio/algorithm/kinematics.hpp" 10 #include "pinocchio/algorithm/kinematics-derivatives.hpp" 11 #include "pinocchio/algorithm/rnea.hpp" 12 #include "pinocchio/algorithm/rnea-derivatives.hpp" 13 #include "pinocchio/algorithm/aba.hpp" 14 #include "pinocchio/algorithm/aba-derivatives.hpp" 15 #include "pinocchio/algorithm/crba.hpp" 16 #include "pinocchio/parsers/sample-models.hpp" 20 #include <boost/test/unit_test.hpp> 21 #include <boost/utility/binary.hpp> 23 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
27 using namespace Eigen;
42 MatrixXd aba_partial_dq(model.
nv,model.
nv); aba_partial_dq.setZero();
43 MatrixXd aba_partial_dv(model.
nv,model.
nv); aba_partial_dv.setZero();
50 BOOST_CHECK(
data.oMi[k].isApprox(data_ref.oMi[k]));
51 BOOST_CHECK(
data.v[k].isApprox(data_ref.v[k]));
52 BOOST_CHECK(
data.ov[k].isApprox(data_ref.ov[k]));
53 BOOST_CHECK(
data.oa_gf[k].isApprox(data_ref.oa_gf[k]));
54 BOOST_CHECK(
data.of[k].isApprox(data_ref.of[k]));
55 BOOST_CHECK(
data.oYcrb[k].isApprox(data_ref.oYcrb[k]));
56 BOOST_CHECK(
data.doYcrb[k].isApprox(data_ref.doYcrb[k]));
60 BOOST_CHECK(
data.J.isApprox(data_ref.
J));
62 aba(model,data_ref,q,v,tau);
63 BOOST_CHECK(
data.ddq.isApprox(data_ref.
ddq));
66 data_ref.
Minv.triangularView<Eigen::StrictlyLower>()
67 = data_ref.
Minv.transpose().triangularView<Eigen::StrictlyLower>();
69 BOOST_CHECK(aba_partial_dtau.isApprox(data_ref.
Minv));
71 BOOST_CHECK(
data.J.isApprox(data_ref.
J));
72 BOOST_CHECK(
data.dJ.isApprox(data_ref.
dJ));
73 BOOST_CHECK(
data.dVdq.isApprox(data_ref.
dVdq));
74 BOOST_CHECK(
data.dAdq.isApprox(data_ref.
dAdq));
75 BOOST_CHECK(
data.dAdv.isApprox(data_ref.
dAdv));
76 BOOST_CHECK(
data.dtau_dq.isApprox(data_ref.
dtau_dq));
77 BOOST_CHECK(
data.dtau_dv.isApprox(data_ref.
dtau_dv));
79 MatrixXd aba_partial_dq_fd(model.
nv,model.
nv); aba_partial_dq_fd.setZero();
80 MatrixXd aba_partial_dv_fd(model.
nv,model.
nv); aba_partial_dv_fd.setZero();
81 MatrixXd aba_partial_dtau_fd(model.
nv,model.
nv); aba_partial_dtau_fd.setZero();
88 const double alpha = 1e-8;
89 for(
int k = 0; k < model.
nv; ++k)
93 a_plus =
aba(model,data_fd,q_plus,v,tau);
95 aba_partial_dq_fd.col(k) = (a_plus -
a0)/alpha;
98 BOOST_CHECK(aba_partial_dq.isApprox(aba_partial_dq_fd,sqrt(alpha)));
101 for(
int k = 0; k < model.
nv; ++k)
104 a_plus =
aba(model,data_fd,q,v_plus,tau);
106 aba_partial_dv_fd.col(k) = (a_plus -
a0)/alpha;
109 BOOST_CHECK(aba_partial_dv.isApprox(aba_partial_dv_fd,sqrt(alpha)));
112 for(
int k = 0; k < model.
nv; ++k)
114 tau_plus[k] += alpha;
115 a_plus =
aba(model,data_fd,q,v,tau_plus);
117 aba_partial_dtau_fd.col(k) = (a_plus -
a0)/alpha;
118 tau_plus[k] -= alpha;
120 BOOST_CHECK(aba_partial_dtau.isApprox(aba_partial_dtau_fd,sqrt(alpha)));
125 using namespace Eigen;
140 MatrixXd aba_partial_dq(model.
nv,model.
nv); aba_partial_dq.setZero();
141 MatrixXd aba_partial_dv(model.
nv,model.
nv); aba_partial_dv.setZero();
148 BOOST_CHECK(
data.J.isApprox(data_ref.
J));
149 BOOST_CHECK(
data.dJ.isApprox(data_ref.
dJ));
150 BOOST_CHECK(
data.dVdq.isApprox(data_ref.
dVdq));
151 BOOST_CHECK(
data.dAdq.isApprox(data_ref.
dAdq));
152 BOOST_CHECK(
data.dAdv.isApprox(data_ref.
dAdv));
153 BOOST_CHECK(
data.dtau_dq.isApprox(data_ref.
dtau_dq));
154 BOOST_CHECK(
data.dtau_dv.isApprox(data_ref.
dtau_dv));
155 BOOST_CHECK(
data.Minv.isApprox(aba_partial_dtau));
156 BOOST_CHECK(
data.ddq_dq.isApprox(aba_partial_dq));
157 BOOST_CHECK(
data.ddq_dv.isApprox(aba_partial_dv));
162 using namespace Eigen;
178 ForceVector fext((
size_t)model.
njoints);
179 for(ForceVector::iterator it = fext.begin(); it != fext.end(); ++it)
182 MatrixXd aba_partial_dq(model.
nv,model.
nv); aba_partial_dq.setZero();
183 MatrixXd aba_partial_dv(model.
nv,model.
nv); aba_partial_dv.setZero();
187 aba_partial_dq, aba_partial_dv, aba_partial_dtau);
189 aba(model,data_ref,q,v,tau,fext);
197 BOOST_CHECK(
data.ddq.isApprox(data_ref.
ddq));
200 BOOST_CHECK(aba_partial_dv.isApprox(data_ref.
ddq_dv));
201 BOOST_CHECK(aba_partial_dtau.isApprox(data_ref.
Minv));
203 MatrixXd aba_partial_dq_fd(model.
nv,model.
nv); aba_partial_dq_fd.setZero();
204 MatrixXd aba_partial_dv_fd(model.
nv,model.
nv); aba_partial_dv_fd.setZero();
205 MatrixXd aba_partial_dtau_fd(model.
nv,model.
nv); aba_partial_dtau_fd.setZero();
212 const double alpha = 1e-8;
213 for(
int k = 0; k < model.
nv; ++k)
217 a_plus =
aba(model,data_fd,q_plus,v,tau,fext);
219 aba_partial_dq_fd.col(k) = (a_plus -
a0)/alpha;
222 BOOST_CHECK(aba_partial_dq.isApprox(aba_partial_dq_fd,sqrt(alpha)));
225 for(
int k = 0; k < model.
nv; ++k)
228 a_plus =
aba(model,data_fd,q,v_plus,tau,fext);
230 aba_partial_dv_fd.col(k) = (a_plus -
a0)/alpha;
233 BOOST_CHECK(aba_partial_dv.isApprox(aba_partial_dv_fd,sqrt(alpha)));
236 for(
int k = 0; k < model.
nv; ++k)
238 tau_plus[k] += alpha;
239 a_plus =
aba(model,data_fd,q,v,tau_plus,fext);
241 aba_partial_dtau_fd.col(k) = (a_plus -
a0)/alpha;
242 tau_plus[k] -= alpha;
244 BOOST_CHECK(aba_partial_dtau.isApprox(aba_partial_dtau_fd,sqrt(alpha)));
247 Data data_shortcut(model);
249 BOOST_CHECK(data_shortcut.ddq_dq.isApprox(aba_partial_dq));
250 BOOST_CHECK(data_shortcut.ddq_dv.isApprox(aba_partial_dv));
251 BOOST_CHECK(data_shortcut.Minv.isApprox(aba_partial_dtau));
256 using namespace Eigen;
262 Data data1(model), data2(model);
273 for(
int k = 0; k < 20; ++k)
278 BOOST_CHECK(data1.J.isApprox(data2.
J));
279 BOOST_CHECK(data1.dJ.isApprox(data2.
dJ));
280 BOOST_CHECK(data1.dVdq.isApprox(data2.
dVdq));
281 BOOST_CHECK(data1.dAdq.isApprox(data2.
dAdq));
282 BOOST_CHECK(data1.dAdv.isApprox(data2.
dAdv));
284 BOOST_CHECK(data1.dFdq.isApprox(data2.
dFdq));
285 BOOST_CHECK(data1.dFdv.isApprox(data2.
dFdv));
287 BOOST_CHECK(data1.dtau_dq.isApprox(data2.
dtau_dq));
288 BOOST_CHECK(data1.dtau_dv.isApprox(data2.
dtau_dv));
290 BOOST_CHECK(data1.ddq_dq.isApprox(data2.
ddq_dq));
291 BOOST_CHECK(data1.ddq_dv.isApprox(data2.
ddq_dv));
292 BOOST_CHECK(data1.Minv.isApprox(data2.
Minv));
297 using namespace Eigen;
314 MatrixXd aba_partial_dq(model.
nv,model.
nv); aba_partial_dq.setZero();
315 MatrixXd aba_partial_dv(model.
nv,model.
nv); aba_partial_dv.setZero();
316 MatrixXd aba_partial_dtau(model.
nv,model.
nv); aba_partial_dtau.setZero();
321 BOOST_CHECK(
data.J.isApprox(data_ref.
J));
322 BOOST_CHECK(
data.dJ.isApprox(data_ref.
dJ));
324 for(
size_t k = 1; k < (size_t)model.
njoints; ++k)
326 BOOST_CHECK(
data.oMi[k].isApprox(data_ref.oMi[k]));
327 BOOST_CHECK(
data.ov[k].isApprox(data_ref.ov[k]));
328 BOOST_CHECK(
data.oa[k].isApprox(data_ref.oa[k]));
332 BOOST_AUTO_TEST_SUITE_END()
Matrix6x dJ
Derivative of the Jacobian with respect to the time.
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...
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor|Options > RowMatrixXs
Matrix6x J
Jacobian of joint placements.
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.
MatrixXs dtau_dv
Partial derivative of the joint torque vector with respect to the joint velocity. ...
Matrix6x dAdv
Variation of the spatial acceleration set with respect to the joint velocity.
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 integrate(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const Eigen::MatrixBase< ReturnType > &qout)
Integrate a configuration vector for the specified model for a tangent vector during one unit time...
int njoints
Number of joints.
ConfigVectorType lowerPositionLimit
Lower joint configuration limit.
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.
MatrixXs dtau_dq
Partial derivative of the joint torque vector with respect to the joint configuration.
RowMatrixXs Minv
The inverse of the joint space inertia matrix (a square matrix of dim model.nv).
MatrixXs ddq_dq
Partial derivative of the joint acceleration vector with respect to the joint configuration.
Matrix6x dFdq
Variation of the forceset with respect to the joint configuration.
Matrix6x dAdq
Variation of the spatial acceleration set with respect to the joint configuration.
bp::tuple computeRNEADerivatives(const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &a)
#define PINOCCHIO_ALIGNED_STD_VECTOR(Type)
pinocchio::JointIndex JointIndex
void computeForwardKinematicsDerivatives(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 > &a)
Computes all the terms required to compute the derivatives of the placement, spatial velocity and acc...
TangentVectorType ddq
The joint accelerations computed from ABA.
Matrix6x dFdv
Variation of the forceset with respect to the joint velocity.
BOOST_AUTO_TEST_CASE(test_aba_derivatives)
MatrixXs ddq_dv
Partial derivative of the joint acceleration vector with respect to the joint velocity.
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.
ConfigVectorType upperPositionLimit
Upper joint configuration limit.
void computeABADerivatives(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, const Eigen::MatrixBase< MatrixType1 > &aba_partial_dq, const Eigen::MatrixBase< MatrixType2 > &aba_partial_dv, const Eigen::MatrixBase< MatrixType3 > &aba_partial_dtau)
The derivatives of the Articulated-Body algorithm.
void humanoidRandom(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true)
Create a humanoid kinematic tree with 6-DOF limbs and random joint placements.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
int nq
Dimension of the configuration vector representation.
Matrix6x dVdq
Variation of the spatial velocity set with respect to the joint configuration.