| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | // | ||
| 2 | // Copyright (c) 2018 CNRS | ||
| 3 | // Authors: Pierre Fernbach | ||
| 4 | // | ||
| 5 | // This file is part of bezier_COM_traj | ||
| 6 | // hpp-core is free software: you can redistribute it | ||
| 7 | // and/or modify it under the terms of the GNU Lesser General Public | ||
| 8 | // License as published by the Free Software Foundation, either version | ||
| 9 | // 3 of the License, or (at your option) any later version. | ||
| 10 | // | ||
| 11 | // hpp-core is distributed in the hope that it will be | ||
| 12 | // useful, but WITHOUT ANY WARRANTY; without even the implied warranty | ||
| 13 | // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU | ||
| 14 | // General Lesser Public License for more details. You should have | ||
| 15 | // received a copy of the GNU Lesser General Public License along with | ||
| 16 | // hpp-core If not, see | ||
| 17 | // <http://www.gnu.org/licenses/>. | ||
| 18 | |||
| 19 | #define BOOST_TEST_MODULE transition - quasiStatic | ||
| 20 | #include <boost/test/included/unit_test.hpp> | ||
| 21 | #include <hpp/bezier-com-traj/common_solve_methods.hh> | ||
| 22 | #include <hpp/bezier-com-traj/solve.hh> | ||
| 23 | #include <hpp/centroidal-dynamics/centroidal_dynamics.hh> | ||
| 24 | |||
| 25 | #include "test_helper.hh" | ||
| 26 | |||
| 27 | BOOST_AUTO_TEST_SUITE(quasiStatic) | ||
| 28 | |||
| 29 |
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(single_support) { |
| 30 | // check if state valid with only one contact : | ||
| 31 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | MatrixX3 normal(1, 3); |
| 32 |
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 | normal << 0, 0, 1; |
| 33 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | MatrixX3 position(1, 3); |
| 34 |
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 | position << 0, 0, 0; |
| 35 | std::pair<MatrixX3, VectorX> Ab = generateConstraints( | ||
| 36 |
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 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
|
2 | normal, position, Matrix3::Identity(), Vector3::Zero()); |
| 37 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | std::pair<Matrix3, Vector3> Hg = computeCost(); |
| 38 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Vector3 init = Vector3::Zero(); |
| 39 |
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 | bezier_com_traj::ResultData res = bezier_com_traj::solve(Ab, Hg, init); |
| 40 |
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 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
|
2 | BOOST_CHECK(res.success_); |
| 41 | |||
| 42 | // sample positions for second foot inside kinematics constraints and check | ||
| 43 | // for feasibility : | ||
| 44 | 2 | } | |
| 45 | |||
| 46 |
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(quasiStatic_exist) { |
| 47 | // sample positions for second foot inside kinematics constraints and check | ||
| 48 | // for feasibility : Vector3 firstLeg_n(0,0,1); Vector3 firstLeg_p(0,0,0); | ||
| 49 | |||
| 50 |
2/2✓ Branch 0 taken 500 times.
✓ Branch 1 taken 1 times.
|
1002 | for (size_t i = 0; i < 500; ++i) { |
| 51 |
1/2✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
|
1000 | MatrixX3 normal(1, 3); |
| 52 |
1/2✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
|
1000 | MatrixX3 position(1, 3); |
| 53 | // normal.block<1,3>(0,0) = firstLeg_n; | ||
| 54 | // position.block<1,3>(0,0) = firstLeg_p; | ||
| 55 | 1000 | double x = fRandom(KIN_X_MIN, KIN_X_MAX); | |
| 56 | 1000 | double y = fRandom(KIN_Y_MIN, KIN_Y_MAX); | |
| 57 |
3/6✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
|
1000 | normal.block<1, 3>(0, 0) = Vector3(0, 0, 1); |
| 58 |
3/6✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
|
1000 | position.block<1, 3>(0, 0) = Vector3(x, y, 0.); |
| 59 | |||
| 60 | std::pair<MatrixX3, VectorX> Ab = generateConstraints( | ||
| 61 |
7/14✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 500 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 500 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 500 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 500 times.
✗ Branch 20 not taken.
|
1000 | normal, position, Matrix3::Identity(), Vector3::Zero()); |
| 62 |
1/2✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
|
1000 | std::pair<Matrix3, Vector3> Hg = computeCost(); |
| 63 |
2/4✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
|
1000 | Vector3 init = Vector3::Zero(); |
| 64 |
4/8✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 500 times.
✗ Branch 11 not taken.
|
1000 | bezier_com_traj::ResultData res = bezier_com_traj::solve(Ab, Hg, init); |
| 65 |
6/12✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 500 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 500 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 500 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 500 times.
✗ Branch 18 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 500 times.
|
1000 | BOOST_CHECK(res.success_); |
| 66 | 1000 | } | |
| 67 | 2 | } | |
| 68 | |||
| 69 |
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(quasiStatic_empty_upX) { |
| 70 |
2/2✓ Branch 0 taken 500 times.
✓ Branch 1 taken 1 times.
|
1002 | for (size_t i = 0; i < 500; ++i) { |
| 71 |
1/2✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
|
1000 | MatrixX3 normal(1, 3); |
| 72 |
1/2✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
|
1000 | MatrixX3 position(1, 3); |
| 73 | // normal.block<1,3>(0,0) = firstLeg_n; | ||
| 74 | // position.block<1,3>(0,0) = firstLeg_p; | ||
| 75 | 1000 | double x = fRandom(KIN_X_MAX + (LX / 2.) + 0.001, 10); | |
| 76 | 1000 | double y = fRandom(KIN_Y_MIN, KIN_Y_MAX); | |
| 77 |
3/6✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
|
1000 | normal.block<1, 3>(0, 0) = Vector3(0, 0, 1); |
| 78 |
3/6✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
|
1000 | position.block<1, 3>(0, 0) = Vector3(x, y, 0.); |
| 79 | |||
| 80 | std::pair<MatrixX3, VectorX> Ab = generateConstraints( | ||
| 81 |
7/14✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 500 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 500 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 500 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 500 times.
✗ Branch 20 not taken.
|
1000 | normal, position, Matrix3::Identity(), Vector3::Zero()); |
| 82 |
1/2✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
|
1000 | std::pair<Matrix3, Vector3> Hg = computeCost(); |
| 83 |
2/4✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
|
1000 | Vector3 init = Vector3::Zero(); |
| 84 |
4/8✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 500 times.
✗ Branch 11 not taken.
|
1000 | bezier_com_traj::ResultData res = bezier_com_traj::solve(Ab, Hg, init); |
| 85 |
6/12✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 500 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 500 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 500 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 500 times.
✗ Branch 18 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 500 times.
|
1000 | BOOST_CHECK(!res.success_); |
| 86 | 1000 | } | |
| 87 | 2 | } | |
| 88 | |||
| 89 |
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(quasiStatic_empty_downX) { |
| 90 |
2/2✓ Branch 0 taken 500 times.
✓ Branch 1 taken 1 times.
|
1002 | for (size_t i = 0; i < 500; ++i) { |
| 91 |
1/2✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
|
1000 | MatrixX3 normal(1, 3); |
| 92 |
1/2✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
|
1000 | MatrixX3 position(1, 3); |
| 93 | // normal.block<1,3>(0,0) = firstLeg_n; | ||
| 94 | // position.block<1,3>(0,0) = firstLeg_p; | ||
| 95 | 1000 | double x = fRandom(-10, KIN_X_MIN - (LX / 2.) - 0.001); | |
| 96 | 1000 | double y = fRandom(KIN_Y_MIN, KIN_Y_MAX); | |
| 97 |
3/6✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
|
1000 | normal.block<1, 3>(0, 0) = Vector3(0, 0, 1); |
| 98 |
3/6✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
|
1000 | position.block<1, 3>(0, 0) = Vector3(x, y, 0.); |
| 99 | |||
| 100 | std::pair<MatrixX3, VectorX> Ab = generateConstraints( | ||
| 101 |
7/14✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 500 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 500 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 500 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 500 times.
✗ Branch 20 not taken.
|
1000 | normal, position, Matrix3::Identity(), Vector3::Zero()); |
| 102 |
1/2✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
|
1000 | std::pair<Matrix3, Vector3> Hg = computeCost(); |
| 103 |
2/4✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
|
1000 | Vector3 init = Vector3::Zero(); |
| 104 |
4/8✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 500 times.
✗ Branch 11 not taken.
|
1000 | bezier_com_traj::ResultData res = bezier_com_traj::solve(Ab, Hg, init); |
| 105 |
6/12✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 500 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 500 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 500 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 500 times.
✗ Branch 18 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 500 times.
|
1000 | BOOST_CHECK(!res.success_); |
| 106 | 1000 | } | |
| 107 | 2 | } | |
| 108 | |||
| 109 |
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(quasiStatic_empty_downY) { |
| 110 |
2/2✓ Branch 0 taken 500 times.
✓ Branch 1 taken 1 times.
|
1002 | for (size_t i = 0; i < 500; ++i) { |
| 111 |
1/2✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
|
1000 | MatrixX3 normal(1, 3); |
| 112 |
1/2✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
|
1000 | MatrixX3 position(1, 3); |
| 113 | // normal.block<1,3>(0,0) = firstLeg_n; | ||
| 114 | // position.block<1,3>(0,0) = firstLeg_p; | ||
| 115 | 1000 | double x = fRandom(KIN_X_MIN, KIN_X_MAX); | |
| 116 | 1000 | double y = fRandom(-10, KIN_Y_MIN - (LY / 2.) - 0.001); | |
| 117 |
3/6✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
|
1000 | normal.block<1, 3>(0, 0) = Vector3(0, 0, 1); |
| 118 |
3/6✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
|
1000 | position.block<1, 3>(0, 0) = Vector3(x, y, 0.); |
| 119 | |||
| 120 | std::pair<MatrixX3, VectorX> Ab = generateConstraints( | ||
| 121 |
7/14✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 500 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 500 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 500 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 500 times.
✗ Branch 20 not taken.
|
1000 | normal, position, Matrix3::Identity(), Vector3::Zero()); |
| 122 |
1/2✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
|
1000 | std::pair<Matrix3, Vector3> Hg = computeCost(); |
| 123 |
2/4✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
|
1000 | Vector3 init = Vector3::Zero(); |
| 124 |
4/8✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 500 times.
✗ Branch 11 not taken.
|
1000 | bezier_com_traj::ResultData res = bezier_com_traj::solve(Ab, Hg, init); |
| 125 |
6/12✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 500 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 500 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 500 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 500 times.
✗ Branch 18 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 500 times.
|
1000 | BOOST_CHECK(!res.success_); |
| 126 | 1000 | } | |
| 127 | 2 | } | |
| 128 | |||
| 129 |
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(quasiStatic_empty_upY) { |
| 130 |
2/2✓ Branch 0 taken 500 times.
✓ Branch 1 taken 1 times.
|
1002 | for (size_t i = 0; i < 500; ++i) { |
| 131 |
1/2✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
|
1000 | MatrixX3 normal(1, 3); |
| 132 |
1/2✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
|
1000 | MatrixX3 position(1, 3); |
| 133 | // normal.block<1,3>(0,0) = firstLeg_n; | ||
| 134 | // position.block<1,3>(0,0) = firstLeg_p; | ||
| 135 | 1000 | double x = fRandom(KIN_X_MIN, KIN_X_MAX); | |
| 136 | 1000 | double y = fRandom(KIN_Y_MAX + (LY / 2.) + 0.001, 10); | |
| 137 |
3/6✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
|
1000 | normal.block<1, 3>(0, 0) = Vector3(0, 0, 1); |
| 138 |
3/6✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
|
1000 | position.block<1, 3>(0, 0) = Vector3(x, y, 0.); |
| 139 | |||
| 140 | std::pair<MatrixX3, VectorX> Ab = generateConstraints( | ||
| 141 |
7/14✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 500 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 500 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 500 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 500 times.
✗ Branch 20 not taken.
|
1000 | normal, position, Matrix3::Identity(), Vector3::Zero()); |
| 142 |
1/2✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
|
1000 | std::pair<Matrix3, Vector3> Hg = computeCost(); |
| 143 |
2/4✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
|
1000 | Vector3 init = Vector3::Zero(); |
| 144 |
4/8✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 500 times.
✗ Branch 11 not taken.
|
1000 | bezier_com_traj::ResultData res = bezier_com_traj::solve(Ab, Hg, init); |
| 145 |
6/12✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 500 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 500 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 500 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 500 times.
✗ Branch 18 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 500 times.
|
1000 | BOOST_CHECK(!res.success_); |
| 146 | 1000 | } | |
| 147 | 2 | } | |
| 148 | |||
| 149 | BOOST_AUTO_TEST_SUITE_END() | ||
| 150 |