casadi-aba.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 tau(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_tau = ::casadi::SX::sym("tau", model.nv);
50  TangentVectorAD tau_ad(model.nv);
51  tau_ad =
52  Eigen::Map<TangentVectorAD>(static_cast<std::vector<ADScalar>>(cs_tau).data(), model.nv, 1);
53 
54  // Build CasADi function
55  aba(ad_model, ad_data, q_ad, v_ad, tau_ad);
56  ::casadi::SX a_ad(model.nv, 1);
57 
58  for (Eigen::DenseIndex k = 0; k < model.nv; ++k)
59  a_ad(k) = ad_data.ddq[k];
60 
61  ::casadi::Function eval_aba(
62  "eval_aba", ::casadi::SXVector{cs_q, cs_v, cs_tau}, ::casadi::SXVector{a_ad});
63 
64  // Evaluate CasADi expression with real value
65  std::vector<double> q_vec((size_t)model.nq);
66  Eigen::Map<Eigen::VectorXd>(q_vec.data(), model.nq, 1) = q;
67 
68  std::vector<double> v_vec((size_t)model.nv);
69  Eigen::Map<Eigen::VectorXd>(v_vec.data(), model.nv, 1) = v;
70 
71  std::vector<double> tau_vec((size_t)model.nv);
72  Eigen::Map<Eigen::VectorXd>(tau_vec.data(), model.nv, 1) = tau;
73 
74  ::casadi::DM a_casadi_res = eval_aba(::casadi::DMVector{q_vec, v_vec, tau_vec})[0];
75  Data::TangentVectorType a_casadi_vec = Eigen::Map<Data::TangentVectorType>(
76  static_cast<std::vector<double>>(a_casadi_res).data(), model.nv, 1);
77 
78  // Eval ABA using classic Pinocchio model
80 
81  // Print both results
82  std::cout << "pinocchio double:\n" << "\ta = " << data.ddq.transpose() << std::endl;
83  std::cout << "pinocchio CasADi:\n" << "\ta = " << a_casadi_vec.transpose() << std::endl;
84 }
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::aba
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & aba(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 Convention convention=Convention::LOCAL)
The Articulated-Body algorithm. It computes the forward dynamics, aka the joint accelerations given t...
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
aba.hpp
forward-dynamics-derivatives.tau
tau
Definition: forward-dynamics-derivatives.py:25
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
pinocchio::v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Definition: joint-configuration.hpp:1118
main
int main(int, char **)
Definition: casadi-aba.cpp:8
fill
fill
casadi.hpp
sample-models.hpp
pinocchio::ModelTpl
Definition: context/generic.hpp:20
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:20