21 #include <boost/test/unit_test.hpp> 
   22 #include <boost/utility/binary.hpp> 
   26 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
 
   41   model.lowerPositionLimit.head<3>().
fill(-1.);
 
   42   model.upperPositionLimit.head<3>().
fill(1.);
 
   49   TangentVector 
v(TangentVector::Random(
model.nv));
 
   59   jacobian_local.setZero();
 
   60   jacobian_world.setZero();
 
   62   BOOST_CHECK(jacobian_local.isZero() && jacobian_world.isZero());
 
   69   ConfigVectorAD q_ad(
model.nq);
 
   70   for (Eigen::DenseIndex k = 0; k < 
model.nq; ++k)
 
   74   std::cout << 
"q =\n " << q_ad << std::endl;
 
   77   TangentVectorAD v_ad(
model.nv);
 
   78   for (Eigen::DenseIndex k = 0; k < 
model.nv; ++k)
 
   82   std::cout << 
"v =\n " << v_ad << std::endl;
 
   86   MotionAD & v_local = ad_data.v[(size_t)
joint_id];
 
   87   MotionAD v_world = ad_data.oMi[(size_t)
joint_id].
act(v_local);
 
   89   casadi::SX cs_v_local(6, 1), cs_v_world(6, 1);
 
   90   for (Eigen::DenseIndex k = 0; k < 6; ++k)
 
   92     cs_v_local(k) = v_local.toVector()[k];
 
   93     cs_v_world(k) = v_world.toVector()[k];
 
   95   std::cout << 
"v_local = " << cs_v_local << std::endl;
 
   96   std::cout << 
"v_world = " << cs_v_world << std::endl;
 
   98   casadi::Function eval_velocity_local(
 
   99     "eval_velocity_local", casadi::SXVector{cs_q, cs_v}, casadi::SXVector{cs_v_local});
 
  100   std::cout << 
"eval_velocity_local = " << eval_velocity_local << std::endl;
 
  102   casadi::Function eval_velocity_world(
 
  103     "eval_velocity_world", casadi::SXVector{cs_q, cs_v}, casadi::SXVector{cs_v_world});
 
  104   std::cout << 
"eval_velocity_world = " << eval_velocity_world << std::endl;
 
  107   casadi::Function eval_jacobian_local(
 
  108     "eval_jacobian_local", casadi::SXVector{cs_q, cs_v}, casadi::SXVector{
dv_dv_local});
 
  109   std::cout << 
"eval_jacobian_local = " << eval_jacobian_local << std::endl;
 
  111   casadi::SX dv_dv_world = 
jacobian(cs_v_world, cs_v);
 
  112   casadi::Function eval_jacobian_world(
 
  113     "eval_jacobian_world", casadi::SXVector{cs_q, cs_v}, casadi::SXVector{dv_dv_world});
 
  115   std::vector<double> q_vec((
size_t)
model.nq);
 
  116   Eigen::Map<ConfigVector>(q_vec.data(), 
model.nq, 1) = 
q;
 
  118   std::vector<double> v_vec((
size_t)
model.nv);
 
  119   Eigen::Map<TangentVector>(v_vec.data(), 
model.nv, 1) = 
v;
 
  121   casadi::DMVector v_local_res = eval_velocity_local(casadi::DMVector{q_vec, v_vec});
 
  122   casadi::DMVector J_local_res = eval_jacobian_local(casadi::DMVector{q_vec, v_vec});
 
  123   std::cout << 
"J_local_res:" << J_local_res << std::endl;
 
  125   std::vector<double> v_local_vec(
static_cast<std::vector<double>
>(v_local_res[0]));
 
  127     (jacobian_local * 
v).
isApprox(Eigen::Map<pinocchio::Motion::Vector6>(v_local_vec.data())));
 
  129   casadi::DMVector v_world_res = eval_velocity_world(casadi::DMVector{q_vec, v_vec});
 
  130   casadi::DMVector J_world_res = eval_jacobian_world(casadi::DMVector{q_vec, v_vec});
 
  132   std::vector<double> v_world_vec(
static_cast<std::vector<double>
>(v_world_res[0]));
 
  134     (jacobian_world * 
v).
isApprox(Eigen::Map<pinocchio::Motion::Vector6>(v_world_vec.data())));
 
  138   std::vector<double> J_local_vec(
static_cast<std::vector<double>
>(J_local_res[0]));
 
  139   J_local_mat = Eigen::Map<Data::Matrix6x>(J_local_vec.data(), 6, 
model.nv);
 
  140   BOOST_CHECK(jacobian_local.isApprox(J_local_mat));
 
  142   std::vector<double> J_world_vec(
static_cast<std::vector<double>
>(J_world_res[0]));
 
  143   J_world_mat = Eigen::Map<Data::Matrix6x>(J_world_vec.data(), 6, 
model.nv);
 
  144   BOOST_CHECK(jacobian_world.isApprox(J_world_mat));
 
  160   model.lowerPositionLimit.head<3>().
fill(-1.);
 
  161   model.upperPositionLimit.head<3>().
fill(1.);
 
  168   TangentVector 
v(TangentVector::Random(
model.nv));
 
  169   TangentVector 
a(TangentVector::Random(
model.nv));
 
  179   ConfigVectorAD q_ad(
model.nq);
 
  183   TangentVectorAD v_ad(
model.nv);
 
  187   TangentVectorAD a_ad(
model.nv);
 
  209   model.lowerPositionLimit.head<3>().
fill(-1.);
 
  210   model.upperPositionLimit.head<3>().
fill(1.);
 
  217   TangentVector 
v(TangentVector::Random(
model.nv));
 
  218   TangentVector 
a(TangentVector::Random(
model.nv));
 
  228   ConfigVectorAD q_ad(
model.nq);
 
  229   q_ad = Eigen::Map<ConfigVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_q).
data(), 
model.nq, 1);
 
  232   TangentVectorAD v_ad(
model.nv);
 
  233   v_ad = Eigen::Map<TangentVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_v).
data(), 
model.nv, 1);
 
  236   TangentVectorAD a_ad(
model.nv);
 
  237   a_ad = Eigen::Map<TangentVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_a).
data(), 
model.nv, 1);
 
  239   rnea(ad_model, ad_data, q_ad, v_ad, a_ad);
 
  240   casadi::SX tau_ad(
model.nv, 1);
 
  243   for (Eigen::DenseIndex k = 0; k < 
model.nv; ++k)
 
  244     tau_ad(k) = ad_data.tau[k];
 
  245   casadi::Function eval_rnea(
 
  246     "eval_rnea", casadi::SXVector{cs_q, cs_v, cs_a}, casadi::SXVector{tau_ad});
 
  248   std::vector<double> q_vec((
size_t)
model.nq);
 
  249   Eigen::Map<ConfigVector>(q_vec.data(), 
model.nq, 1) = 
q;
 
  251   std::vector<double> v_vec((
size_t)
model.nv);
 
  252   Eigen::Map<TangentVector>(v_vec.data(), 
model.nv, 1) = 
v;
 
  254   std::vector<double> a_vec((
size_t)
model.nv);
 
  255   Eigen::Map<TangentVector>(a_vec.data(), 
model.nv, 1) = 
a;
 
  256   casadi::DM tau_res = eval_rnea(casadi::DMVector{q_vec, v_vec, a_vec})[0];
 
  257   std::cout << 
"tau_res = " << tau_res << std::endl;
 
  259     static_cast<std::vector<double>
>(tau_res).
data(), 
model.nv, 1);
 
  261   BOOST_CHECK(
data.tau.isApprox(tau_vec));
 
  277   model.lowerPositionLimit.head<3>().
fill(-1.);
 
  278   model.upperPositionLimit.head<3>().
fill(1.);
 
  285   TangentVector 
v(TangentVector::Random(
model.nv));
 
  286   TangentVector 
a(TangentVector::Random(
model.nv));
 
  294   data.M.triangularView<Eigen::StrictlyLower>() =
 
  295     data.M.transpose().triangularView<Eigen::StrictlyLower>();
 
  299   ConfigVectorAD q_ad(
model.nq);
 
  300   q_ad = Eigen::Map<ConfigVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_q).
data(), 
model.nq, 1);
 
  303   TangentVectorAD v_ad(
model.nv);
 
  304   v_ad = Eigen::Map<TangentVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_v).
data(), 
model.nv, 1);
 
  307   TangentVectorAD a_ad(
model.nv);
 
  308   a_ad = Eigen::Map<TangentVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_a).
data(), 
model.nv, 1);
 
  311   rnea(ad_model, ad_data, q_ad, v_ad, a_ad);
 
  312   casadi::SX cs_tau(
model.nv, 1);
 
  315   for (Eigen::DenseIndex k = 0; k < 
model.nv; ++k)
 
  316     cs_tau(k) = ad_data.tau[k];
 
  317   casadi::Function eval_rnea(
 
  318     "eval_rnea", casadi::SXVector{cs_q, cs_v, cs_a}, casadi::SXVector{cs_tau});
 
  321   ad_data.M.triangularView<Eigen::StrictlyLower>() =
 
  322     ad_data.M.transpose().triangularView<Eigen::StrictlyLower>();
 
  324   for (Eigen::DenseIndex j = 0; j < 
model.nv; ++j)
 
  326     for (Eigen::DenseIndex 
i = 0; 
i < 
model.nv; ++
i)
 
  328       M_ad(
i, j) = ad_data.M(
i, j);
 
  332   std::vector<double> q_vec((
size_t)
model.nq);
 
  333   Eigen::Map<ConfigVector>(q_vec.data(), 
model.nq, 1) = 
q;
 
  335   std::vector<double> v_vec((
size_t)
model.nv);
 
  336   Eigen::Map<TangentVector>(v_vec.data(), 
model.nv, 1) = 
v;
 
  338   std::vector<double> a_vec((
size_t)
model.nv);
 
  339   Eigen::Map<TangentVector>(a_vec.data(), 
model.nv, 1) = 
a;
 
  341   casadi::Function eval_crba(
"eval_crba", casadi::SXVector{cs_q}, casadi::SXVector{M_ad});
 
  342   casadi::DM M_res = eval_crba(casadi::DMVector{q_vec})[0];
 
  344     Eigen::Map<Data::MatrixXs>(
static_cast<std::vector<double>
>(M_res).
data(), 
model.nv, 
model.nv);
 
  346   BOOST_CHECK(
data.M.isApprox(M_mat));
 
  349   casadi::Function eval_dtau_da(
 
  350     "eval_dtau_da", casadi::SXVector{cs_q, cs_v, cs_a}, casadi::SXVector{
dtau_da});
 
  351   casadi::DM dtau_da_res = eval_dtau_da(casadi::DMVector{q_vec, v_vec, a_vec})[0];
 
  353     static_cast<std::vector<double>
>(dtau_da_res).
data(), 
model.nv, 
model.nv);
 
  354   BOOST_CHECK(
data.M.isApprox(dtau_da_mat));
 
  370   model.lowerPositionLimit.head<3>().
fill(-1.);
 
  371   model.upperPositionLimit.head<3>().
fill(1.);
 
  378   TangentVector 
v(TangentVector::Random(
model.nv));
 
  379   TangentVector 
tau(TangentVector::Random(
model.nv));
 
  389   ConfigVectorAD q_ad(
model.nq);
 
  390   q_ad = Eigen::Map<ConfigVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_q).
data(), 
model.nq, 1);
 
  393   TangentVectorAD v_ad(
model.nv);
 
  394   v_ad = Eigen::Map<TangentVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_v).
data(), 
model.nv, 1);
 
  397   TangentVectorAD tau_ad(
model.nv);
 
  399     Eigen::Map<TangentVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_tau).
data(), 
model.nv, 1);
 
  403   casadi::SX cs_ddq(
model.nv, 1);
 
  404   for (Eigen::DenseIndex k = 0; k < 
model.nv; ++k)
 
  405     cs_ddq(k) = ad_data.ddq[k];
 
  406   casadi::Function eval_aba(
 
  407     "eval_aba", casadi::SXVector{cs_q, cs_v, cs_tau}, casadi::SXVector{cs_ddq});
 
  409   std::vector<double> q_vec((
size_t)
model.nq);
 
  410   Eigen::Map<ConfigVector>(q_vec.data(), 
model.nq, 1) = 
q;
 
  412   std::vector<double> v_vec((
size_t)
model.nv);
 
  413   Eigen::Map<TangentVector>(v_vec.data(), 
model.nv, 1) = 
v;
 
  415   std::vector<double> tau_vec((
size_t)
model.nv);
 
  416   Eigen::Map<TangentVector>(tau_vec.data(), 
model.nv, 1) = 
tau;
 
  418   casadi::DM ddq_res = eval_aba(casadi::DMVector{q_vec, v_vec, tau_vec})[0];
 
  420     static_cast<std::vector<double>
>(ddq_res).
data(), 
model.nv, 1);
 
  422   BOOST_CHECK(ddq_mat.isApprox(
data.ddq));
 
  427   using casadi::DMVector;
 
  429   using casadi::SXVector;
 
  443   SX zero_vec(SX::zeros(2 * 
nv));
 
  448   cConfig_t cq0(
nq), cq1(
nq);
 
  449   cTangent_t cdq0(
nv), cdq1(
nv);
 
  454   ADScalar cs_dqall = vertcat(cs_dq0, cs_dq1);
 
  465   auto norm_interp = log_interp.dot(log_interp);
 
  466   auto Jnorm_interp = 
jacobian(norm_interp, cs_dqall);
 
  468   casadi::Function Jnorm_eval(
 
  469     "Jnorm", SXVector{cs_q0, cs_q1}, SXVector{substitute(Jnorm_interp, cs_dqall, zero_vec)});
 
  470   std::cout << Jnorm_eval << 
'\n';
 
  476   typedef Eigen::Map<Model::ConfigVectorType> ConfigMap_t;
 
  477   std::vector<double> q0_vec((
size_t)
nq);
 
  478   std::vector<double> q1_vec((
size_t)
nq);
 
  479   std::vector<double> q2_vec((
size_t)
nq);
 
  480   ConfigMap_t(q0_vec.data(), 
nq, 1) = 
q0;
 
  481   ConfigMap_t(q1_vec.data(), 
nq, 1) = 
q1;
 
  482   ConfigMap_t(q2_vec.data(), 
nq, 1) = 
q2;
 
  484   std::cout << Jnorm_eval(DMVector{q0_vec, q0_vec})[0] << 
'\n';
 
  485   std::cout << Jnorm_eval(DMVector{q0_vec, q1_vec})[0] << 
'\n';
 
  486   std::cout << Jnorm_eval(DMVector{q1_vec, q1_vec})[0] << 
'\n';
 
  487   std::cout << Jnorm_eval(DMVector{q2_vec, q2_vec})[0] << 
'\n';
 
  495   model.lowerPositionLimit.head<3>().
fill(-1.);
 
  496   model.upperPositionLimit.head<3>().
fill(1.);
 
  504   model2.lowerPositionLimit.tail<1>().
fill(-4.);
 
  512   using casadi::DMVector;
 
  514   using casadi::SXVector;
 
  523   model.appendBodyToJoint(1, pinocchio::Inertia::Identity());
 
  525   model.lowerPositionLimit.head<3>().
fill(-1.);
 
  526   model.upperPositionLimit.head<3>().
fill(1.);
 
  537   SX zero_vec(SX::zeros(2 * 
nv));
 
  542   cConfig_t cq0(
nq), cq1(
nq);
 
  543   cTangent_t cdq0(
nv), cdq1(
nv);
 
  548   ADScalar cs_dqall = vertcat(cs_dq0, cs_dq1);
 
  553   const double dt(0.05);
 
  557   const auto KE_expr = ad_data.kinetic_energy;
 
  558   const auto gKE_expr = 
jacobian(KE_expr, cs_dqall);
 
  559   const auto HKE_expr = 
jacobian(gKE_expr, cs_dqall);
 
  561   casadi::Function KE_eval(
 
  562     "KE", SXVector{cs_q0, cs_q1}, SXVector{substitute(KE_expr, cs_dqall, zero_vec)});
 
  563   casadi::Function gKE_eval(
 
  564     "gKE", SXVector{cs_q0, cs_q1}, SXVector{substitute(gKE_expr, cs_dqall, zero_vec)});
 
  565   casadi::Function HKE_eval(
 
  566     "HKE", SXVector{cs_q0, cs_q1}, SXVector{substitute(HKE_expr, cs_dqall, zero_vec)});
 
  567   std::cout << HKE_eval << std::endl;
 
  579   const static double eps = 1e-8;
 
  581   auto fd_grad_lambda =
 
  588       Eigen::VectorXd jac_fd(2 * 
nv);
 
  591       for (
int i = 0; 
i < 
nv; 
i++)
 
  600         casadi::DM diff1 = (dp1 - dm) / 
eps;
 
  605         casadi::DM diff2 = (dp2 - dm) / 
eps;
 
  607         jac_fd[
i] = 
static_cast<double>(diff1);
 
  608         jac_fd[
i + 
nv] = 
static_cast<double>(diff2);
 
  616   std::cout << 
"eval: {q0d,q0d}: " << KE_eval(DMVector{q0d, q0d}) << std::endl;
 
  617   std::cout << 
"grad: {q0d,q0d}: " << gKE_eval(DMVector{q0d, q0d}) << std::endl;
 
  618   std::cout << 
"FD grad: {q0d,q0d}:" << fd_grad_lambda(
q0, 
q0).transpose() << std::endl;
 
  619   std::cout << 
"---" << std::endl;
 
  621   std::cout << 
"eval: {q1d,q1d}: " << KE_eval(DMVector{q1d, q1d}) << std::endl;
 
  622   std::cout << 
"grad: {q1d,q1d}: " << gKE_eval(DMVector{q1d, q1d}) << std::endl;
 
  623   std::cout << 
"FD grad: {q1d,q1d}:" << fd_grad_lambda(
q1, 
q1).transpose() << std::endl;
 
  624   std::cout << 
"---" << std::endl;
 
  626   std::cout << 
"eval: {q1d,q2d}: " << KE_eval(DMVector{q1d, q2d}) << std::endl;
 
  627   std::cout << 
"grad: {q1d,q2d}: " << gKE_eval(DMVector{q1d, q2d}) << std::endl;
 
  628   std::cout << 
"FD grad: {q1d,q2d}:" << fd_grad_lambda(
q1, 
q2).transpose() << std::endl;
 
  629   std::cout << 
"---" << std::endl;
 
  631   std::cout << 
"eval: {q2d,q2d}: " << KE_eval(DMVector{q2d, q2d}) << std::endl;
 
  632   std::cout << 
"grad: {q2d,q2d}: " << gKE_eval(DMVector{q2d, q2d}) << std::endl;
 
  633   std::cout << 
"FD grad: {q2d,q2d}:" << fd_grad_lambda(
q2, 
q2).transpose() << std::endl;
 
  634   std::cout << 
"---" << std::endl;
 
  644       Eigen::MatrixXd jac_fd(2 * 
nv, 2 * 
nv);
 
  645       for (
int i = 0; 
i < 
nv; 
i++)
 
  653         auto diff1 = (dp[0] - dm[0]) / 
eps;
 
  657         auto diff2 = (dp[0] - dm[0]) / 
eps;
 
  659         for (
int j = 0; j < jac_fd.rows(); j++)
 
  661           jac_fd(j, 
i) = 
static_cast<double>(diff1(j));
 
  662           jac_fd(j, 
i + 
nv) = 
static_cast<double>(diff2(j));
 
  671   std::cout << HKE_eval(DMVector{q0d, q0d})[0] << 
'\n';
 
  672   auto jac_fd = fd_hess_ambda(
q0, 
q0);
 
  673   std::cout << jac_fd << 
'\n';
 
  675   std::cout << HKE_eval(DMVector{q1d, q2d})[0] << 
'\n';
 
  676   jac_fd = fd_hess_ambda(
q1, 
q2);
 
  677   std::cout << jac_fd << 
'\n';
 
  679   std::cout << HKE_eval(DMVector{q0d, q2d})[0] << 
'\n';
 
  680   jac_fd = fd_hess_ambda(
q0, 
q2);
 
  681   std::cout << jac_fd << 
'\n';
 
  683   std::cout << HKE_eval(DMVector{q2d, q2d})[0] << 
'\n';
 
  684   jac_fd = fd_hess_ambda(
q2, 
q2);
 
  685   std::cout << jac_fd << 
'\n';
 
  688 BOOST_AUTO_TEST_SUITE_END()