Go to the documentation of this file.
16 #include <casadi/casadi.hpp>
19 #include <boost/test/unit_test.hpp>
20 #include <boost/utility/binary.hpp>
22 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
29 typedef typename Model::ConfigVectorType ConfigVector;
30 typedef typename Model::TangentVectorType TangentVector;
32 const Scalar prec = Eigen::NumTraits<Scalar>::dummy_precision();
36 model.lowerPositionLimit.head<3>().
fill(-1.);
37 model.upperPositionLimit.head<3>().
fill(1.);
40 const std::string RF =
"rleg6_joint";
42 const std::string LF =
"lleg6_joint";
51 ci_RF.joint1_placement.setRandom();
57 ci_LF.joint1_placement.setRandom();
60 const double mu0 = 0.;
63 TangentVector
v(TangentVector::Random(
model.nv));
64 TangentVector
tau(TangentVector::Random(
model.nv));
75 BOOST_CHECK(ad_casadi.
ddq.isApprox(
data.ddq, 1e1 * prec));
76 BOOST_CHECK(ad_casadi.
lambda_c.isApprox(
data.lambda_c, 1e1 * prec));
77 BOOST_CHECK(ad_casadi.
ddq_dq.isApprox(
data.ddq_dq, 1e1 * prec));
78 BOOST_CHECK(ad_casadi.
ddq_dv.isApprox(
data.ddq_dv, 1e1 * prec));
79 BOOST_CHECK(ad_casadi.
ddq_dtau.isApprox(
data.ddq_dtau, 1e1 * prec));
80 BOOST_CHECK(ad_casadi.
dlambda_dq.isApprox(
data.dlambda_dq, 1e1 * prec));
81 BOOST_CHECK(ad_casadi.
dlambda_dv.isApprox(
data.dlambda_dv, 1e1 * prec));
85 BOOST_AUTO_TEST_SUITE_END()
void evalFunction(const Eigen::MatrixBase< ConfigVectorType1 > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &tau)
TangentVectorType lambda_c
void computeConstraintDynamicsDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_data, const ProximalSettingsTpl< Scalar > &settings, const Eigen::MatrixBase< MatrixType1 > &ddq_partial_dq, const Eigen::MatrixBase< MatrixType2 > &ddq_partial_dv, const Eigen::MatrixBase< MatrixType3 > &ddq_partial_dtau, const Eigen::MatrixBase< MatrixType4 > &lambda_partial_dq, const Eigen::MatrixBase< MatrixType5 > &lambda_partial_dv, const Eigen::MatrixBase< MatrixType6 > &lambda_partial_dtau)
BOOST_AUTO_TEST_CASE(test_constraintDynamicsDerivatives_casadi_algo)
void humanoidRandom(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true)
Create a humanoid kinematic tree with 6-DOF limbs and random joint placements.
void loadLib(const bool generate_if_not_exist=true)
ModelTpl< Scalar, Options > Model
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.
@ CONTACT_6D
Point contact model.
DataTpl< Scalar, Options > Data
void initConstraintDynamics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, Allocator > &contact_models)
Init the forward dynamics data according to the contact information contained in contact_models.
#define PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(T)
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & constraintDynamics(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 std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_datas, ProximalSettingsTpl< Scalar > &settings)
Computes the forward dynamics with contact constraints according to a given list of contact informati...
pinocchio
Author(s):
autogenerated on Thu Dec 19 2024 03:41:28