| Directory: | ./ |
|---|---|
| File: | tests/configuration-shooters.cc |
| Date: | 2025-03-10 11:18:21 |
| Exec | Total | Coverage | |
|---|---|---|---|
| Lines: | 44 | 44 | 100.0% |
| Branches: | 175 | 344 | 50.9% |
| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | // Copyright (c) 2018, Joseph Mirabel | ||
| 2 | // Authors: Joseph Mirabel (joseph.mirabel@laas.fr) | ||
| 3 | // | ||
| 4 | |||
| 5 | // Redistribution and use in source and binary forms, with or without | ||
| 6 | // modification, are permitted provided that the following conditions are | ||
| 7 | // met: | ||
| 8 | // | ||
| 9 | // 1. Redistributions of source code must retain the above copyright | ||
| 10 | // notice, this list of conditions and the following disclaimer. | ||
| 11 | // | ||
| 12 | // 2. Redistributions in binary form must reproduce the above copyright | ||
| 13 | // notice, this list of conditions and the following disclaimer in the | ||
| 14 | // documentation and/or other materials provided with the distribution. | ||
| 15 | // | ||
| 16 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS | ||
| 17 | // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT | ||
| 18 | // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR | ||
| 19 | // A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT | ||
| 20 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, | ||
| 21 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT | ||
| 22 | // LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, | ||
| 23 | // DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY | ||
| 24 | // THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT | ||
| 25 | // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE | ||
| 26 | // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH | ||
| 27 | // DAMAGE. | ||
| 28 | |||
| 29 | #define BOOST_TEST_MODULE configuration_shooters | ||
| 30 | #include <boost/test/included/unit_test.hpp> | ||
| 31 | #include <hpp/core/configuration-shooter/gaussian.hh> | ||
| 32 | #include <hpp/core/configuration-shooter/uniform-tpl.hh> | ||
| 33 | #include <hpp/core/configuration-shooter/uniform.hh> | ||
| 34 | #include <hpp/pinocchio/configuration.hh> | ||
| 35 | #include <hpp/pinocchio/device.hh> | ||
| 36 | #include <hpp/pinocchio/simple-device.hh> | ||
| 37 | #include <hpp/pinocchio/urdf/util.hh> | ||
| 38 | #include <pinocchio/fwd.hpp> | ||
| 39 | #include <pinocchio/multibody/model.hpp> | ||
| 40 | |||
| 41 | using hpp::pinocchio::DevicePtr_t; | ||
| 42 | |||
| 43 | using namespace hpp::core::configurationShooter; | ||
| 44 | |||
| 45 | namespace pin_test = hpp::pinocchio::unittest; | ||
| 46 | |||
| 47 | 1 | hpp::pinocchio::DevicePtr_t makeDevice() { | |
| 48 | using namespace hpp::pinocchio; | ||
| 49 | |||
| 50 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | DevicePtr_t device = Device::create("test"); |
| 51 |
6/12✓ 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 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
|
1 | urdf::loadModelFromString(device, 0, "", "prismatic_x", |
| 52 | "<robot name='n'><link name='base_link'/></robot>", | ||
| 53 | ""); | ||
| 54 | |||
| 55 | 1 | return device; | |
| 56 | } | ||
| 57 | |||
| 58 | template <typename CS_t> | ||
| 59 | 6 | void basic_test(CS_t cs, DevicePtr_t robot) { | |
| 60 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
6 | hpp::core::Configuration_t q; |
| 61 |
2/2✓ Branch 1 taken 30 times.
✓ Branch 2 taken 3 times.
|
66 | for (int i = 0; i < 10; ++i) { |
| 62 |
1/2✓ Branch 2 taken 30 times.
✗ Branch 3 not taken.
|
60 | cs->shoot(q); |
| 63 |
2/4✓ Branch 2 taken 30 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 30 times.
✗ Branch 6 not taken.
|
60 | hpp::pinocchio::ArrayXb unused(robot->numberDof()); |
| 64 |
8/16✓ Branch 1 taken 30 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 30 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 30 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 30 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 30 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 30 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 30 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 30 times.
|
60 | BOOST_CHECK(!hpp::pinocchio::saturate(robot, q, unused)); |
| 65 | } | ||
| 66 | 6 | } | |
| 67 | |||
| 68 |
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(uniform) { |
| 69 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
4 | DevicePtr_t robot = pin_test::makeDevice(pin_test::HumanoidSimple); |
| 70 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | UniformPtr_t cs = Uniform::create(robot); |
| 71 | |||
| 72 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | basic_test(cs, robot); |
| 73 | 2 | } | |
| 74 | |||
| 75 |
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(gaussian) { |
| 76 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
4 | DevicePtr_t robot = pin_test::makeDevice(pin_test::HumanoidSimple); |
| 77 | |||
| 78 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | GaussianPtr_t cs = Gaussian::create(robot); |
| 79 | |||
| 80 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | basic_test(cs, robot); |
| 81 | |||
| 82 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | cs->sigma(0); |
| 83 | |||
| 84 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | hpp::core::Configuration_t q; |
| 85 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | cs->shoot(q); |
| 86 |
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(q.isApprox(cs->center())); |
| 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(uniform_seedable) { |
| 90 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | DevicePtr_t robot = makeDevice(); |
| 91 | |||
| 92 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | robot->model().lowerPositionLimit[0] = -1.0; |
| 93 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | robot->model().upperPositionLimit[0] = 1.0; |
| 94 | |||
| 95 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | UniformSeedable::Ptr_t shooter = UniformSeedable::create(robot); |
| 96 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | basic_test(shooter, robot); |
| 97 | |||
| 98 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | hpp::core::Configuration_t q; |
| 99 | |||
| 100 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | hpp::core::vector_t shoots(100); |
| 101 | |||
| 102 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | shooter->seed(0); |
| 103 |
2/2✓ Branch 1 taken 100 times.
✓ Branch 2 taken 1 times.
|
202 | for (int i = 0; i < shoots.size(); ++i) { |
| 104 |
1/2✓ Branch 2 taken 100 times.
✗ Branch 3 not taken.
|
200 | shooter->shoot(q); |
| 105 |
2/4✓ Branch 1 taken 100 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 100 times.
✗ Branch 5 not taken.
|
200 | shoots[i] = q[0]; |
| 106 |
6/12✓ Branch 1 taken 100 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 100 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 100 times.
✗ Branch 9 not taken.
✓ Branch 13 taken 100 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 100 times.
✗ Branch 17 not taken.
✗ Branch 20 not taken.
✓ Branch 21 taken 100 times.
|
200 | BOOST_CHECK_LE(q[0], 1.0); |
| 107 |
6/12✓ Branch 1 taken 100 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 100 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 100 times.
✗ Branch 9 not taken.
✓ Branch 13 taken 100 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 100 times.
✗ Branch 17 not taken.
✗ Branch 20 not taken.
✓ Branch 21 taken 100 times.
|
200 | BOOST_CHECK_GE(q[0], -1.0); |
| 108 | } | ||
| 109 | |||
| 110 | // Check that setting the seed gives the same sequence of random values. | ||
| 111 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | shooter->seed(0); |
| 112 |
2/2✓ Branch 1 taken 100 times.
✓ Branch 2 taken 1 times.
|
202 | for (int i = 0; i < shoots.size(); ++i) { |
| 113 |
1/2✓ Branch 2 taken 100 times.
✗ Branch 3 not taken.
|
200 | shooter->shoot(q); |
| 114 |
7/14✓ Branch 1 taken 100 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 100 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 100 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 100 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 100 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 100 times.
✗ Branch 20 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 100 times.
|
200 | BOOST_CHECK_EQUAL(shoots[i], q[0]); |
| 115 | } | ||
| 116 | 2 | } | |
| 117 |