contact-inverse-dynamics.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2019-2023 INRIA
3 //
4 
20 
21 #include <iostream>
22 
23 #include <boost/test/unit_test.hpp>
24 #include <boost/utility/binary.hpp>
25 #include <optional>
26 
27 #define KP 10
28 #define KD 10
29 
30 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
31 
34  const pinocchio::Model & model,
37  pinocchio::ReferenceFrame reference_frame,
40 {
42  using namespace pinocchio;
44 
45  const Data::SE3 & oMi = data.oMi[joint_id];
46  const Data::SE3 & iMc = placement;
47  const Data::SE3 oMc = oMi * iMc;
48 
49  const Motion ov = oMi.act(data.v[joint_id]);
50  const Motion oa = oMi.act(data.a[joint_id]);
51 
52  switch (reference_frame)
53  {
54  case WORLD:
55  if (type == CONTACT_3D)
56  classicAcceleration(ov, oa, res.linear());
57  else
58  res.linear() = oa.linear();
59  res.angular() = oa.angular();
60  break;
62  if (type == CONTACT_3D)
63  res.linear() = oMc.rotation() * classicAcceleration(data.v[joint_id], data.a[joint_id], iMc);
64  else
65  res.linear() = oMc.rotation() * (iMc.actInv(data.a[joint_id])).linear();
66  res.angular() = oMi.rotation() * data.a[joint_id].angular();
67  break;
68  case LOCAL:
69  if (type == CONTACT_3D)
70  classicAcceleration(data.v[joint_id], data.a[joint_id], iMc, res.linear());
71  else
72  res.linear() = (iMc.actInv(data.a[joint_id])).linear();
73  res.angular() = iMc.rotation().transpose() * data.a[joint_id].angular();
74  break;
75  default:
76  break;
77  }
78 
79  return res;
80 }
81 
82 BOOST_AUTO_TEST_CASE(test_contact_inverse_dynamics_3D)
83 {
84  using namespace Eigen;
85  using namespace pinocchio;
86 
89  pinocchio::Data data(model), data_ref(model);
90 
91  model.lowerPositionLimit.head<3>().fill(-1.);
92  model.upperPositionLimit.head<3>().fill(1.);
93  VectorXd q = randomConfiguration(model);
94 
95  VectorXd v = VectorXd::Random(model.nv);
96  VectorXd tau = VectorXd::Random(model.nv);
97 
98  const std::string RF = "rleg6_joint";
99  // const Model::JointIndex RF_id = model.getJointId(RF);
100  const std::string LF = "lleg6_joint";
101  // const Model::JointIndex LF_id = model.getJointId(LF);
102 
103  // Contact models and data
105  RigidConstraintModelVector;
106  typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) RigidConstraintDataVector;
107  typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(CoulombFrictionCone) CoulombFrictionConeVector;
108 
109  RigidConstraintModelVector contact_models;
110  RigidConstraintDataVector contact_datas;
111  CoulombFrictionConeVector cones;
112  RigidConstraintModel ci_RF(CONTACT_3D, model, model.getJointId(RF), LOCAL);
113  contact_models.push_back(ci_RF);
114  contact_datas.push_back(RigidConstraintData(ci_RF));
115  cones.push_back(CoulombFrictionCone(0.4));
116  RigidConstraintModel ci_LF(CONTACT_3D, model, model.getJointId(LF), LOCAL);
117  contact_models.push_back(ci_LF);
118  contact_datas.push_back(RigidConstraintData(ci_LF));
119  cones.push_back(CoulombFrictionCone(0.4));
120 
121  RigidConstraintDataVector contact_datas_ref(contact_datas);
122 
123  Eigen::DenseIndex constraint_dim = 0;
124  for (size_t k = 0; k < contact_models.size(); ++k)
126 
127  Eigen::MatrixXd J_ref(constraint_dim, model.nv);
128  J_ref.setZero();
129 
130  double dt = 1e-3;
131  Eigen::VectorXd R = Eigen::VectorXd::Zero(constraint_dim);
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);
135  ProximalSettings prox_settings(1e-12, 1e-6, 1);
138  model, data_ref, q, v, a, dt, contact_models, contact_datas, cones, R, constraint_correction,
139  prox_settings, lambda_guess);
140  // constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas_ref,
141  // prox_settings_cd); forwardKinematics(model, data_ref, q, v, v*0);
142 
143  // Data::Matrix6x Jtmp = Data::Matrix6x::Zero(6,model.nv);
144  // getJointJacobian(model,data_ref,ci_RF.joint1_id,ci_RF.reference_frame,Jtmp);
145  // J_ref.middleRows<3>(0) = Jtmp.middleRows<3>(Motion::LINEAR);
146  // Jtmp.setZero(); getJointJacobian(model,data_ref,ci_LF.joint1_id,ci_LF.reference_frame,Jtmp);
147  // J_ref.middleRows<3>(3) = Jtmp.middleRows<3>(Motion::LINEAR);
148 
149  // Eigen::VectorXd gamma(constraint_dim);
150 
151  // gamma.segment<3>(0) =
152  // computeAcceleration(model,data_ref,ci_RF.joint1_id,ci_RF.reference_frame,ci_RF.type).linear();
153  // gamma.segment<3>(3) =
154  // computeAcceleration(model,data_ref,ci_LF.joint1_id,ci_LF.reference_frame,ci_LF.type).linear();
155 
156  // BOOST_CHECK((J_ref*data_ref.ddq + gamma).isZero());
157 
158  // Data data_constrained_dyn(model);
159 
160  // PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
161  // PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
162  // forwardDynamics(model,data_constrained_dyn,q,v,tau,J_ref,gamma,0.);
163  // PINOCCHIO_COMPILER_DIAGNOSTIC_POP
164 
165  // BOOST_CHECK((J_ref*data_constrained_dyn.ddq + gamma).isZero());
166 
167  // ProximalSettings prox_settings;
168  // prox_settings.max_iter = 10;
169  // prox_settings.mu = 1e8;
170  // contactABA(model, data, q, v, tau, contact_models, contact_datas, prox_settings);
171 
172  // BOOST_CHECK((J_ref*data.ddq + gamma).isZero());
173 
174  // // Call the algorithm a second time
175  // Data data2(model);
176  // ProximalSettings prox_settings2;
177  // contactABA(model, data2, q, v, tau, contact_models, contact_datas, prox_settings2);
178 
179  // BOOST_CHECK(prox_settings2.iter == 0);
180 }
181 
182 BOOST_AUTO_TEST_SUITE_END()
pinocchio::RigidConstraintData
RigidConstraintDataTpl< context::Scalar, context::Options > RigidConstraintData
Definition: algorithm/fwd.hpp:27
pinocchio::WORLD
@ WORLD
Definition: multibody/fwd.hpp:48
display-shapes-meshcat.placement
placement
Definition: display-shapes-meshcat.py:24
frames.hpp
common_symbols.type
type
Definition: common_symbols.py:35
Eigen
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio::CoulombFrictionConeTpl
&#160;
Definition: algorithm/constraints/coulomb-friction-cone.hpp:20
compute-all-terms.hpp
computeAcceleration
pinocchio::Motion computeAcceleration(const pinocchio::Model &model, pinocchio::Data &data, const pinocchio::JointIndex &joint_id, pinocchio::ReferenceFrame reference_frame, const pinocchio::ContactType type, const pinocchio::SE3 &placement=pinocchio::SE3::Identity())
Computes motions in the world frame.
Definition: contact-inverse-dynamics.cpp:33
pinocchio::ReferenceFrame
ReferenceFrame
Various conventions to express the velocity of a moving frame.
Definition: multibody/fwd.hpp:46
pinocchio::SE3Tpl
Definition: context/casadi.hpp:29
kinematics.hpp
pinocchio::contactInverseDynamics
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,...
Definition: contact-inverse-dynamics.hpp:190
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::classicAcceleration
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.
Definition: spatial/classic-acceleration.hpp:29
pinocchio::buildModels::humanoidRandom
void humanoidRandom(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true)
Create a humanoid kinematic tree with 6-DOF limbs and random joint placements.
pinocchio::res
ReturnType res
Definition: spatial/classic-acceleration.hpp:57
R
R
pinocchio::randomConfiguration
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.
Definition: joint-configuration.hpp:315
rnea.hpp
timer.hpp
aba.hpp
anymal-simulation.model
model
Definition: anymal-simulation.py:8
pinocchio::LOCAL_WORLD_ALIGNED
@ LOCAL_WORLD_ALIGNED
Definition: multibody/fwd.hpp:52
simulation-contact-dynamics.contact_datas
list contact_datas
Definition: simulation-contact-dynamics.py:60
forward-dynamics-derivatives.tau
tau
Definition: forward-dynamics-derivatives.py:25
joint-configuration.hpp
pinocchio::ProximalSettingsTpl
Structure containing all the settings parameters for the proximal algorithms.
Definition: algorithm/fwd.hpp:13
pinocchio::placement
const MotionDense< Motion2 > const SE3Tpl< SE3Scalar, SE3Options > & placement
Definition: spatial/classic-acceleration.hpp:122
pinocchio::RigidConstraintModelTpl
Definition: algorithm/constraints/fwd.hpp:14
pinocchio::RigidConstraintDataTpl
Definition: algorithm/constraints/fwd.hpp:16
cartpole.v
v
Definition: cartpole.py:153
pinocchio::initConstraintDynamics
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.
pinocchio::SE3Tpl::rotation
ConstAngularRef rotation() const
Definition: se3-base.hpp:48
size
FCL_REAL size() const
q
q
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(test_contact_inverse_dynamics_3D)
Definition: contact-inverse-dynamics.cpp:82
PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR
#define PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(T)
Definition: container/aligned-vector.hpp:13
a
Vec3f a
contact-inverse-dynamics.hpp
fill
fill
centroidal.hpp
pinocchio::MotionTpl::Zero
static MotionTpl Zero()
Definition: motion-tpl.hpp:136
pinocchio::ContactType
ContactType
&#160;
Definition: algorithm/contact-info.hpp:19
pinocchio::CoulombFrictionCone
CoulombFrictionConeTpl< context::Scalar > CoulombFrictionCone
Definition: algorithm/constraints/fwd.hpp:47
pinocchio::SE3Tpl::Identity
static SE3Tpl Identity()
Definition: spatial/se3-tpl.hpp:136
pinocchio::JointIndex
Index JointIndex
Definition: multibody/fwd.hpp:26
contact-cholesky.contact_models
list contact_models
Definition: contact-cholesky.py:22
contact-info.hpp
contact-dynamics.hpp
anymal-simulation.constraint_dim
constraint_dim
Definition: anymal-simulation.py:52
sample-models.hpp
pinocchio::MotionTpl
Definition: context/casadi.hpp:27
append-urdf-model-with-another-model.joint_id
joint_id
Definition: append-urdf-model-with-another-model.py:34
jacobian.hpp
pinocchio::ModelTpl
Definition: context/generic.hpp:20
constrained-dynamics.hpp
simulation-closed-kinematic-chains.prox_settings
prox_settings
Definition: simulation-closed-kinematic-chains.py:163
classic-acceleration.hpp
pinocchio::CONTACT_3D
@ CONTACT_3D
Definition: algorithm/contact-info.hpp:21
cartpole.dt
float dt
Definition: cartpole.py:145
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
PINOCCHIO_UNUSED_VARIABLE
#define PINOCCHIO_UNUSED_VARIABLE(var)
Helper to declare that a parameter is unused.
Definition: include/pinocchio/macros.hpp:72
pinocchio::LOCAL
@ LOCAL
Definition: multibody/fwd.hpp:50


pinocchio
Author(s):
autogenerated on Sun Dec 22 2024 03:41:08