Directory: | ./ |
---|---|
File: | unittest/casadi/rnea-derivatives.cpp |
Date: | 2025-02-12 21:03:38 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 92 | 92 | 100.0% |
Branches: | 309 | 616 | 50.2% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | // | ||
2 | // Copyright (c) 2019-2020 INRIA | ||
3 | // | ||
4 | |||
5 | #include "pinocchio/autodiff/casadi.hpp" | ||
6 | #include "pinocchio/autodiff/casadi-algo.hpp" | ||
7 | |||
8 | #include "pinocchio/algorithm/rnea.hpp" | ||
9 | #include "pinocchio/algorithm/rnea-derivatives.hpp" | ||
10 | #include "pinocchio/algorithm/aba.hpp" | ||
11 | #include "pinocchio/algorithm/aba-derivatives.hpp" | ||
12 | #include "pinocchio/algorithm/joint-configuration.hpp" | ||
13 | |||
14 | #include "pinocchio/multibody/sample-models.hpp" | ||
15 | |||
16 | #include <casadi/casadi.hpp> | ||
17 | |||
18 | #include <iostream> | ||
19 | #include <boost/test/unit_test.hpp> | ||
20 | #include <boost/utility/binary.hpp> | ||
21 | |||
22 | BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) | ||
23 | |||
24 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_rnea_derivatives) |
25 | { | ||
26 | typedef double Scalar; | ||
27 | typedef casadi::SX ADScalar; | ||
28 | |||
29 | typedef pinocchio::ModelTpl<Scalar> Model; | ||
30 | typedef Model::Data Data; | ||
31 | |||
32 | typedef pinocchio::ModelTpl<ADScalar> ADModel; | ||
33 | typedef ADModel::Data ADData; | ||
34 | |||
35 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Model model; |
36 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::buildModels::humanoidRandom(model); |
37 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | model.lowerPositionLimit.head<3>().fill(-1.); |
38 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | model.upperPositionLimit.head<3>().fill(1.); |
39 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Data data(model); |
40 | |||
41 | typedef Model::ConfigVectorType ConfigVector; | ||
42 | typedef Model::TangentVectorType TangentVector; | ||
43 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ConfigVector q(model.nq); |
44 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | q = pinocchio::randomConfiguration(model); |
45 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | TangentVector v(TangentVector::Random(model.nv)); |
46 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | TangentVector a(TangentVector::Random(model.nv)); |
47 | |||
48 | typedef ADModel::ConfigVectorType ConfigVectorAD; | ||
49 | typedef ADModel::TangentVectorType TangentVectorAD; | ||
50 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ADModel ad_model = model.cast<ADScalar>(); |
51 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ADData ad_data(ad_model); |
52 | |||
53 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::rnea(model, data, q, v, a); |
54 | |||
55 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
4 | casadi::SX cs_q = casadi::SX::sym("q", model.nq); |
56 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
4 | casadi::SX cs_v_int = casadi::SX::sym("v_inc", model.nv); |
57 | |||
58 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | ConfigVectorAD q_ad(model.nq), v_int_ad(model.nv), q_int_ad(model.nq); |
59 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
|
2 | q_ad = Eigen::Map<ConfigVectorAD>(static_cast<std::vector<ADScalar>>(cs_q).data(), model.nq, 1); |
60 | v_int_ad = | ||
61 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
|
2 | Eigen::Map<ConfigVectorAD>(static_cast<std::vector<ADScalar>>(cs_v_int).data(), model.nv, 1); |
62 | |||
63 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::integrate(ad_model, q_ad, v_int_ad, q_int_ad); |
64 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | casadi::SX cs_q_int(model.nq, 1); |
65 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::casadi::copy(q_int_ad, cs_q_int); |
66 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | std::vector<double> q_vec((size_t)model.nq); |
67 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
|
2 | Eigen::Map<ConfigVector>(q_vec.data(), model.nq, 1) = q; |
68 | |||
69 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | std::vector<double> v_int_vec((size_t)model.nv); |
70 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
|
2 | Eigen::Map<TangentVector>(v_int_vec.data(), model.nv, 1).setZero(); |
71 | |||
72 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
4 | casadi::SX cs_v = casadi::SX::sym("v", model.nv); |
73 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | TangentVectorAD v_ad(model.nv); |
74 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
|
2 | v_ad = Eigen::Map<TangentVectorAD>(static_cast<std::vector<ADScalar>>(cs_v).data(), model.nv, 1); |
75 | |||
76 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
4 | casadi::SX cs_a = casadi::SX::sym("a", model.nv); |
77 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | TangentVectorAD a_ad(model.nv); |
78 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
|
2 | a_ad = Eigen::Map<TangentVectorAD>(static_cast<std::vector<ADScalar>>(cs_a).data(), model.nv, 1); |
79 | |||
80 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | rnea(ad_model, ad_data, q_int_ad, v_ad, a_ad); |
81 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | casadi::SX cs_tau(model.nv, 1); |
82 |
2/2✓ Branch 0 taken 32 times.
✓ Branch 1 taken 1 times.
|
66 | for (Eigen::DenseIndex k = 0; k < model.nv; ++k) |
83 | { | ||
84 |
3/6✓ Branch 1 taken 32 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 32 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 32 times.
✗ Branch 8 not taken.
|
64 | cs_tau(k) = ad_data.tau[k]; |
85 | } | ||
86 | casadi::Function eval_rnea( | ||
87 |
9/18✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 1 times.
✗ Branch 30 not taken.
|
18 | "eval_rnea", casadi::SXVector{cs_q, cs_v_int, cs_v, cs_a}, casadi::SXVector{cs_tau}); |
88 | |||
89 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | std::vector<double> v_vec((size_t)model.nv); |
90 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
|
2 | Eigen::Map<TangentVector>(v_vec.data(), model.nv, 1) = v; |
91 | |||
92 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | std::vector<double> a_vec((size_t)model.nv); |
93 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
|
2 | Eigen::Map<TangentVector>(a_vec.data(), model.nv, 1) = a; |
94 | |||
95 | // check return value | ||
96 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
|
12 | casadi::DM tau_res = eval_rnea(casadi::DMVector{q_vec, v_int_vec, v_vec, a_vec})[0]; |
97 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
6 | Data::TangentVectorType tau_vec = Eigen::Map<Data::TangentVectorType>( |
98 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
6 | static_cast<std::vector<double>>(tau_res).data(), model.nv, 1); |
99 | |||
100 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(data.tau.isApprox(tau_vec)); |
101 | |||
102 | // compute references | ||
103 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Data::MatrixXs dtau_dq_ref(model.nv, model.nv), dtau_dv_ref(model.nv, model.nv), |
104 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | dtau_da_ref(model.nv, model.nv); |
105 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | dtau_dq_ref.setZero(); |
106 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | dtau_dv_ref.setZero(); |
107 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | dtau_da_ref.setZero(); |
108 | |||
109 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::computeRNEADerivatives(model, data, q, v, a, dtau_dq_ref, dtau_dv_ref, dtau_da_ref); |
110 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | dtau_da_ref.triangularView<Eigen::StrictlyLower>() = |
111 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
4 | dtau_da_ref.transpose().triangularView<Eigen::StrictlyLower>(); |
112 | |||
113 | // check with respect to q+dq | ||
114 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | casadi::SX dtau_dq = jacobian(cs_tau, cs_v_int); |
115 | casadi::Function eval_dtau_dq( | ||
116 |
9/18✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 1 times.
✗ Branch 30 not taken.
|
18 | "eval_dtau_dq", casadi::SXVector{cs_q, cs_v_int, cs_v, cs_a}, casadi::SXVector{dtau_dq}); |
117 | |||
118 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
|
12 | casadi::DM dtau_dq_res = eval_dtau_dq(casadi::DMVector{q_vec, v_int_vec, v_vec, a_vec})[0]; |
119 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | std::vector<double> dtau_dq_vec(static_cast<std::vector<double>>(dtau_dq_res)); |
120 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 1 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 1 times.
✗ Branch 29 not taken.
✗ Branch 33 not taken.
✓ Branch 34 taken 1 times.
|
2 | BOOST_CHECK( |
121 | Eigen::Map<Data::MatrixXs>(dtau_dq_vec.data(), model.nv, model.nv).isApprox(dtau_dq_ref)); | ||
122 | |||
123 | // check with respect to v+dv | ||
124 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | casadi::SX dtau_dv = jacobian(cs_tau, cs_v); |
125 | casadi::Function eval_dtau_dv( | ||
126 |
9/18✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 1 times.
✗ Branch 30 not taken.
|
18 | "eval_dtau_dv", casadi::SXVector{cs_q, cs_v_int, cs_v, cs_a}, casadi::SXVector{dtau_dv}); |
127 | |||
128 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
|
12 | casadi::DM dtau_dv_res = eval_dtau_dv(casadi::DMVector{q_vec, v_int_vec, v_vec, a_vec})[0]; |
129 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | std::vector<double> dtau_dv_vec(static_cast<std::vector<double>>(dtau_dv_res)); |
130 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 1 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 1 times.
✗ Branch 29 not taken.
✗ Branch 33 not taken.
✓ Branch 34 taken 1 times.
|
2 | BOOST_CHECK( |
131 | Eigen::Map<Data::MatrixXs>(dtau_dv_vec.data(), model.nv, model.nv).isApprox(dtau_dv_ref)); | ||
132 | |||
133 | // check with respect to a+da | ||
134 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | casadi::SX dtau_da = jacobian(cs_tau, cs_a); |
135 | casadi::Function eval_dtau_da( | ||
136 |
9/18✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 1 times.
✗ Branch 30 not taken.
|
18 | "eval_dtau_da", casadi::SXVector{cs_q, cs_v_int, cs_v, cs_a}, casadi::SXVector{dtau_da}); |
137 | |||
138 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
|
12 | casadi::DM dtau_da_res = eval_dtau_da(casadi::DMVector{q_vec, v_int_vec, v_vec, a_vec})[0]; |
139 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | std::vector<double> dtau_da_vec(static_cast<std::vector<double>>(dtau_da_res)); |
140 |
9/18✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 1 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 1 times.
✗ Branch 29 not taken.
✗ Branch 33 not taken.
✓ Branch 34 taken 1 times.
|
2 | BOOST_CHECK( |
141 | Eigen::Map<Data::MatrixXs>(dtau_da_vec.data(), model.nv, model.nv).isApprox(dtau_da_ref)); | ||
142 | |||
143 | // call RNEA derivatives in Casadi | ||
144 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | casadi::SX cs_dtau_dq(model.nv, model.nv); |
145 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | casadi::SX cs_dtau_dv(model.nv, model.nv); |
146 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | casadi::SX cs_dtau_da(model.nv, model.nv); |
147 | |||
148 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | computeRNEADerivatives(ad_model, ad_data, q_ad, v_ad, a_ad); |
149 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ad_data.M.triangularView<Eigen::StrictlyLower>() = |
150 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
4 | ad_data.M.transpose().triangularView<Eigen::StrictlyLower>(); |
151 | |||
152 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::casadi::copy(ad_data.dtau_dq, cs_dtau_dq); |
153 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::casadi::copy(ad_data.dtau_dv, cs_dtau_dv); |
154 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::casadi::copy(ad_data.M, cs_dtau_da); |
155 | |||
156 | casadi::Function eval_rnea_derivatives_dq( | ||
157 |
8/16✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
|
16 | "eval_rnea_derivatives_dq", casadi::SXVector{cs_q, cs_v, cs_a}, casadi::SXVector{cs_dtau_dq}); |
158 | |||
159 | casadi::DM dtau_dq_res_direct = | ||
160 |
6/12✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
|
10 | eval_rnea_derivatives_dq(casadi::DMVector{q_vec, v_vec, a_vec})[0]; |
161 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
6 | Data::MatrixXs dtau_dq_res_direct_map = Eigen::Map<Data::MatrixXs>( |
162 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
6 | static_cast<std::vector<double>>(dtau_dq_res_direct).data(), model.nv, model.nv); |
163 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(dtau_dq_ref.isApprox(dtau_dq_res_direct_map)); |
164 | |||
165 | casadi::Function eval_rnea_derivatives_dv( | ||
166 |
8/16✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
|
16 | "eval_rnea_derivatives_dv", casadi::SXVector{cs_q, cs_v, cs_a}, casadi::SXVector{cs_dtau_dv}); |
167 | |||
168 | casadi::DM dtau_dv_res_direct = | ||
169 |
6/12✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
|
10 | eval_rnea_derivatives_dv(casadi::DMVector{q_vec, v_vec, a_vec})[0]; |
170 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
6 | Data::MatrixXs dtau_dv_res_direct_map = Eigen::Map<Data::MatrixXs>( |
171 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
6 | static_cast<std::vector<double>>(dtau_dv_res_direct).data(), model.nv, model.nv); |
172 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(dtau_dv_ref.isApprox(dtau_dv_res_direct_map)); |
173 | |||
174 | casadi::Function eval_rnea_derivatives_da( | ||
175 |
8/16✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
|
16 | "eval_rnea_derivatives_da", casadi::SXVector{cs_q, cs_v, cs_a}, casadi::SXVector{cs_dtau_da}); |
176 | |||
177 | casadi::DM dtau_da_res_direct = | ||
178 |
6/12✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
|
10 | eval_rnea_derivatives_da(casadi::DMVector{q_vec, v_vec, a_vec})[0]; |
179 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
6 | Data::MatrixXs dtau_da_res_direct_map = Eigen::Map<Data::MatrixXs>( |
180 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
6 | static_cast<std::vector<double>>(dtau_da_res_direct).data(), model.nv, model.nv); |
181 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(dtau_da_ref.isApprox(dtau_da_res_direct_map)); |
182 | 2 | } | |
183 | |||
184 | BOOST_AUTO_TEST_SUITE_END() | ||
185 |