Go to the documentation of this file.
23 #include <boost/test/unit_test.hpp>
24 #include <boost/utility/binary.hpp>
30 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
52 switch (reference_frame)
58 res.linear() = oa.linear();
59 res.angular() = oa.angular();
73 res.angular() = iMc.rotation().transpose() *
data.a[
joint_id].angular();
84 using namespace Eigen;
91 model.lowerPositionLimit.head<3>().
fill(-1.);
92 model.upperPositionLimit.head<3>().
fill(1.);
95 VectorXd
v = VectorXd::Random(
model.nv);
96 VectorXd
tau = VectorXd::Random(
model.nv);
98 const std::string RF =
"rleg6_joint";
100 const std::string LF =
"lleg6_joint";
105 RigidConstraintModelVector;
111 CoulombFrictionConeVector cones;
132 Eigen::VectorXd constraint_correction = Eigen::VectorXd::Zero(
constraint_dim);
133 boost::optional<Eigen::VectorXd> lambda_guess = boost::optional<Eigen::VectorXd>(boost::none);
134 Eigen::VectorXd
a = Eigen::VectorXd::Zero(
model.nv);
138 model, data_ref,
q,
v,
a,
dt,
contact_models,
contact_datas, cones,
R, constraint_correction,
182 BOOST_AUTO_TEST_SUITE_END()
RigidConstraintDataTpl< context::Scalar, context::Options > RigidConstraintData
ReferenceFrame
Various conventions to express the velocity of a moving frame.
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & contactInverseDynamics(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, Scalar dt, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_datas, const std::vector< CoulombFrictionConeTpl< Scalar >, CoulombFrictionConelAllocator > &cones, const Eigen::MatrixBase< VectorLikeR > &R, const Eigen::MatrixBase< VectorLikeGamma > &constraint_correction, ProximalSettingsTpl< Scalar > &settings, const boost::optional< VectorLikeLam > &lambda_guess=boost::none)
The Contact Inverse Dynamics algorithm. It computes the inverse dynamics in the presence of contacts,...
void classicAcceleration(const MotionDense< Motion1 > &spatial_velocity, const MotionDense< Motion2 > &spatial_acceleration, const Eigen::MatrixBase< Vector3Like > &res)
Computes the classic acceleration from a given spatial velocity and spatial acceleration.
void humanoidRandom(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true)
Create a humanoid kinematic tree with 6-DOF limbs and random joint placements.
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.
Structure containing all the settings parameters for the proximal algorithms.
const MotionDense< Motion2 > const SE3Tpl< SE3Scalar, SE3Options > & placement
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.
ConstAngularRef rotation() const
#define PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(T)
CoulombFrictionConeTpl< context::Scalar > CoulombFrictionCone
Main pinocchio namespace.
#define PINOCCHIO_UNUSED_VARIABLE(var)
Helper to declare that a parameter is unused.
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:43