16 #include <casadi/casadi.hpp>
19 #include <boost/test/unit_test.hpp>
20 #include <boost/utility/binary.hpp>
22 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
27 typedef casadi::SX ADScalar;
37 model.lowerPositionLimit.head<3>().
fill(-1.);
38 model.upperPositionLimit.head<3>().
fill(1.);
41 typedef Model::ConfigVectorType ConfigVector;
42 typedef Model::TangentVectorType TangentVector;
45 TangentVector
v(TangentVector::Random(
model.nv));
46 TangentVector
a(TangentVector::Random(
model.nv));
48 typedef ADModel::ConfigVectorType ConfigVectorAD;
49 typedef ADModel::TangentVectorType TangentVectorAD;
50 ADModel ad_model =
model.cast<ADScalar>();
51 ADData ad_data(ad_model);
59 q_ad = Eigen::Map<ConfigVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_q).
data(),
model.nq, 1);
61 Eigen::Map<ConfigVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_v_int).
data(),
model.nv, 1);
64 casadi::SX cs_q_int(
model.nq, 1);
66 std::vector<double> q_vec((
size_t)
model.nq);
67 Eigen::Map<ConfigVector>(q_vec.data(),
model.nq, 1) =
q;
69 std::vector<double> v_int_vec((
size_t)
model.nv);
70 Eigen::Map<TangentVector>(v_int_vec.data(),
model.nv, 1).setZero();
73 TangentVectorAD v_ad(
model.nv);
74 v_ad = Eigen::Map<TangentVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_v).
data(),
model.nv, 1);
77 TangentVectorAD a_ad(
model.nv);
78 a_ad = Eigen::Map<TangentVectorAD>(
static_cast<std::vector<ADScalar>
>(cs_a).
data(),
model.nv, 1);
80 rnea(ad_model, ad_data, q_int_ad, v_ad, a_ad);
81 casadi::SX cs_tau(
model.nv, 1);
82 for (Eigen::DenseIndex k = 0; k <
model.nv; ++k)
84 cs_tau(k) = ad_data.tau[k];
86 casadi::Function eval_rnea(
87 "eval_rnea", casadi::SXVector{cs_q, cs_v_int, cs_v, cs_a}, casadi::SXVector{cs_tau});
89 std::vector<double> v_vec((
size_t)
model.nv);
90 Eigen::Map<TangentVector>(v_vec.data(),
model.nv, 1) =
v;
92 std::vector<double> a_vec((
size_t)
model.nv);
93 Eigen::Map<TangentVector>(a_vec.data(),
model.nv, 1) =
a;
96 casadi::DM tau_res = eval_rnea(casadi::DMVector{q_vec, v_int_vec, v_vec, a_vec})[0];
97 Data::TangentVectorType tau_vec = Eigen::Map<Data::TangentVectorType>(
98 static_cast<std::vector<double>
>(tau_res).
data(),
model.nv, 1);
100 BOOST_CHECK(
data.tau.isApprox(tau_vec));
105 dtau_dq_ref.setZero();
106 dtau_dv_ref.setZero();
107 dtau_da_ref.setZero();
110 dtau_da_ref.triangularView<Eigen::StrictlyLower>() =
111 dtau_da_ref.transpose().triangularView<Eigen::StrictlyLower>();
115 casadi::Function eval_dtau_dq(
116 "eval_dtau_dq", casadi::SXVector{cs_q, cs_v_int, cs_v, cs_a}, casadi::SXVector{
dtau_dq});
118 casadi::DM dtau_dq_res = eval_dtau_dq(casadi::DMVector{q_vec, v_int_vec, v_vec, a_vec})[0];
119 std::vector<double> dtau_dq_vec(
static_cast<std::vector<double>
>(dtau_dq_res));
121 Eigen::Map<Data::MatrixXs>(dtau_dq_vec.data(),
model.nv,
model.nv).isApprox(dtau_dq_ref));
125 casadi::Function eval_dtau_dv(
126 "eval_dtau_dv", casadi::SXVector{cs_q, cs_v_int, cs_v, cs_a}, casadi::SXVector{
dtau_dv});
128 casadi::DM dtau_dv_res = eval_dtau_dv(casadi::DMVector{q_vec, v_int_vec, v_vec, a_vec})[0];
129 std::vector<double> dtau_dv_vec(
static_cast<std::vector<double>
>(dtau_dv_res));
131 Eigen::Map<Data::MatrixXs>(dtau_dv_vec.data(),
model.nv,
model.nv).isApprox(dtau_dv_ref));
135 casadi::Function eval_dtau_da(
136 "eval_dtau_da", casadi::SXVector{cs_q, cs_v_int, cs_v, cs_a}, casadi::SXVector{
dtau_da});
138 casadi::DM dtau_da_res = eval_dtau_da(casadi::DMVector{q_vec, v_int_vec, v_vec, a_vec})[0];
139 std::vector<double> dtau_da_vec(
static_cast<std::vector<double>
>(dtau_da_res));
141 Eigen::Map<Data::MatrixXs>(dtau_da_vec.data(),
model.nv,
model.nv).isApprox(dtau_da_ref));
149 ad_data.M.triangularView<Eigen::StrictlyLower>() =
150 ad_data.M.transpose().triangularView<Eigen::StrictlyLower>();
156 casadi::Function eval_rnea_derivatives_dq(
157 "eval_rnea_derivatives_dq", casadi::SXVector{cs_q, cs_v, cs_a}, casadi::SXVector{cs_dtau_dq});
159 casadi::DM dtau_dq_res_direct =
160 eval_rnea_derivatives_dq(casadi::DMVector{q_vec, v_vec, a_vec})[0];
161 Data::MatrixXs dtau_dq_res_direct_map = Eigen::Map<Data::MatrixXs>(
162 static_cast<std::vector<double>
>(dtau_dq_res_direct).
data(),
model.nv,
model.nv);
163 BOOST_CHECK(dtau_dq_ref.isApprox(dtau_dq_res_direct_map));
165 casadi::Function eval_rnea_derivatives_dv(
166 "eval_rnea_derivatives_dv", casadi::SXVector{cs_q, cs_v, cs_a}, casadi::SXVector{cs_dtau_dv});
168 casadi::DM dtau_dv_res_direct =
169 eval_rnea_derivatives_dv(casadi::DMVector{q_vec, v_vec, a_vec})[0];
170 Data::MatrixXs dtau_dv_res_direct_map = Eigen::Map<Data::MatrixXs>(
171 static_cast<std::vector<double>
>(dtau_dv_res_direct).
data(),
model.nv,
model.nv);
172 BOOST_CHECK(dtau_dv_ref.isApprox(dtau_dv_res_direct_map));
174 casadi::Function eval_rnea_derivatives_da(
175 "eval_rnea_derivatives_da", casadi::SXVector{cs_q, cs_v, cs_a}, casadi::SXVector{cs_dtau_da});
177 casadi::DM dtau_da_res_direct =
178 eval_rnea_derivatives_da(casadi::DMVector{q_vec, v_vec, a_vec})[0];
179 Data::MatrixXs dtau_da_res_direct_map = Eigen::Map<Data::MatrixXs>(
180 static_cast<std::vector<double>
>(dtau_da_res_direct).
data(),
model.nv,
model.nv);
181 BOOST_CHECK(dtau_da_ref.isApprox(dtau_da_res_direct_map));
184 BOOST_AUTO_TEST_SUITE_END()