Directory: | ./ |
---|---|
File: | tests/multithread.cc |
Date: | 2025-05-05 12:19:30 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 38 | 38 | 100.0% |
Branches: | 113 | 222 | 50.9% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | // Copyright (c) 2016, 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 multithread_test | ||
30 | |||
31 | #include <stdlib.h> | ||
32 | |||
33 | #include <../tests/convex-shape-contact-function.hh> | ||
34 | #include <../tests/util.hh> | ||
35 | #include <hpp/constraints/configuration-constraint.hh> | ||
36 | #include <hpp/constraints/convex-shape-contact.hh> | ||
37 | #include <hpp/constraints/generic-transformation.hh> | ||
38 | #include <hpp/pinocchio/device.hh> | ||
39 | #include <hpp/pinocchio/simple-device.hh> | ||
40 | #include <pinocchio/fwd.hpp> | ||
41 | |||
42 | using hpp::pinocchio::Configuration_t; | ||
43 | using hpp::pinocchio::ConfigurationPtr_t; | ||
44 | using hpp::pinocchio::Device; | ||
45 | using hpp::pinocchio::DevicePtr_t; | ||
46 | using hpp::pinocchio::JointPtr_t; | ||
47 | using hpp::pinocchio::Transform3s; | ||
48 | |||
49 | using namespace hpp::constraints; | ||
50 | |||
51 |
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(multithread) { |
52 | DevicePtr_t device = hpp::pinocchio::unittest::makeDevice( | ||
53 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
4 | hpp::pinocchio::unittest::HumanoidSimple); |
54 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | device->numberDeviceData(4); |
55 |
2/4✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
|
4 | JointPtr_t ee1 = device->getJointByName("lleg5_joint"), |
56 |
2/4✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
|
4 | ee2 = device->getJointByName("rleg5_joint"); |
57 |
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_REQUIRE(device); |
58 | |||
59 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Configuration_t q; |
60 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | randomConfig(device, q); |
61 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | device->currentConfiguration(q); |
62 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | device->computeForwardKinematics(hpp::pinocchio::JOINT_POSITION); |
63 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | Transform3s tf1(ee1->currentTransformation()); |
64 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | Transform3s tf2(ee2->currentTransformation()); |
65 | |||
66 | 2 | std::vector<DifferentiableFunctionPtr_t> functions; | |
67 |
4/8✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
|
4 | functions.push_back(ConfigurationConstraint::create( |
68 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | "Configuration", device, device->currentConfiguration())); |
69 |
4/8✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
|
2 | functions.push_back(Orientation::create("Orientation", device, ee2, tf2)); |
70 |
4/8✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
|
2 | functions.push_back(Position::create("Position", device, ee2, tf2, tf1)); |
71 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | functions.push_back( |
72 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
4 | Transformation::create("Transformation", device, ee1, tf1)); |
73 |
4/8✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
|
2 | functions.push_back(RelativeOrientation::create("RelativeOrientation", device, |
74 | ee1, ee2, tf1)); | ||
75 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | functions.push_back( |
76 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
|
4 | RelativePosition::create("RelativePosition", device, ee1, ee2, tf1, tf2)); |
77 |
4/8✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
|
2 | functions.push_back(RelativeTransformation::create( |
78 | "RelativeTransformation", device, ee1, ee2, tf1, tf2)); | ||
79 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
|
2 | functions.push_back(createConvexShapeContact_triangles( |
80 | device, ee1, "ConvexShapeContact triangle")); | ||
81 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
|
2 | functions.push_back(createConvexShapeContact_punctual( |
82 | device, ee1, "ConvexShapeContact punctual")); | ||
83 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
|
2 | functions.push_back(createConvexShapeContact_convex( |
84 | device, ee1, "ConvexShapeContact convex")); | ||
85 | |||
86 | 2 | const int N = 100; | |
87 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | randomConfig(device, q); |
88 |
2/2✓ Branch 1 taken 10 times.
✓ Branch 2 taken 1 times.
|
22 | for (std::size_t i = 0; i < functions.size(); ++i) { |
89 | 20 | DifferentiableFunctionPtr_t f = functions[i]; | |
90 | |||
91 |
2/4✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 10 times.
✗ Branch 8 not taken.
|
40 | std::vector<LiegroupElement> vs(N, LiegroupElement(f->outputSpace())); |
92 | std::vector<matrix_t> Js( | ||
93 |
2/4✓ Branch 6 taken 10 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 10 times.
✗ Branch 10 not taken.
|
40 | N, matrix_t(f->outputDerivativeSize(), f->inputDerivativeSize())); |
94 | 20 | #pragma omp parallel for | |
95 | for (int j = 0; j < N; ++j) { | ||
96 | f->value(vs[j], q); | ||
97 | f->jacobian(Js[j], q); | ||
98 | } | ||
99 | |||
100 |
2/2✓ Branch 0 taken 990 times.
✓ Branch 1 taken 10 times.
|
2000 | for (int j = 1; j < N; ++j) { |
101 |
5/10✓ Branch 1 taken 990 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 990 times.
✗ Branch 6 not taken.
✓ Branch 14 taken 990 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 990 times.
✗ Branch 18 not taken.
✗ Branch 21 not taken.
✓ Branch 22 taken 990 times.
|
1980 | BOOST_CHECK_EQUAL(vs[0].vector(), vs[j].vector()); |
102 |
5/10✓ Branch 1 taken 990 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 990 times.
✗ Branch 6 not taken.
✓ Branch 12 taken 990 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 990 times.
✗ Branch 16 not taken.
✗ Branch 19 not taken.
✓ Branch 20 taken 990 times.
|
1980 | BOOST_CHECK_EQUAL(Js[0], Js[j]); |
103 | } | ||
104 | 20 | } | |
105 | 2 | } | |
106 |