| Directory: | ./ |
|---|---|
| File: | unittest/centroidal.cpp |
| Date: | 2025-02-12 21:03:38 |
| Exec | Total | Coverage | |
|---|---|---|---|
| Lines: | 245 | 246 | 99.6% |
| Branches: | 846 | 1690 | 50.1% |
| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | // | ||
| 2 | // Copyright (c) 2015-2019 CNRS INRIA | ||
| 3 | // | ||
| 4 | |||
| 5 | #include "pinocchio/algorithm/crba.hpp" | ||
| 6 | #include "pinocchio/algorithm/centroidal.hpp" | ||
| 7 | #include "pinocchio/algorithm/rnea.hpp" | ||
| 8 | #include "pinocchio/algorithm/jacobian.hpp" | ||
| 9 | #include "pinocchio/algorithm/center-of-mass.hpp" | ||
| 10 | #include "pinocchio/algorithm/joint-configuration.hpp" | ||
| 11 | |||
| 12 | #include "pinocchio/multibody/sample-models.hpp" | ||
| 13 | |||
| 14 | #include "pinocchio/utils/timer.hpp" | ||
| 15 | |||
| 16 | #include <iostream> | ||
| 17 | |||
| 18 | #include <boost/test/unit_test.hpp> | ||
| 19 | #include <boost/utility/binary.hpp> | ||
| 20 | |||
| 21 | template<typename JointModel> | ||
| 22 | 2 | static void addJointAndBody( | |
| 23 | pinocchio::Model & model, | ||
| 24 | const pinocchio::JointModelBase<JointModel> & joint, | ||
| 25 | const std::string & parent_name, | ||
| 26 | const std::string & name, | ||
| 27 | const pinocchio::SE3 placement = pinocchio::SE3::Random(), | ||
| 28 | bool setRandomLimits = true) | ||
| 29 | { | ||
| 30 | using namespace pinocchio; | ||
| 31 | typedef typename JointModel::ConfigVector_t CV; | ||
| 32 | typedef typename JointModel::TangentVector_t TV; | ||
| 33 | |||
| 34 | Model::JointIndex idx; | ||
| 35 | |||
| 36 |
1/2✓ Branch 0 taken 2 times.
✗ Branch 1 not taken.
|
2 | if (setRandomLimits) |
| 37 |
21/42✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 2 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 2 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 2 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 2 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 2 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 2 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 2 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 2 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 2 times.
✗ Branch 32 not taken.
✓ Branch 34 taken 2 times.
✗ Branch 35 not taken.
✓ Branch 37 taken 2 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 2 times.
✗ Branch 41 not taken.
✓ Branch 43 taken 2 times.
✗ Branch 44 not taken.
✓ Branch 46 taken 2 times.
✗ Branch 47 not taken.
✓ Branch 49 taken 2 times.
✗ Branch 50 not taken.
✓ Branch 52 taken 2 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 2 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 2 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 2 times.
✗ Branch 62 not taken.
|
2 | idx = model.addJoint( |
| 38 | model.getJointId(parent_name), joint, SE3::Random(), name + "_joint", | ||
| 39 | TV::Random() + TV::Constant(1), TV::Random() + TV::Constant(1), | ||
| 40 | CV::Random() - CV::Constant(1), CV::Random() + CV::Constant(1)); | ||
| 41 | else | ||
| 42 | ✗ | idx = model.addJoint(model.getJointId(parent_name), joint, placement, name + "_joint"); | |
| 43 | |||
| 44 |
1/2✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
|
2 | model.addJointFrame(idx); |
| 45 | |||
| 46 |
3/6✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 2 times.
✗ Branch 8 not taken.
|
2 | model.appendBodyToJoint(idx, Inertia::Random(), SE3::Identity()); |
| 47 |
3/6✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 2 times.
✗ Branch 8 not taken.
|
2 | model.addBodyFrame(name + "_body", idx); |
| 48 | 2 | } | |
| 49 | |||
| 50 | BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) | ||
| 51 | |||
| 52 |
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_ccrba) |
| 53 | { | ||
| 54 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::Model model; |
| 55 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::buildModels::humanoidRandom(model); |
| 56 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | pinocchio::Data data(model), data_ref(model); |
| 57 | |||
| 58 |
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.); |
| 59 |
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.); |
| 60 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Eigen::VectorXd q = randomConfiguration(model); |
| 61 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Eigen::VectorXd v = Eigen::VectorXd::Ones(model.nv); |
| 62 | |||
| 63 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::crba(model, data_ref, q, pinocchio::Convention::LOCAL); |
| 64 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | data_ref.M.triangularView<Eigen::StrictlyLower>() = |
| 65 |
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 | data_ref.M.transpose().triangularView<Eigen::StrictlyLower>(); |
| 66 | |||
| 67 |
2/4✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | data_ref.Ycrb[0] = data_ref.liMi[1].act(data_ref.Ycrb[1]); |
| 68 | |||
| 69 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::Data data_ref_other(model); |
| 70 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::crba(model, data_ref_other, q, pinocchio::Convention::WORLD); |
| 71 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | data_ref_other.M.triangularView<Eigen::StrictlyLower>() = |
| 72 |
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 | data_ref_other.M.transpose().triangularView<Eigen::StrictlyLower>(); |
| 73 |
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_ref_other.M.isApprox(data_ref.M)); |
| 74 | |||
| 75 |
3/6✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
|
2 | pinocchio::SE3 cMo(pinocchio::SE3::Matrix3::Identity(), -data_ref.Ycrb[0].lever()); |
| 76 |
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 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 1 times.
|
2 | BOOST_CHECK(data_ref.Ycrb[0].isApprox(data_ref_other.oYcrb[0])); |
| 77 | |||
| 78 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ccrba(model, data, q, v); |
| 79 |
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 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 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
|
2 | BOOST_CHECK(data.com[0].isApprox(-cMo.translation(), 1e-12)); |
| 80 |
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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 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(data.oYcrb[0].matrix().isApprox(data_ref.Ycrb[0].matrix(), 1e-12)); |
| 81 | |||
| 82 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | pinocchio::Inertia Ig_ref(cMo.act(data.oYcrb[0])); |
| 83 |
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 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✗ Branch 31 not taken.
✓ Branch 32 taken 1 times.
|
2 | BOOST_CHECK(data.Ig.matrix().isApprox(Ig_ref.matrix(), 1e-12)); |
| 84 | |||
| 85 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | pinocchio::SE3 oM1(data_ref.liMi[1]); |
| 86 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::SE3 cM1(cMo * oM1); |
| 87 | |||
| 88 | pinocchio::Data::Matrix6x Ag_ref( | ||
| 89 |
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 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
|
2 | cM1.inverse().toActionMatrix().transpose() * data_ref.M.topRows<6>()); |
| 90 |
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 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(data.Ag.isApprox(Ag_ref, 1e-12)); |
| 91 | 2 | } | |
| 92 | |||
| 93 |
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_centroidal_mapping) |
| 94 | { | ||
| 95 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::Model model; |
| 96 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::buildModels::humanoidRandom(model); |
| 97 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | pinocchio::Data data(model), data_ref(model); |
| 98 | |||
| 99 |
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.); |
| 100 |
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.); |
| 101 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Eigen::VectorXd q = randomConfiguration(model); |
| 102 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Eigen::VectorXd v = Eigen::VectorXd::Zero(model.nv); |
| 103 | |||
| 104 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | computeCentroidalMap(model, data, q); |
| 105 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ccrba(model, data_ref, q, v); |
| 106 | |||
| 107 |
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.J.isApprox(data_ref.J)); |
| 108 |
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.Ag.isApprox(data_ref.Ag)); |
| 109 | |||
| 110 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | computeJointJacobians(model, data_ref, q); |
| 111 | |||
| 112 |
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.J.isApprox(data_ref.J)); |
| 113 | 2 | } | |
| 114 | |||
| 115 |
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_dccrb) |
| 116 | { | ||
| 117 | using namespace pinocchio; | ||
| 118 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Model model; |
| 119 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | buildModels::humanoidRandom(model); |
| 120 |
5/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 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.
|
2 | addJointAndBody(model, JointModelSpherical(), "larm6_joint", "larm7"); |
| 121 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Data data(model), data_ref(model); |
| 122 | |||
| 123 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | model.lowerPositionLimit.head<7>().fill(-1.); |
| 124 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | model.upperPositionLimit.head<7>().fill(1.); |
| 125 | |||
| 126 | Eigen::VectorXd q = | ||
| 127 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | randomConfiguration(model, model.lowerPositionLimit, model.upperPositionLimit); |
| 128 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Eigen::VectorXd v = Eigen::VectorXd::Random(model.nv); |
| 129 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Eigen::VectorXd a = Eigen::VectorXd::Random(model.nv); |
| 130 | |||
| 131 |
4/8✓ 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.
|
2 | const Eigen::VectorXd g = rnea(model, data_ref, q, 0 * v, 0 * a); |
| 132 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | rnea(model, data_ref, q, v, a); |
| 133 | |||
| 134 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::crba(model, data_ref, q, pinocchio::Convention::LOCAL); |
| 135 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | data_ref.M.triangularView<Eigen::StrictlyLower>() = |
| 136 |
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 | data_ref.M.transpose().triangularView<Eigen::StrictlyLower>(); |
| 137 | |||
| 138 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 cMo(SE3::Identity()); |
| 139 |
2/4✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
2 | data_ref.Ycrb[0] = data_ref.liMi[1].act(data_ref.Ycrb[1]); |
| 140 |
3/6✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
|
2 | cMo.translation() = -data_ref.Ycrb[0].lever(); |
| 141 | |||
| 142 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | SE3 oM1(data_ref.liMi[1]); |
| 143 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 cM1(cMo * oM1); |
| 144 |
4/8✓ 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.
|
2 | Data::Matrix6x Ag_ref(cM1.toDualActionMatrix() * data_ref.M.topRows<6>()); |
| 145 | |||
| 146 |
5/10✓ 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 13 taken 1 times.
✗ Branch 14 not taken.
|
2 | Force hdot_ref(cM1.act(Force(data_ref.tau.head<6>() - g.head<6>()))); |
| 147 | |||
| 148 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ccrba(model, data_ref, q, v); |
| 149 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | dccrba(model, data, q, v); |
| 150 |
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.Ag.isApprox(Ag_ref)); |
| 151 |
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.Ag.isApprox(data_ref.Ag)); |
| 152 |
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.hg.isApprox(data_ref.hg)); |
| 153 | |||
| 154 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | centerOfMass(model, data_ref, q, v, a); |
| 155 |
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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(data_ref.com[0].isApprox(data_ref.Ycrb[0].lever())); |
| 156 |
10/20✓ 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 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 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 31 taken 1 times.
✗ Branch 32 not taken.
✗ Branch 36 not taken.
✓ Branch 37 taken 1 times.
|
2 | BOOST_CHECK(data_ref.vcom[0].isApprox(data.hg.linear() / data_ref.M(0, 0))); |
| 157 |
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 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 1 times.
|
2 | BOOST_CHECK(data_ref.vcom[0].isApprox(data.vcom[0])); |
| 158 |
10/20✓ 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 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 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 31 taken 1 times.
✗ Branch 32 not taken.
✗ Branch 36 not taken.
✓ Branch 37 taken 1 times.
|
2 | BOOST_CHECK(data_ref.acom[0].isApprox(hdot_ref.linear() / data_ref.M(0, 0))); |
| 159 | |||
| 160 |
4/8✓ 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.
|
2 | Force hdot(data.Ag * a + data.dAg * v); |
| 161 |
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(hdot.isApprox(hdot_ref)); |
| 162 | |||
| 163 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | dccrba(model, data, q, 0 * v); |
| 164 |
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.dAg.isZero()); |
| 165 | |||
| 166 | // Check that dYcrb is equal to doYcrb | ||
| 167 | { | ||
| 168 | // Compute dYcrb | ||
| 169 |
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 | Data data_ref(model), data_ref_plus(model), data(model); |
| 170 | |||
| 171 | 2 | const double alpha = 1e-8; | |
| 172 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Eigen::VectorXd q_plus(model.nq); |
| 173 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | q_plus = integrate(model, q, alpha * v); |
| 174 | |||
| 175 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | forwardKinematics(model, data_ref, q); |
| 176 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::crba(model, data_ref, q, pinocchio::Convention::LOCAL); |
| 177 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::crba(model, data_ref_plus, q_plus, pinocchio::Convention::LOCAL); |
| 178 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | forwardKinematics(model, data_ref_plus, q_plus); |
| 179 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | dccrba(model, data, q, v); |
| 180 | |||
| 181 |
2/2✓ Branch 0 taken 28 times.
✓ Branch 1 taken 1 times.
|
58 | for (size_t i = 1; i < (size_t)model.njoints; ++i) |
| 182 | { | ||
| 183 |
2/4✓ Branch 3 taken 28 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 28 times.
✗ Branch 7 not taken.
|
56 | Inertia::Matrix6 dYcrb = (data_ref_plus.oMi[i].act(data_ref_plus.Ycrb[i]).matrix() |
| 184 |
3/6✓ Branch 3 taken 28 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 28 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 28 times.
✗ Branch 10 not taken.
|
112 | - data_ref.oMi[i].act(data_ref.Ycrb[i]).matrix()) |
| 185 |
2/4✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 28 times.
✗ Branch 5 not taken.
|
56 | / alpha; |
| 186 |
7/14✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 28 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 28 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 28 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 28 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 28 times.
|
56 | BOOST_CHECK(data.doYcrb[i].isApprox(dYcrb, sqrt(alpha))); |
| 187 | } | ||
| 188 | 2 | } | |
| 189 | |||
| 190 | { | ||
| 191 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Data data(model); |
| 192 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ccrba(model, data_ref, q, v); |
| 193 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 oMc_ref(SE3::Identity()); |
| 194 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | oMc_ref.translation() = data_ref.com[0]; |
| 195 |
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 | const Data::Matrix6x Ag_ref = oMc_ref.toDualActionMatrix() * data_ref.Ag; |
| 196 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::crba(model, data_ref, q, pinocchio::Convention::LOCAL); |
| 197 | const Data::Matrix6x Ag_ref_from_M = | ||
| 198 |
4/8✓ 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.
|
2 | data_ref.oMi[1].toDualActionMatrix() * data_ref.M.topRows<6>(); |
| 199 | |||
| 200 | 2 | const double alpha = 1e-8; | |
| 201 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Eigen::VectorXd q_plus(model.nq); |
| 202 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | q_plus = integrate(model, q, alpha * v); |
| 203 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ccrba(model, data_ref, q_plus, v); |
| 204 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 oMc_ref_plus(SE3::Identity()); |
| 205 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | oMc_ref_plus.translation() = data_ref.com[0]; |
| 206 |
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 | const Data::Matrix6x Ag_plus_ref = oMc_ref_plus.toDualActionMatrix() * data_ref.Ag; |
| 207 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::crba(model, data_ref, q_plus, pinocchio::Convention::LOCAL); |
| 208 | const Data::Matrix6x Ag_plus_ref_from_M = | ||
| 209 |
4/8✓ 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.
|
2 | data_ref.oMi[1].toDualActionMatrix() * data_ref.M.topRows<6>(); |
| 210 |
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 | const Data::Matrix6x dAg_ref = (Ag_plus_ref - Ag_ref) / alpha; |
| 211 |
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 | const Data::Matrix6x dAg_ref_from_M = (Ag_plus_ref_from_M - Ag_ref_from_M) / alpha; |
| 212 | |||
| 213 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | dccrba(model, data, q, v); |
| 214 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 oMc(SE3::Identity()); |
| 215 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | oMc.translation() = data.com[0]; |
| 216 |
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 | Data::Matrix6x dAg = oMc.toDualActionMatrix() * data.dAg; |
| 217 |
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(oMc.isApprox(oMc_ref)); |
| 218 |
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 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(dAg_ref.isApprox(dAg_ref_from_M, sqrt(alpha))); |
| 219 | 2 | } | |
| 220 | |||
| 221 | // Check for dAg/dt | ||
| 222 | { | ||
| 223 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Data data(model); |
| 224 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ccrba(model, data_ref, q, v); |
| 225 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | const Data::Matrix6x Ag_ref = data_ref.Ag; |
| 226 | |||
| 227 | 2 | const double alpha = 1e-8; | |
| 228 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Eigen::VectorXd q_plus(model.nq); |
| 229 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | q_plus = integrate(model, q, alpha * v); |
| 230 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ccrba(model, data_ref, q_plus, v); |
| 231 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | const Data::Matrix6x Ag_plus_ref = data_ref.Ag; |
| 232 |
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 | const Data::Matrix6x dAg_ref = (Ag_plus_ref - Ag_ref) / alpha; |
| 233 | |||
| 234 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | dccrba(model, data, q, v); |
| 235 |
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 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(data.dAg.isApprox(dAg_ref, sqrt(alpha))); |
| 236 | 2 | } | |
| 237 | |||
| 238 | // Compute tensor dAg/dq | ||
| 239 | { | ||
| 240 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
|
4 | std::vector<Data::Matrix6x> dAgdq((size_t)model.nv, Data::Matrix6x::Zero(6, model.nv)); |
| 241 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Data data(model), data_fd(model); |
| 242 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Eigen::VectorXd v_fd(Eigen::VectorXd::Zero(model.nv)); |
| 243 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ccrba(model, data_fd, q, v); |
| 244 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 oMc_ref(SE3::Identity()); |
| 245 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | oMc_ref.translation() = data_fd.com[0]; |
| 246 | |||
| 247 |
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 | Data::Matrix6x Ag0 = oMc_ref.toDualActionMatrix() * data_fd.Ag; |
| 248 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | const Force hg0 = oMc_ref.act(data_fd.hg); |
| 249 | |||
| 250 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Data::Matrix6x Ag_fd(6, model.nv); |
| 251 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Force hg_fd; |
| 252 | 2 | const double alpha = 1e-8; | |
| 253 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Eigen::VectorXd q_plus(model.nq); |
| 254 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Data::Matrix6x dhdq(6, model.nv); |
| 255 |
2/2✓ Branch 0 taken 35 times.
✓ Branch 1 taken 1 times.
|
72 | for (int k = 0; k < model.nv; ++k) |
| 256 | { | ||
| 257 |
1/2✓ Branch 1 taken 35 times.
✗ Branch 2 not taken.
|
70 | v_fd[k] = alpha; |
| 258 |
1/2✓ Branch 1 taken 35 times.
✗ Branch 2 not taken.
|
70 | q_plus = integrate(model, q, v_fd); |
| 259 |
1/2✓ Branch 1 taken 35 times.
✗ Branch 2 not taken.
|
70 | ccrba(model, data_fd, q_plus, v); |
| 260 |
1/2✓ Branch 1 taken 35 times.
✗ Branch 2 not taken.
|
70 | SE3 oMc_fd(SE3::Identity()); |
| 261 |
2/4✓ Branch 2 taken 35 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 35 times.
✗ Branch 6 not taken.
|
70 | oMc_fd.translation() = data_fd.com[0]; |
| 262 |
3/6✓ Branch 1 taken 35 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 35 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 35 times.
✗ Branch 8 not taken.
|
70 | Ag_fd = oMc_fd.toDualActionMatrix() * data_fd.Ag; |
| 263 |
2/4✓ Branch 1 taken 35 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 35 times.
✗ Branch 5 not taken.
|
70 | hg_fd = oMc_fd.act(data_fd.hg); |
| 264 |
3/6✓ Branch 1 taken 35 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 35 times.
✗ Branch 5 not taken.
✓ Branch 8 taken 35 times.
✗ Branch 9 not taken.
|
70 | dAgdq[(size_t)k] = (Ag_fd - Ag0) / alpha; |
| 265 |
5/10✓ Branch 1 taken 35 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 35 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 35 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 35 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 35 times.
✗ Branch 14 not taken.
|
70 | dhdq.col(k) = (hg_fd - hg0).toVector() / alpha; |
| 266 |
1/2✓ Branch 1 taken 35 times.
✗ Branch 2 not taken.
|
70 | v_fd[k] = 0.; |
| 267 | } | ||
| 268 | |||
| 269 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Data::Matrix6x dAg_ref(6, model.nv); |
| 270 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | dAg_ref.setZero(); |
| 271 |
2/2✓ Branch 0 taken 35 times.
✓ Branch 1 taken 1 times.
|
72 | for (int k = 0; k < model.nv; ++k) |
| 272 | { | ||
| 273 |
3/6✓ Branch 2 taken 35 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 35 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 35 times.
✗ Branch 9 not taken.
|
70 | dAg_ref.col(k) = dAgdq[(size_t)k] * v; |
| 274 | } | ||
| 275 | |||
| 276 |
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 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(dhdq.isApprox(dAg_ref, sqrt(alpha))); |
| 277 |
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 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✗ Branch 31 not taken.
✓ Branch 32 taken 1 times.
|
2 | BOOST_CHECK((dAg_ref * v).isApprox(dhdq * v, sqrt(alpha))); |
| 278 | 2 | } | |
| 279 | 2 | } | |
| 280 | |||
| 281 |
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_centroidal_mapping_time_derivative) |
| 282 | { | ||
| 283 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::Model model; |
| 284 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::buildModels::humanoidRandom(model); |
| 285 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | pinocchio::Data data(model), data_ref(model); |
| 286 | |||
| 287 |
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.); |
| 288 |
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.); |
| 289 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Eigen::VectorXd q = randomConfiguration(model); |
| 290 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Eigen::VectorXd v = Eigen::VectorXd::Zero(model.nv); |
| 291 | |||
| 292 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | computeCentroidalMapTimeVariation(model, data, q, v); |
| 293 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | dccrba(model, data_ref, q, v); |
| 294 | |||
| 295 |
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.J.isApprox(data_ref.J)); |
| 296 |
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.dJ.isApprox(data_ref.dJ)); |
| 297 |
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.Ag.isApprox(data_ref.Ag)); |
| 298 |
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.dAg.isApprox(data_ref.dAg)); |
| 299 | |||
| 300 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | computeJointJacobiansTimeVariation(model, data_ref, q, v); |
| 301 | |||
| 302 |
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.J.isApprox(data_ref.J)); |
| 303 |
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.dJ.isApprox(data_ref.dJ)); |
| 304 | 2 | } | |
| 305 | |||
| 306 |
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_computeCentroidalMomentum_computeCentroidalMomentumTimeVariation) |
| 307 | { | ||
| 308 | using namespace pinocchio; | ||
| 309 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Model model; |
| 310 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | buildModels::humanoidRandom(model); |
| 311 |
5/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 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.
|
2 | addJointAndBody(model, JointModelSpherical(), "larm6_joint", "larm7"); |
| 312 |
4/8✓ 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.
|
2 | Data data(model), data_fk1(model), data_fk2(model), data_ref(model); |
| 313 | |||
| 314 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | model.lowerPositionLimit.head<7>().fill(-1.); |
| 315 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | model.upperPositionLimit.head<7>().fill(1.); |
| 316 | |||
| 317 | Eigen::VectorXd q = | ||
| 318 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | randomConfiguration(model, model.lowerPositionLimit, model.upperPositionLimit); |
| 319 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Eigen::VectorXd v = Eigen::VectorXd::Random(model.nv); |
| 320 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Eigen::VectorXd a = Eigen::VectorXd::Random(model.nv); |
| 321 | |||
| 322 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ccrba(model, data_ref, q, v); |
| 323 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | forwardKinematics(model, data_ref, q, v); |
| 324 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | centerOfMass(model, data_ref, q, v, false); |
| 325 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | computeCentroidalMomentum(model, data, q, v); |
| 326 | |||
| 327 |
6/12✓ 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 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✗ Branch 24 not taken.
✓ Branch 25 taken 1 times.
|
2 | BOOST_CHECK(data.mass[0] == data_ref.mass[0]); |
| 328 |
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 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 1 times.
|
2 | BOOST_CHECK(data.com[0].isApprox(data_ref.com[0])); |
| 329 |
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.hg.isApprox(data_ref.hg)); |
| 330 |
2/2✓ Branch 0 taken 28 times.
✓ Branch 1 taken 1 times.
|
58 | for (size_t k = 1; k < (size_t)model.njoints; ++k) |
| 331 | { | ||
| 332 |
6/12✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 28 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 28 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 28 times.
✗ Branch 20 not taken.
✗ Branch 24 not taken.
✓ Branch 25 taken 28 times.
|
56 | BOOST_CHECK(data.mass[k] == data_ref.mass[k]); |
| 333 |
7/14✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 28 times.
✗ Branch 12 not taken.
✓ Branch 17 taken 28 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 28 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 28 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 28 times.
|
56 | BOOST_CHECK(data.com[k].isApprox(data_ref.com[k])); |
| 334 |
7/14✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 28 times.
✗ Branch 12 not taken.
✓ Branch 17 taken 28 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 28 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 28 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 28 times.
|
56 | BOOST_CHECK(data.v[k].isApprox(data_ref.v[k])); |
| 335 | } | ||
| 336 | |||
| 337 | // Check other signature | ||
| 338 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | forwardKinematics(model, data_fk1, q, v); |
| 339 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | computeCentroidalMomentum(model, data_fk1); |
| 340 | |||
| 341 |
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_fk1.hg.isApprox(data.hg)); |
| 342 | |||
| 343 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | computeCentroidalMomentumTimeVariation(model, data, q, v, a); |
| 344 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | model.gravity.setZero(); |
| 345 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | rnea(model, data_ref, q, v, a); |
| 346 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | dccrba(model, data_ref, q, v); |
| 347 |
4/8✓ 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.
|
2 | const Force hgdot(data_ref.Ag * a + data_ref.dAg * v); |
| 348 | |||
| 349 |
6/12✓ 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 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✗ Branch 24 not taken.
✓ Branch 25 taken 1 times.
|
2 | BOOST_CHECK(data.mass[0] == data_ref.mass[0]); |
| 350 |
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 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 1 times.
|
2 | BOOST_CHECK(data.com[0].isApprox(data_ref.com[0])); |
| 351 |
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.hg.isApprox(data_ref.hg)); |
| 352 |
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.dhg.isApprox(hgdot)); |
| 353 |
2/2✓ Branch 0 taken 28 times.
✓ Branch 1 taken 1 times.
|
58 | for (size_t k = 1; k < (size_t)model.njoints; ++k) |
| 354 | { | ||
| 355 |
6/12✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 28 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 28 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 28 times.
✗ Branch 20 not taken.
✗ Branch 24 not taken.
✓ Branch 25 taken 28 times.
|
56 | BOOST_CHECK(data.mass[k] == data_ref.mass[k]); |
| 356 |
7/14✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 28 times.
✗ Branch 12 not taken.
✓ Branch 17 taken 28 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 28 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 28 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 28 times.
|
56 | BOOST_CHECK(data.com[k].isApprox(data_ref.com[k])); |
| 357 |
7/14✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 28 times.
✗ Branch 12 not taken.
✓ Branch 17 taken 28 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 28 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 28 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 28 times.
|
56 | BOOST_CHECK(data.v[k].isApprox(data_ref.v[k])); |
| 358 |
7/14✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 28 times.
✗ Branch 12 not taken.
✓ Branch 17 taken 28 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 28 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 28 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 28 times.
|
56 | BOOST_CHECK(data.a[k].isApprox(data_ref.a_gf[k])); |
| 359 |
7/14✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 28 times.
✗ Branch 12 not taken.
✓ Branch 17 taken 28 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 28 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 28 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 28 times.
|
56 | BOOST_CHECK(data.f[k].isApprox(data_ref.f[k])); |
| 360 | } | ||
| 361 | |||
| 362 | // Check other signature | ||
| 363 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | forwardKinematics(model, data_fk2, q, v, a); |
| 364 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | computeCentroidalMomentumTimeVariation(model, data_fk2); |
| 365 | |||
| 366 |
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_fk2.hg.isApprox(data.hg)); |
| 367 |
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_fk2.dhg.isApprox(data.dhg)); |
| 368 | |||
| 369 | // Check against finite differences | ||
| 370 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Data data_fd(model); |
| 371 | 2 | const double eps = 1e-8; | |
| 372 |
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 | Eigen::VectorXd v_plus = v + eps * a; |
| 373 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Eigen::VectorXd q_plus = integrate(model, q, eps * v); |
| 374 | |||
| 375 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | const Force hg = computeCentroidalMomentum(model, data_fd, q, v); |
| 376 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | const SE3::Vector3 com = data_fd.com[0]; |
| 377 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | const Force hg_plus = computeCentroidalMomentum(model, data_fd, q_plus, v_plus); |
| 378 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | const SE3::Vector3 com_plus = data_fd.com[0]; |
| 379 | |||
| 380 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 transform(SE3::Identity()); |
| 381 |
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 | transform.translation() = com_plus - com; |
| 382 |
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 | Force dhg_ref = (transform.act(hg_plus) - hg) / eps; |
| 383 | |||
| 384 |
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 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(data.dhg.isApprox(dhg_ref, sqrt(eps))); |
| 385 | 2 | } | |
| 386 | |||
| 387 | BOOST_AUTO_TEST_SUITE_END() | ||
| 388 |