5 #include "pinocchio/multibody/model.hpp" 6 #include "pinocchio/multibody/data.hpp" 7 #include "pinocchio/multibody/joint/joint-spherical.hpp" 8 #include "pinocchio/algorithm/crba.hpp" 9 #include "pinocchio/algorithm/centroidal.hpp" 10 #include "pinocchio/algorithm/centroidal-derivatives.hpp" 11 #include "pinocchio/algorithm/rnea-derivatives.hpp" 12 #include "pinocchio/algorithm/jacobian.hpp" 13 #include "pinocchio/algorithm/center-of-mass.hpp" 14 #include "pinocchio/algorithm/joint-configuration.hpp" 15 #include "pinocchio/parsers/sample-models.hpp" 16 #include "pinocchio/utils/timer.hpp" 20 #include <boost/test/unit_test.hpp> 21 #include <boost/utility/binary.hpp> 23 template<
typename Jo
intModel>
26 const std::string & parent_name,
27 const std::string &
name,
29 bool setRandomLimits =
true)
32 typedef typename JointModel::ConfigVector_t CV;
33 typedef typename JointModel::TangentVector_t TV;
41 TV::Random() + TV::Constant(1),
42 TV::Random() + TV::Constant(1),
43 CV::Random() - CV::Constant(1),
44 CV::Random() + CV::Constant(1)
62 const std::string parent_name = model.
names.back();
63 const std::string
joint_name =
"ee_spherical_joint";
76 dh_dq(6,model.
nv),dhdot_dq(6,model.
nv), dhdot_dv(6,model.
nv), dhdot_da(6,model.
nv);
78 dh_dq,dhdot_dq,dhdot_dv,dhdot_da);
81 for(
size_t k = 0; k < (size_t)model.
njoints; ++k)
83 BOOST_CHECK(
data.oMi[k].isApprox(data_ref.oMi[k]));
84 BOOST_CHECK(
data.oYcrb[k].isApprox(data_ref.oYcrb[k]));
86 BOOST_CHECK(dhdot_da.isApprox(data_ref.
Ag));
89 for(
size_t k = 1; k < (size_t)model.
njoints; ++k)
91 BOOST_CHECK(
data.v[k].isApprox(data_ref.v[k]));
92 BOOST_CHECK(
data.ov[k].isApprox(
data.oMi[k].act(data_ref.v[k])));
93 BOOST_CHECK(
data.oa[k].isApprox(
data.oMi[k].act(data_ref.a[k])));
94 BOOST_CHECK(
data.oh[k].isApprox(
data.oMi[k].act(data_ref.h[k])));
97 BOOST_CHECK(
data.mass[0] == data_ref.
mass[0]);
98 BOOST_CHECK(
data.com[0].isApprox(data_ref.com[0]));
100 BOOST_CHECK(
data.oh[0].isApprox(data_ref.h[0]));
101 BOOST_CHECK(
data.of[0].isApprox(data_ref.f[0]));
103 BOOST_CHECK(
data.hg.isApprox(data_ref.
hg));
104 BOOST_CHECK(
data.dhg.isApprox(data_ref.
dhg));
108 const double eps = 1e-8;
111 BOOST_CHECK(
data.hg.isApprox(data_ref.
hg));
119 for(Eigen::DenseIndex k = 0; k < model.
nv; ++k)
128 dhdot_dq_fd.col(k) = (dhg_plus - dhg).toVector()/
eps;
129 dh_dq_fd.col(k) = (hg_plus - hg).toVector()/
eps;
133 BOOST_CHECK(dhdot_dq.isApprox(dhdot_dq_fd,sqrt(eps)));
134 BOOST_CHECK(dh_dq.isApprox(dh_dq_fd,sqrt(eps)));
139 for(Eigen::DenseIndex k = 0; k < model.
nv; ++k)
145 dhdot_dv_fd.col(k) = (dhg_plus - dhg).toVector()/
eps;
150 BOOST_CHECK(dhdot_dv.isApprox(dhdot_dv_fd,sqrt(eps)));
156 for(Eigen::DenseIndex k = 0; k < model.
nv; ++k)
162 dhdot_da_fd.col(k) = (dhg_plus - dhg).toVector()/
eps;
167 BOOST_CHECK(dhdot_da.isApprox(dhdot_da_fd,sqrt(eps)));
170 BOOST_CHECK(
data.dAdv.isApprox(data_ref.
dAdv));
171 BOOST_CHECK(
data.dAdq.isApprox(data_ref.
dAdq));
172 BOOST_CHECK(
data.J.isApprox(data_ref.
J));
173 BOOST_CHECK(
data.dJ.isApprox(data_ref.
dJ));
174 BOOST_CHECK(
data.dVdq.isApprox(data_ref.
dVdq));
191 dh_dq(6,model.
nv), dhdot_dq(6,model.
nv), dhdot_dv(6,model.
nv), dhdot_da(6,model.
nv);
193 dh_dq_ref(6,model.
nv), dhdot_dq_ref(6,model.
nv), dhdot_dv_ref(6,model.
nv), dhdot_da_ref(6,model.
nv);
196 dh_dq_ref, dhdot_dq_ref,dhdot_dv_ref,dhdot_da_ref);
200 dh_dq, dhdot_dq,dhdot_dv,dhdot_da);
202 BOOST_CHECK(
data.J.isApprox(data_ref.
J));
206 BOOST_CHECK(
data.oYcrb[k].isApprox(data_ref.oYcrb[k]));
210 BOOST_CHECK(force.
isApprox(force_ref));
213 BOOST_CHECK(
data.com[0].isApprox(data_ref.com[0]));
215 BOOST_CHECK(
data.hg.isApprox(data_ref.
hg));
216 BOOST_CHECK(
data.dhg.isApprox(data_ref.
dhg));
218 BOOST_CHECK(
data.Fcrb[0].isApprox(data_ref.
dFdq));
219 BOOST_CHECK(
data.dFdv.isApprox(data_ref.
dFdv));
220 BOOST_CHECK(
data.dFda.isApprox(data_ref.
dFda));
221 BOOST_CHECK(dh_dq.isApprox(dh_dq_ref));
222 BOOST_CHECK(dhdot_dq.isApprox(dhdot_dq_ref));
223 BOOST_CHECK(dhdot_dv.isApprox(dhdot_dv_ref));
224 BOOST_CHECK(dhdot_da.isApprox(dhdot_da_ref));
228 BOOST_AUTO_TEST_SUITE_END()
Matrix6x dJ
Derivative of the Jacobian with respect to the time.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
bool isApprox(const ForceDense< M2 > &f, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
void addJointAndBody(Model &model, const JointModelBase< D > &jmodel, const Model::JointIndex parent_id, const SE3 &joint_placement, const std::string &name, const Inertia &Y)
void computeCentroidalDynamicsDerivatives(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, const Eigen::MatrixBase< Matrix6xLike0 > &dh_dq, const Eigen::MatrixBase< Matrix6xLike1 > &dhdot_dq, const Eigen::MatrixBase< Matrix6xLike2 > &dhdot_dv, const Eigen::MatrixBase< Matrix6xLike3 > &dhdot_da)
Computes the analytical derivatives of the centroidal dynamics with respect to the joint configuratio...
FrameIndex addJointFrame(const JointIndex &joint_index, int previous_frame_index=-1)
Add a joint to the frame tree.
Matrix6x J
Jacobian of joint placements.
Matrix6x dAdv
Variation of the spatial acceleration set with respect to the joint velocity.
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...
static InertiaTpl Random()
int njoints
Number of joints.
Matrix6x dFda
Variation of the forceset with respect to the joint acceleration.
std::vector< std::string > names
Name of joint i
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.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
const DataTpl< Scalar, Options, JointCollectionTpl >::Force & computeCentroidalMomentumTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Computes the Centroidal momemtum and its time derivatives, a.k.a. the total momenta of the system and...
void computeRNEADerivatives(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, const Eigen::MatrixBase< MatrixType1 > &rnea_partial_dq, const Eigen::MatrixBase< MatrixType2 > &rnea_partial_dv, const Eigen::MatrixBase< MatrixType3 > &rnea_partial_da)
Computes the partial derivatives of the Recursive Newton Euler Algorithms with respect to the joint c...
void getCentroidalDynamicsDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Matrix6xLike1 > &dh_dq, const Eigen::MatrixBase< Matrix6xLike1 > &dhdot_dq, const Eigen::MatrixBase< Matrix6xLike2 > &dhdot_dv, const Eigen::MatrixBase< Matrix6xLike3 > &dhdot_da)
Retrive the analytical derivatives of the centroidal dynamics from the RNEA derivatives. pinocchio::computeRNEADerivatives should have been called first.
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & ccrba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the Centroidal Momentum Matrix, the Composite Ridig Body Inertia as well as the centroidal m...
Matrix6x dFdq
Variation of the forceset with respect to the joint configuration.
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.
Matrix6x dAdq
Variation of the spatial acceleration set with respect to the joint configuration.
pinocchio::JointIndex JointIndex
static void addJointAndBody(pinocchio::Model &model, const pinocchio::JointModelBase< JointModel > &joint, const std::string &parent_name, const std::string &name, const pinocchio::SE3 placement=pinocchio::SE3::Random(), bool setRandomLimits=true)
Motion gravity
Spatial gravity of the model.
BOOST_AUTO_TEST_CASE(test_centroidal_derivatives)
#define BOOST_TEST_MODULE
Matrix6x dFdv
Variation of the forceset with respect to the joint velocity.
Force dhg
Centroidal momentum time derivative.
Main pinocchio namespace.
JointIndex getJointId(const std::string &name) const
Return the index of a joint given by its name.
Matrix6x Ag
Centroidal Momentum Matrix.
int nv
Dimension of the velocity vector space.
ConfigVectorType upperPositionLimit
Upper joint configuration limit.
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.
Force hg
Centroidal momentum quantity.
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
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
JointCollectionTpl & model
int nq
Dimension of the configuration vector representation.
std::vector< Scalar > mass
Vector of subtree mass. In other words, mass[j] is the mass of the subtree supported by joint ...
Matrix6x dVdq
Variation of the spatial velocity set with respect to the joint configuration.
FrameIndex addBodyFrame(const std::string &body_name, const JointIndex &parentJoint, const SE3 &body_placement=SE3::Identity(), int previousFrame=-1)
Add a body to the frame tree.