8 int main(
int ,
char ** )
13 typedef ::casadi::SX ADScalar;
24 model.lowerPositionLimit.head<3>().
fill(-1.);
25 model.upperPositionLimit.head<3>().
fill(1.);
29 Eigen::VectorXd
q(
model.nq);
31 Eigen::VectorXd
v(Eigen::VectorXd::Random(
model.nv));
32 Eigen::VectorXd
tau(Eigen::VectorXd::Random(
model.nv));
35 typedef ADModel::ConfigVectorType ConfigVectorAD;
36 typedef ADModel::TangentVectorType TangentVectorAD;
37 ADModel ad_model =
model.cast<ADScalar>();
38 ADData ad_data(ad_model);
42 ConfigVectorAD q_ad(
model.nq);
43 q_ad = Eigen::Map<ConfigVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_q).
data(),
model.nq, 1);
46 TangentVectorAD v_ad(
model.nv);
47 v_ad = Eigen::Map<TangentVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_v).
data(),
model.nv, 1);
50 TangentVectorAD tau_ad(
model.nv);
52 Eigen::Map<TangentVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_tau).
data(),
model.nv, 1);
55 aba(ad_model, ad_data, q_ad, v_ad, tau_ad);
56 ::casadi::SX a_ad(
model.nv, 1);
58 for (Eigen::DenseIndex k = 0; k <
model.nv; ++k)
59 a_ad(k) = ad_data.ddq[k];
61 ::casadi::Function eval_aba(
62 "eval_aba", ::casadi::SXVector{cs_q, cs_v, cs_tau}, ::casadi::SXVector{a_ad});
65 std::vector<double> q_vec((
size_t)
model.nq);
66 Eigen::Map<Eigen::VectorXd>(q_vec.data(),
model.nq, 1) =
q;
68 std::vector<double> v_vec((
size_t)
model.nv);
69 Eigen::Map<Eigen::VectorXd>(v_vec.data(),
model.nv, 1) =
v;
71 std::vector<double> tau_vec((
size_t)
model.nv);
72 Eigen::Map<Eigen::VectorXd>(tau_vec.data(),
model.nv, 1) =
tau;
74 ::casadi::DM a_casadi_res = eval_aba(::casadi::DMVector{q_vec, v_vec, tau_vec})[0];
76 static_cast<std::vector<double>
>(a_casadi_res).
data(),
model.nv, 1);
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;