Directory: | ./ |
---|---|
File: | unittest/geometry-model.cpp |
Date: | 2025-02-12 21:03:38 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 114 | 117 | 97.4% |
Branches: | 340 | 652 | 52.1% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | // | ||
2 | // Copyright (c) 2015-2022 CNRS INRIA | ||
3 | // | ||
4 | |||
5 | #include <iostream> | ||
6 | |||
7 | #include "pinocchio/multibody/model.hpp" | ||
8 | #include "pinocchio/multibody/data.hpp" | ||
9 | |||
10 | #include "pinocchio/multibody/geometry.hpp" | ||
11 | #include "pinocchio/parsers/urdf.hpp" | ||
12 | |||
13 | #include <vector> | ||
14 | #include <boost/test/unit_test.hpp> | ||
15 | |||
16 | using namespace pinocchio; | ||
17 | |||
18 | BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) | ||
19 | |||
20 |
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(manage_collision_pairs) |
21 | { | ||
22 | std::string filename = | ||
23 | PINOCCHIO_MODEL_DIR | ||
24 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
4 | + std::string("/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf"); |
25 | 2 | std::vector<std::string> package_dirs; | |
26 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | std::string mesh_dir = PINOCCHIO_MODEL_DIR; |
27 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | package_dirs.push_back(mesh_dir); |
28 | |||
29 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Model model; |
30 |
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 | pinocchio::urdf::buildModel(filename, pinocchio::JointModelFreeFlyer(), model); |
31 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | GeometryModel geom_model; |
32 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | pinocchio::urdf::buildGeom(model, filename, pinocchio::COLLISION, geom_model, package_dirs); |
33 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_model.addAllCollisionPairs(); |
34 | |||
35 |
2/2✓ Branch 0 taken 20 times.
✓ Branch 1 taken 1 times.
|
42 | for (Eigen::DenseIndex i = 0; i < (Eigen::DenseIndex)geom_model.ngeoms; ++i) |
36 | { | ||
37 |
2/2✓ Branch 0 taken 190 times.
✓ Branch 1 taken 20 times.
|
420 | for (Eigen::DenseIndex j = i + 1; j < (Eigen::DenseIndex)geom_model.ngeoms; ++j) |
38 | { | ||
39 |
7/14✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 190 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 190 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 190 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 190 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 190 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 190 times.
|
380 | BOOST_CHECK(geom_model.collisionPairMapping(i, j) < (int)geom_model.collisionPairs.size()); |
40 |
7/14✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 190 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 190 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 190 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 190 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 190 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 190 times.
|
380 | BOOST_CHECK(geom_model.collisionPairMapping(j, i) < (int)geom_model.collisionPairs.size()); |
41 |
8/16✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 190 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 190 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 190 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 190 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 190 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 190 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 190 times.
|
380 | BOOST_CHECK(geom_model.collisionPairMapping(j, i) == geom_model.collisionPairMapping(i, j)); |
42 | |||
43 |
2/4✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 190 times.
✗ Branch 4 not taken.
|
380 | if (geom_model.collisionPairMapping(i, j) != -1) |
44 | { | ||
45 |
1/2✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
|
380 | const PairIndex pair_index = (PairIndex)geom_model.collisionPairMapping(i, j); |
46 | 380 | const CollisionPair & cp_ref = geom_model.collisionPairs[pair_index]; | |
47 |
1/2✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
|
380 | const CollisionPair cp((size_t)i, (size_t)j); |
48 |
6/12✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 190 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 190 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 190 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 190 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 190 times.
|
380 | BOOST_CHECK(cp == cp_ref); |
49 | } | ||
50 | } | ||
51 | } | ||
52 | |||
53 | ✗ | GeometryModel::MatrixXb collision_map(GeometryModel::MatrixXb::Zero( | |
54 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | (Eigen::DenseIndex)geom_model.ngeoms, (Eigen::DenseIndex)geom_model.ngeoms)); |
55 | |||
56 |
2/2✓ Branch 1 taken 190 times.
✓ Branch 2 taken 1 times.
|
382 | for (size_t k = 0; k < geom_model.collisionPairs.size(); ++k) |
57 | { | ||
58 | 380 | const CollisionPair & cp = geom_model.collisionPairs[k]; | |
59 |
1/2✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
|
380 | collision_map((Eigen::DenseIndex)cp.first, (Eigen::DenseIndex)cp.second) = true; |
60 | } | ||
61 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | GeometryModel::MatrixXb collision_map_lower = collision_map.transpose(); |
62 | |||
63 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | GeometryModel geom_model_copy, geom_model_copy_lower; |
64 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | pinocchio::urdf::buildGeom(model, filename, pinocchio::COLLISION, geom_model_copy, package_dirs); |
65 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | pinocchio::urdf::buildGeom( |
66 | model, filename, pinocchio::COLLISION, geom_model_copy_lower, package_dirs); | ||
67 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_model_copy.setCollisionPairs(collision_map); |
68 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_model_copy_lower.setCollisionPairs(collision_map_lower, false); |
69 | |||
70 |
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(geom_model_copy.collisionPairs.size() == geom_model.collisionPairs.size()); |
71 |
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(geom_model_copy_lower.collisionPairs.size() == geom_model.collisionPairs.size()); |
72 |
2/2✓ Branch 1 taken 190 times.
✓ Branch 2 taken 1 times.
|
382 | for (size_t k = 0; k < geom_model_copy.collisionPairs.size(); ++k) |
73 | { | ||
74 |
7/14✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 190 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 190 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 190 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 190 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 190 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 190 times.
|
380 | BOOST_CHECK(geom_model.existCollisionPair(geom_model_copy.collisionPairs[k])); |
75 |
7/14✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 190 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 190 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 190 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 190 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 190 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 190 times.
|
380 | BOOST_CHECK(geom_model.existCollisionPair(geom_model_copy_lower.collisionPairs[k])); |
76 | } | ||
77 |
2/2✓ Branch 1 taken 190 times.
✓ Branch 2 taken 1 times.
|
382 | for (size_t k = 0; k < geom_model.collisionPairs.size(); ++k) |
78 | { | ||
79 |
7/14✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 190 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 190 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 190 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 190 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 190 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 190 times.
|
380 | BOOST_CHECK(geom_model_copy.existCollisionPair(geom_model.collisionPairs[k])); |
80 |
7/14✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 190 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 190 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 190 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 190 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 190 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 190 times.
|
380 | BOOST_CHECK(geom_model_copy_lower.existCollisionPair(geom_model.collisionPairs[k])); |
81 | } | ||
82 | |||
83 | { | ||
84 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | GeometryData geom_data(geom_model); |
85 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_data.activateAllCollisionPairs(); |
86 | |||
87 |
2/2✓ Branch 1 taken 190 times.
✓ Branch 2 taken 1 times.
|
382 | for (size_t k = 0; k < geom_data.activeCollisionPairs.size(); ++k) |
88 |
7/14✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 190 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 190 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 190 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 190 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 190 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 190 times.
|
380 | BOOST_CHECK(geom_data.activeCollisionPairs[k]); |
89 | 2 | } | |
90 | |||
91 | { | ||
92 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | GeometryData geom_data(geom_model); |
93 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_data.deactivateAllCollisionPairs(); |
94 | |||
95 |
2/2✓ Branch 1 taken 190 times.
✓ Branch 2 taken 1 times.
|
382 | for (size_t k = 0; k < geom_data.activeCollisionPairs.size(); ++k) |
96 |
7/14✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 190 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 190 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 190 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 190 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 190 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 190 times.
|
380 | BOOST_CHECK(!geom_data.activeCollisionPairs[k]); |
97 | 2 | } | |
98 | |||
99 | { | ||
100 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | GeometryData geom_data(geom_model), geom_data_copy(geom_model), |
101 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_data_copy_lower(geom_model); |
102 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_data_copy.deactivateAllCollisionPairs(); |
103 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_data_copy_lower.deactivateAllCollisionPairs(); |
104 | |||
105 | ✗ | GeometryData::MatrixXb collision_map(GeometryModel::MatrixXb::Zero( | |
106 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | (Eigen::DenseIndex)geom_model.ngeoms, (Eigen::DenseIndex)geom_model.ngeoms)); |
107 |
2/2✓ Branch 1 taken 190 times.
✓ Branch 2 taken 1 times.
|
382 | for (size_t k = 0; k < geom_data.activeCollisionPairs.size(); ++k) |
108 | { | ||
109 | 380 | const CollisionPair & cp = geom_model.collisionPairs[k]; | |
110 |
1/2✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
|
380 | collision_map((Eigen::DenseIndex)cp.first, (Eigen::DenseIndex)cp.second) = |
111 |
1/2✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
|
760 | geom_data.activeCollisionPairs[k]; |
112 | } | ||
113 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | GeometryData::MatrixXb collision_map_lower = collision_map.transpose(); |
114 | |||
115 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_data_copy.setActiveCollisionPairs(geom_model, collision_map); |
116 |
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(geom_data_copy.activeCollisionPairs == geom_data.activeCollisionPairs); |
117 | |||
118 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_data_copy_lower.setActiveCollisionPairs(geom_model, collision_map_lower, false); |
119 |
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(geom_data_copy_lower.activeCollisionPairs == geom_data.activeCollisionPairs); |
120 | 2 | } | |
121 | |||
122 | // Test security margins | ||
123 | { | ||
124 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | GeometryData geom_data_upper(geom_model), geom_data_lower(geom_model); |
125 | |||
126 | ✗ | const GeometryData::MatrixXs security_margin_map(GeometryData::MatrixXs::Ones( | |
127 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | (Eigen::DenseIndex)geom_model.ngeoms, (Eigen::DenseIndex)geom_model.ngeoms)); |
128 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | GeometryData::MatrixXs security_margin_map_upper(security_margin_map); |
129 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | security_margin_map_upper.triangularView<Eigen::Lower>().fill(0.); |
130 | |||
131 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_data_upper.setSecurityMargins(geom_model, security_margin_map, true, true); |
132 |
2/2✓ Branch 1 taken 190 times.
✓ Branch 2 taken 1 times.
|
382 | for (size_t k = 0; k < geom_data_upper.collisionRequests.size(); ++k) |
133 | { | ||
134 |
6/12✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 190 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 190 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 190 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 190 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 190 times.
|
380 | BOOST_CHECK(geom_data_upper.collisionRequests[k].security_margin == 1.); |
135 |
6/12✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 190 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 190 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 190 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 190 times.
✗ Branch 20 not taken.
✗ Branch 24 not taken.
✓ Branch 25 taken 190 times.
|
380 | BOOST_CHECK( |
136 | geom_data_upper.collisionRequests[k].security_margin | ||
137 | == geom_data_upper.collisionRequests[k].distance_upper_bound); | ||
138 | } | ||
139 | |||
140 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_data_lower.setSecurityMargins(geom_model, security_margin_map, false); |
141 |
2/2✓ Branch 1 taken 190 times.
✓ Branch 2 taken 1 times.
|
382 | for (size_t k = 0; k < geom_data_lower.collisionRequests.size(); ++k) |
142 | { | ||
143 |
6/12✓ Branch 1 taken 190 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 190 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 190 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 190 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 190 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 190 times.
|
380 | BOOST_CHECK(geom_data_lower.collisionRequests[k].security_margin == 1.); |
144 | } | ||
145 | 2 | } | |
146 | |||
147 | // Test enableGeometryCollision | ||
148 | { | ||
149 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | GeometryData geom_data(geom_model); |
150 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_data.deactivateAllCollisionPairs(); |
151 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_data.setGeometryCollisionStatus(geom_model, 0, true); |
152 | |||
153 |
2/2✓ Branch 1 taken 190 times.
✓ Branch 2 taken 1 times.
|
382 | for (size_t k = 0; k < geom_data.activeCollisionPairs.size(); ++k) |
154 | { | ||
155 | 380 | const CollisionPair & cp = geom_model.collisionPairs[k]; | |
156 |
3/4✓ Branch 0 taken 171 times.
✓ Branch 1 taken 19 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 171 times.
|
380 | if (cp.first == 0 || cp.second == 0) |
157 | { | ||
158 |
7/14✓ Branch 1 taken 19 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 19 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 19 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 19 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 19 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 19 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 19 times.
|
38 | BOOST_CHECK(geom_data.activeCollisionPairs[k]); |
159 | } | ||
160 | else | ||
161 | { | ||
162 |
7/14✓ Branch 1 taken 171 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 171 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 171 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 171 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 171 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 171 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 171 times.
|
342 | BOOST_CHECK(!geom_data.activeCollisionPairs[k]); |
163 | } | ||
164 | } | ||
165 | 2 | } | |
166 | |||
167 | // Test disableGeometryCollision | ||
168 | { | ||
169 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | GeometryData geom_data(geom_model); |
170 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_data.activateAllCollisionPairs(); |
171 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_data.setGeometryCollisionStatus(geom_model, 0, false); |
172 | |||
173 |
2/2✓ Branch 1 taken 190 times.
✓ Branch 2 taken 1 times.
|
382 | for (size_t k = 0; k < geom_data.activeCollisionPairs.size(); ++k) |
174 | { | ||
175 | 380 | const CollisionPair & cp = geom_model.collisionPairs[k]; | |
176 |
3/4✓ Branch 0 taken 171 times.
✓ Branch 1 taken 19 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 171 times.
|
380 | if (cp.first == 0 || cp.second == 0) |
177 | { | ||
178 |
7/14✓ Branch 1 taken 19 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 19 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 19 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 19 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 19 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 19 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 19 times.
|
38 | BOOST_CHECK(!geom_data.activeCollisionPairs[k]); |
179 | } | ||
180 | else | ||
181 | { | ||
182 |
7/14✓ Branch 1 taken 171 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 171 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 171 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 171 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 171 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 171 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 171 times.
|
342 | BOOST_CHECK(geom_data.activeCollisionPairs[k]); |
183 | } | ||
184 | } | ||
185 | 2 | } | |
186 | 2 | } | |
187 | |||
188 |
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_clone) |
189 | { | ||
190 | std::string filename = | ||
191 | PINOCCHIO_MODEL_DIR | ||
192 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
4 | + std::string("/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf"); |
193 | 2 | std::vector<std::string> package_dirs; | |
194 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | std::string mesh_dir = PINOCCHIO_MODEL_DIR; |
195 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | package_dirs.push_back(mesh_dir); |
196 | |||
197 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Model model; |
198 |
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 | pinocchio::urdf::buildModel(filename, pinocchio::JointModelFreeFlyer(), model); |
199 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | GeometryModel geom_model; |
200 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | pinocchio::urdf::buildGeom(model, filename, pinocchio::COLLISION, geom_model, package_dirs); |
201 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_model.addAllCollisionPairs(); |
202 | |||
203 | 2 | geom_model.geometryObjects[0].geometry = | |
204 |
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 | GeometryObject::CollisionGeometryPtr(new ::hpp::fcl::Sphere(0.5)); |
205 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | GeometryModel geom_model_clone = geom_model.clone(); |
206 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | GeometryModel geom_model_copy = geom_model; |
207 | |||
208 |
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(geom_model_clone == geom_model); |
209 |
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(geom_model_copy == geom_model); |
210 | |||
211 | 2 | static_cast<::hpp::fcl::Sphere *>(geom_model.geometryObjects[0].geometry.get())->radius = 1.; | |
212 |
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(geom_model_clone != geom_model); |
213 |
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(geom_model_copy == geom_model); |
214 | 2 | } | |
215 | |||
216 | BOOST_AUTO_TEST_SUITE_END() | ||
217 |