Go to the documentation of this file.
30 #include <pmmintrin.h>
33 #include <boost/test/unit_test.hpp>
34 #include <boost/utility/binary.hpp>
36 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
41 _MM_SET_DENORMALS_ZERO_MODE(_MM_DENORMALS_ZERO_ON);
43 using namespace Eigen;
49 model.lowerPositionLimit.head<3>().
fill(-1.);
50 model.upperPositionLimit.head<3>().
fill(1.);
53 data.v[0] = Motion::Zero();
57 VectorXd
v = VectorXd::Random(
model.nv);
58 VectorXd
a = VectorXd::Random(
model.nv);
61 const size_t NBT = 10000;
64 std::cout <<
"(the time score in debug mode is not relevant) ";
73 timer.
toc(std::cout, NBT);
78 using namespace Eigen;
84 model.lowerPositionLimit.head<3>().
fill(-1.);
85 model.upperPositionLimit.head<3>().
fill(1.);
91 VectorXd
v = VectorXd::Random(
model.nv);
93 VectorXd tau_nle(VectorXd::Zero(
model.nv));
97 q.tail(
model.nq - 7).setZero();
103 BOOST_CHECK(tau_nle.isApprox(
tau_rnea, 1e-12));
106 q.tail(
model.nq - 7).setZero();
112 BOOST_CHECK(tau_nle.isApprox(
tau_rnea, 1e-12));
115 q.tail(
model.nq - 7).setOnes();
121 BOOST_CHECK(tau_nle.isApprox(
tau_rnea, 1e-12));
130 BOOST_CHECK(tau_nle.isApprox(
tau_rnea, 1e-12));
135 using namespace Eigen;
141 model.lowerPositionLimit.head<3>().
fill(-1.);
142 model.upperPositionLimit.head<3>().
fill(1.);
149 VectorXd
v(VectorXd::Random(
model.nv));
150 VectorXd
a(VectorXd::Random(
model.nv));
155 Force Frf = Force::Random();
158 Force Flf = Force::Random();
162 VectorXd tau_ref(data_rnea.
tau);
165 tau_ref -= Jrf.transpose() * Frf.toVector();
169 tau_ref -= Jlf.transpose() * Flf.toVector();
173 BOOST_CHECK(tau_ref.isApprox(data_rnea_fext.
tau));
178 using namespace Eigen;
183 model.armature = VectorXd::Random(
model.nv) + VectorXd::Ones(
model.nv);
185 model.lowerPositionLimit.head<3>().
fill(-1.);
186 model.upperPositionLimit.head<3>().
fill(1.);
192 VectorXd
v(VectorXd::Random(
model.nv));
193 VectorXd
a(VectorXd::Random(
model.nv));
196 data_ref.
M.triangularView<StrictlyLower>() =
197 data_ref.
M.transpose().triangularView<StrictlyLower>();
200 const VectorXd tau_ref = data_ref.
M *
a +
nle;
203 BOOST_CHECK(tau_ref.isApprox(
data.tau));
208 using namespace Eigen;
214 model.lowerPositionLimit.head<3>().
fill(-1.);
215 model.upperPositionLimit.head<3>().
fill(1.);
225 BOOST_CHECK(data_rnea.
tau.isApprox(
data.g));
231 VectorXd g_ref(-data_rnea.
mass[0] * Jcom.transpose() * Model::gravity981);
233 BOOST_CHECK(g_ref.isApprox(
data.g));
238 using namespace Eigen;
244 model.lowerPositionLimit.head<3>().
fill(-1.);
245 model.upperPositionLimit.head<3>().
fill(1.);
253 ForceVector fext((
size_t)
model.njoints);
254 for (ForceVector::iterator
it = fext.begin();
it != fext.end(); ++
it)
260 BOOST_CHECK(data_rnea.
tau.isApprox(
data.tau));
266 VectorXd static_torque_ref = -data_rnea.
mass[0] * Jcom.transpose() * Model::gravity981;
274 static_torque_ref -= J_local.transpose() * fext[
joint_id].toVector();
277 BOOST_CHECK(static_torque_ref.isApprox(
data.tau));
282 using namespace Eigen;
285 const double prec = Eigen::NumTraits<double>::dummy_precision();
290 model.lowerPositionLimit.head<3>().
fill(-1.);
291 model.upperPositionLimit.head<3>().
fill(1.);
298 VectorXd
v(VectorXd::Random(
model.nv));
300 BOOST_CHECK(
data.C.isZero(prec));
302 model.gravity.setZero();
307 BOOST_CHECK(
data.dJ.isApprox(data_ref.
dJ));
308 BOOST_CHECK(
data.J.isApprox(data_ref.
J));
311 BOOST_CHECK(
tau.isApprox(data_ref.
tau, prec));
317 Motion vcom(data_ref.vcom[0], Data::Vector3::Zero());
321 BOOST_CHECK((cM1.toDualActionMatrix() * data_ref.
M.topRows<6>()).isApprox(data_ref.
Ag, prec));
325 BOOST_CHECK(dh.isApprox(dh_ref, prec));
329 Eigen::MatrixXd
dM(
data.C +
data.C.transpose());
331 const double alpha = 1e-8;
332 Eigen::VectorXd q_plus(
model.nq);
336 data_ref.
M.triangularView<Eigen::StrictlyLower>() =
337 data_ref.
M.transpose().triangularView<Eigen::StrictlyLower>();
339 data_ref_plus.
M.triangularView<Eigen::StrictlyLower>() =
340 data_ref_plus.
M.transpose().triangularView<Eigen::StrictlyLower>();
342 Eigen::MatrixXd dM_ref = (data_ref_plus.
M - data_ref.
M) /
alpha;
343 BOOST_CHECK(
dM.isApprox(dM_ref, sqrt(
alpha)));
347 BOOST_AUTO_TEST_SUITE_END()
MatrixXs M
The joint space inertia matrix (a square matrix of dim model.nv).
Matrix6x dAg
Centroidal Momentum Matrix Time Variation.
std::vector< Scalar > mass
Vector of subtree mass. In other words, mass[j] is the mass of the subtree supported by joint ....
Matrix6x dJ
Derivative of the Jacobian with respect to the time.
ForceTpl< Scalar, Options > Force
void humanoidRandom(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true)
Create a humanoid kinematic tree with 6-DOF limbs and random joint placements.
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & crba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Convention convention=Convention::LOCAL)
Computes the upper triangular part of the joint space inertia matrix M by using the Composite Rigid B...
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...
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....
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & dccrba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the time derivative of the Centroidal Momentum Matrix according to the current configuration...
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.
ConstLinearRef translation() const
Eigen::Matrix< Scalar, 3, Eigen::Dynamic, Options > Matrix3x
The 3d jacobian type (temporary)
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.
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & computeStaticTorque(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const container::aligned_vector< ForceTpl< Scalar, Options >> &fext)
Computes the generalized static torque contribution of the Lagrangian dynamics:
void getJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6Like > &J)
Computes the Jacobian of a specific joint frame expressed in one of the pinocchio::ReferenceFrame opt...
TangentVectorType tau
Vector of joint torques (dim model.nv).
BOOST_AUTO_TEST_CASE(test_rnea)
Matrix6x Ag
Centroidal Momentum Matrix.
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & nonLinearEffects(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the non-linear effects (Corriolis, centrifual and gravitationnal effects),...
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix3x & getJacobianComFromCrba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Extracts both the jacobian of the center of mass (CoM), the total mass of the system and the CoM posi...
Matrix6x J
Jacobian of joint placements.
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & rnea(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)
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques accordi...
void computeJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const JointIndex joint_id, const Eigen::MatrixBase< Matrix6Like > &J)
Computes the Jacobian of a specific joint frame expressed in the local frame of the joint and store t...
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
#define PINOCCHIO_ALIGNED_STD_VECTOR(Type)
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & computeCoriolisMatrix(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the Coriolis Matrix of the Lagrangian dynamics:
Main pinocchio namespace.
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & computeGeneralizedGravity(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the generalized gravity contribution of the Lagrangian dynamics:
pinocchio
Author(s):
autogenerated on Thu Dec 19 2024 03:41:32