casadi-rnea.cpp
Go to the documentation of this file.
2 
4 
7 
8 int main(int /*argc*/, char ** /*argv*/)
9 {
10  using namespace pinocchio;
11 
12  typedef double Scalar;
13  typedef ::casadi::SX ADScalar;
14 
15  typedef ModelTpl<Scalar> Model;
16  typedef Model::Data Data;
17 
18  typedef ModelTpl<ADScalar> ADModel;
19  typedef ADModel::Data ADData;
20 
21  // Create a random humanoid model
22  Model model;
24  model.lowerPositionLimit.head<3>().fill(-1.);
25  model.upperPositionLimit.head<3>().fill(1.);
26  Data data(model);
27 
28  // Pick up random configuration, velocity and acceleration vectors.
29  Eigen::VectorXd q(model.nq);
31  Eigen::VectorXd v(Eigen::VectorXd::Random(model.nv));
32  Eigen::VectorXd a(Eigen::VectorXd::Random(model.nv));
33 
34  // Create CasADi model and data from model
35  typedef ADModel::ConfigVectorType ConfigVectorAD;
36  typedef ADModel::TangentVectorType TangentVectorAD;
37  ADModel ad_model = model.cast<ADScalar>();
38  ADData ad_data(ad_model);
39 
40  // Create symbolic CasADi vectors
41  ::casadi::SX cs_q = ::casadi::SX::sym("q", model.nq);
42  ConfigVectorAD q_ad(model.nq);
43  q_ad = Eigen::Map<ConfigVectorAD>(static_cast<std::vector<ADScalar>>(cs_q).data(), model.nq, 1);
44 
45  ::casadi::SX cs_v = ::casadi::SX::sym("v", model.nv);
46  TangentVectorAD v_ad(model.nv);
47  v_ad = Eigen::Map<TangentVectorAD>(static_cast<std::vector<ADScalar>>(cs_v).data(), model.nv, 1);
48 
49  ::casadi::SX cs_a = ::casadi::SX::sym("a", model.nv);
50  TangentVectorAD a_ad(model.nv);
51  a_ad = Eigen::Map<TangentVectorAD>(static_cast<std::vector<ADScalar>>(cs_a).data(), model.nv, 1);
52 
53  // Build CasADi function
54  rnea(ad_model, ad_data, q_ad, v_ad, a_ad);
55  ::casadi::SX tau_ad(model.nv, 1);
56 
57  for (Eigen::DenseIndex k = 0; k < model.nv; ++k)
58  tau_ad(k) = ad_data.tau[k];
59 
60  ::casadi::Function eval_rnea(
61  "eval_rnea", ::casadi::SXVector{cs_q, cs_v, cs_a}, ::casadi::SXVector{tau_ad});
62 
63  // Evaluate CasADi expression with real value
64  std::vector<double> q_vec((size_t)model.nq);
65  Eigen::Map<Eigen::VectorXd>(q_vec.data(), model.nq, 1) = q;
66 
67  std::vector<double> v_vec((size_t)model.nv);
68  Eigen::Map<Eigen::VectorXd>(v_vec.data(), model.nv, 1) = v;
69 
70  std::vector<double> a_vec((size_t)model.nv);
71  Eigen::Map<Eigen::VectorXd>(a_vec.data(), model.nv, 1) = a;
72 
73  ::casadi::DM tau_casadi_res = eval_rnea(::casadi::DMVector{q_vec, v_vec, a_vec})[0];
74  Data::TangentVectorType tau_casadi_vec = Eigen::Map<Data::TangentVectorType>(
75  static_cast<std::vector<double>>(tau_casadi_res).data(), model.nv, 1);
76 
77  // Eval RNEA using classic Pinocchio model
79 
80  // Print both results
81  std::cout << "pinocchio double:\n" << "\ttau = " << data.tau.transpose() << std::endl;
82  std::cout << "pinocchio CasADi:\n" << "\ttau = " << tau_casadi_vec.transpose() << std::endl;
83 }
pinocchio::DataTpl::TangentVectorType
VectorXs TangentVectorType
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc)....
Definition: multibody/data.hpp:89
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio.casadi::sym
void sym(const Eigen::MatrixBase< MatrixDerived > &eig_mat, std::string const &name)
Definition: autodiff/casadi.hpp:230
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp: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::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:325
rnea.hpp
joint-configuration.hpp
pinocchio::python::context::Data
DataTpl< Scalar, Options > Data
Definition: bindings/python/context/generic.hpp:62
pinocchio::Data
DataTpl< context::Scalar, context::Options > Data
Definition: multibody/fwd.hpp:34
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1117
a
Vec3f a
pinocchio::v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Definition: joint-configuration.hpp:1118
fill
fill
pinocchio::rnea
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...
casadi.hpp
sample-models.hpp
pinocchio::ModelTpl
Definition: context/generic.hpp:20
main
int main(int, char **)
Definition: casadi-rnea.cpp:8
pinocchio::Model
ModelTpl< context::Scalar, context::Options > Model
Definition: multibody/fwd.hpp:33
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Wed Sep 25 2024 02:42:21