Directory: | ./ |
---|---|
File: | tests/test-oriented-triangles1.cc |
Date: | 2025-03-07 12:08:39 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 37 | 37 | 100.0% |
Branches: | 83 | 160 | 51.9% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | // Copyright (C) 2016 LAAS-CNRS | ||
2 | // Author: Anna Seppala | ||
3 | // | ||
4 | // This file is part of the hpp-affordance. | ||
5 | // | ||
6 | // hpp-affordance is free software: you can redistribute it and/or modify | ||
7 | // it under the terms of the GNU Lesser General Public License as published by | ||
8 | // the Free Software Foundation, either version 3 of the License, or | ||
9 | // (at your option) any later version. | ||
10 | // | ||
11 | // hpp-affordance is distributed in the hope that it will be useful, | ||
12 | // but WITHOUT ANY WARRANTY; without even the implied warranty of | ||
13 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the | ||
14 | // GNU Lesser General Public License for more details. | ||
15 | // | ||
16 | // You should have received a copy of the GNU Lesser General Public License | ||
17 | // along with hpp-affordance. If not, see <http://www.gnu.org/licenses/>. | ||
18 | |||
19 | #include <coal/BVH/BVH_model.h> | ||
20 | #include <coal/shape/geometric_shape_to_BVH_model.h> | ||
21 | |||
22 | #include <hpp/affordance/affordance-extraction.hh> | ||
23 | #include <hpp/affordance/operations.hh> | ||
24 | |||
25 | #define BOOST_TEST_MODULE test - oriented - triangles1 | ||
26 | #include <boost/test/included/unit_test.hpp> | ||
27 | |||
28 | using namespace hpp; | ||
29 | |||
30 | BOOST_AUTO_TEST_SUITE(test_affordance) | ||
31 | |||
32 |
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(oriented_triangles1) { |
33 | hpp::affordance::SupportOperationPtr_t support( | ||
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 | new hpp::affordance::SupportOperation()); |
35 | hpp::affordance::LeanOperationPtr_t lean( | ||
36 |
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 | new hpp::affordance::LeanOperation(0.1)); |
37 | |||
38 | 2 | std::vector<hpp::affordance::OperationBasePtr_t> operations; | |
39 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | operations.push_back(support); |
40 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | operations.push_back(lean); |
41 | |||
42 | 2 | std::vector<coal::Vec3f> vertices; | |
43 | 2 | std::vector<coal::Triangle> triangles; | |
44 | |||
45 | typedef coal::BVHModel<coal::OBBRSS> Model; | ||
46 | |||
47 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | coal::Vec3f vert1(0, 0, 0); |
48 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | coal::Vec3f vert2(1, 0, 0); |
49 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | coal::Vec3f vert3(0, 1, 0); |
50 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | vertices.push_back(vert1); |
51 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | vertices.push_back(vert2); |
52 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | vertices.push_back(vert3); |
53 | |||
54 | 2 | int size_ = 8; | |
55 | 2 | int affFound = 0; | |
56 | 2 | int affNotFound = 0; | |
57 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | coal::Vec3f T(0, 0, 0); |
58 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | coal::Vec3f axis(1, 0, 0); |
59 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | coal::Matrix3f R; |
60 | |||
61 |
2/2✓ Branch 0 taken 8 times.
✓ Branch 1 taken 1 times.
|
18 | for (int i = 0; i < size_; ++i) { |
62 |
3/6✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 8 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 8 times.
✗ Branch 8 not taken.
|
16 | coal::shared_ptr<Model> model(new Model()); |
63 |
1/2✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
|
16 | coal::Triangle tri(0, 1, 2); |
64 |
1/2✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
|
16 | triangles.push_back(tri); |
65 | |||
66 |
2/4✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 8 times.
✗ Branch 5 not taken.
|
16 | R = Eigen::AngleAxisd(3.1416 * double(5 * i) / 180.0, axis); |
67 | |||
68 |
1/2✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
|
16 | coal::Transform3s pose(R, T); |
69 | |||
70 |
1/2✓ Branch 2 taken 8 times.
✗ Branch 3 not taken.
|
16 | model->beginModel(); |
71 |
1/2✓ Branch 2 taken 8 times.
✗ Branch 3 not taken.
|
16 | model->addSubModel(vertices, triangles); |
72 |
1/2✓ Branch 2 taken 8 times.
✗ Branch 3 not taken.
|
16 | model->endModel(); |
73 | |||
74 |
2/4✓ Branch 2 taken 8 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 8 times.
✗ Branch 6 not taken.
|
16 | coal::CollisionObject* obj(new coal::CollisionObject(model, pose)); |
75 | |||
76 | hpp::affordance::SemanticsDataPtr_t h = | ||
77 |
1/2✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
|
16 | hpp::affordance::affordanceAnalysis(obj, operations); |
78 | |||
79 |
5/6✓ Branch 3 taken 7 times.
✓ Branch 4 taken 1 times.
✓ Branch 8 taken 7 times.
✗ Branch 9 not taken.
✓ Branch 10 taken 7 times.
✓ Branch 11 taken 1 times.
|
16 | if (h->affordances_[0].size() == 1 && h->affordances_[1].size() == 0) { |
80 | 14 | affFound += 1; | |
81 | } else { | ||
82 | 2 | affNotFound += 1; | |
83 | } | ||
84 | 16 | } | |
85 |
12/24✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 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.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 1 times.
✗ Branch 30 not taken.
✓ Branch 32 taken 1 times.
✗ Branch 33 not taken.
✗ Branch 41 not taken.
✓ Branch 42 taken 1 times.
|
2 | BOOST_CHECK_MESSAGE(affFound == 7 && affNotFound == 1, |
86 | "Strictly six support affordances should have been found " | ||
87 | "and one rejected. Now " | ||
88 | << affFound << "were found and " << affNotFound | ||
89 | << " rejected."); | ||
90 | 2 | } | |
91 | BOOST_AUTO_TEST_SUITE_END() | ||
92 |