|
| 1 | +#include "pinocchio/autodiff/casadi.hpp" |
| 2 | + |
| 3 | +#include "pinocchio/multibody/sample-models.hpp" |
| 4 | + |
| 5 | +#include "pinocchio/algorithm/crba.hpp" |
| 6 | +#include "pinocchio/algorithm/joint-configuration.hpp" |
| 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; |
| 23 | + buildModels::humanoidRandom(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); |
| 30 | + q = randomConfiguration(model); |
| 31 | + |
| 32 | + // Create CasADi model and data from model |
| 33 | + typedef ADModel::ConfigVectorType ConfigVectorAD; |
| 34 | + ADModel ad_model = model.cast<ADScalar>(); |
| 35 | + ADData ad_data(ad_model); |
| 36 | + |
| 37 | + // Create symbolic CasADi vectors |
| 38 | + ::casadi::SX cs_q = ::casadi::SX::sym("q", model.nq); |
| 39 | + ConfigVectorAD q_ad(model.nq); |
| 40 | + q_ad = Eigen::Map<ConfigVectorAD>(static_cast<std::vector<ADScalar>>(cs_q).data(), model.nq, 1); |
| 41 | + |
| 42 | + // Build CasADi function |
| 43 | + crba(ad_model, ad_data, q_ad, pinocchio::Convention::WORLD); |
| 44 | + ad_data.M.triangularView<Eigen::StrictlyLower>() = |
| 45 | + ad_data.M.transpose().triangularView<Eigen::StrictlyLower>(); |
| 46 | + ::casadi::SX M_ad(model.nv, model.nv); |
| 47 | + for (Eigen::DenseIndex j = 0; j < model.nv; ++j) |
| 48 | + { |
| 49 | + for (Eigen::DenseIndex i = 0; i < model.nv; ++i) |
| 50 | + { |
| 51 | + M_ad(i, j) = ad_data.M(i, j); |
| 52 | + } |
| 53 | + } |
| 54 | + |
| 55 | + ::casadi::Function eval_crba("eval_crba", ::casadi::SXVector{cs_q}, ::casadi::SXVector{M_ad}); |
| 56 | + |
| 57 | + // Evaluate CasADi expression with real value |
| 58 | + std::vector<double> q_vec((size_t)model.nq); |
| 59 | + Eigen::Map<Eigen::VectorXd>(q_vec.data(), model.nq, 1) = q; |
| 60 | + |
| 61 | + ::casadi::DM M_res = eval_crba(::casadi::DMVector{q_vec})[0]; |
| 62 | + Data::MatrixXs M_mat = |
| 63 | + Eigen::Map<Data::MatrixXs>(static_cast<std::vector<double>>(M_res).data(), model.nv, model.nv); |
| 64 | + |
| 65 | + // Eval CRBA using classic Pinocchio model |
| 66 | + pinocchio::crba(model, data, q); |
| 67 | + data.M.triangularView<Eigen::StrictlyLower>() = |
| 68 | + data.M.transpose().triangularView<Eigen::StrictlyLower>(); |
| 69 | + |
| 70 | + // Print both results |
| 71 | + std::cout << "pinocchio double:\n" << "\tM =\n" << data.M << std::endl; |
| 72 | + std::cout << "pinocchio CasADi:\n" << "\tM =\n" << M_mat.transpose() << std::endl; |
| 73 | +} |
0 commit comments