GCC Code Coverage Report


Directory: ./
File: unittest/tree-broadphase.cpp
Date: 2025-02-12 21:03:38
Exec Total Coverage
Lines: 39 39 100.0%
Branches: 158 314 50.3%

Line Branch Exec Source
1 //
2 // Copyright (c) 2022 INRIA
3 //
4
5 #include <iostream>
6
7 #include "pinocchio/collision/collision.hpp"
8 #include "pinocchio/collision/broadphase.hpp"
9 #include "pinocchio/collision/tree-broadphase-manager.hpp"
10 #include "pinocchio/parsers/urdf.hpp"
11 #include "pinocchio/parsers/srdf.hpp"
12
13 #include <hpp/fcl/broadphase/broadphase_dynamic_AABB_tree.h>
14
15 #include <vector>
16 #include <boost/test/unit_test.hpp>
17
18 using namespace pinocchio;
19
20 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
21
22
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_tree_broadphase_with_empty_models)
23 {
24
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model model;
25
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 GeometryModel geom_model;
26
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 GeometryData geom_data(geom_model);
27
28 TreeBroadPhaseManagerTpl<hpp::fcl::DynamicAABBTreeCollisionManager> broadphase_manager(
29
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 &model, &geom_model, &geom_data);
30
31
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(broadphase_manager.check());
32 2 }
33
34
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_collisions)
35 {
36 const std::string filename =
37 PINOCCHIO_MODEL_DIR
38
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");
39 2 std::vector<std::string> packageDirs;
40
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 const std::string meshDir = PINOCCHIO_MODEL_DIR;
41
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 packageDirs.push_back(meshDir);
42 const std::string srdf_filename =
43 PINOCCHIO_MODEL_DIR
44
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/srdf/romeo.srdf");
45
46
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model model;
47
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);
48
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 GeometryModel geom_model;
49
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 pinocchio::urdf::buildGeom(model, filename, pinocchio::COLLISION, geom_model, packageDirs);
50
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 geom_model.addAllCollisionPairs();
51
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::srdf::removeCollisionPairs(model, geom_model, srdf_filename, false);
52
53
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 Data data(model), data_broadphase(model);
54
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_broadphase(geom_model);
55
56
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::srdf::loadReferenceConfigurations(model, srdf_filename, false);
57
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
4 Eigen::VectorXd q = model.referenceConfigurations["half_sitting"];
58
59
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::updateGeometryPlacements(model, data, geom_model, geom_data, q);
60
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::updateGeometryPlacements(model, data_broadphase, geom_model, geom_data_broadphase, q);
61
62
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(computeCollisions(geom_model, geom_data) == false);
63
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(computeCollisions(geom_model, geom_data, false) == false);
64
65 TreeBroadPhaseManagerTpl<hpp::fcl::DynamicAABBTreeCollisionManager> broadphase_manager(
66
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 &model, &geom_model, &geom_data_broadphase);
67
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(computeCollisions(broadphase_manager) == false);
68
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(computeCollisions(broadphase_manager, false) == false);
69
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(computeCollisions(model, data_broadphase, broadphase_manager, q) == false);
70
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(computeCollisions(model, data_broadphase, broadphase_manager, q, false) == false);
71
72 2 const int num_configs = 1000;
73
2/2
✓ Branch 0 taken 1000 times.
✓ Branch 1 taken 1 times.
2002 for (int i = 0; i < num_configs; ++i)
74 {
75
1/2
✓ Branch 1 taken 1000 times.
✗ Branch 2 not taken.
2000 Eigen::VectorXd q_rand = randomConfiguration(model);
76
3/6
✓ Branch 1 taken 1000 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1000 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1000 times.
✗ Branch 8 not taken.
2000 q_rand.head<7>() = q.head<7>();
77
78
8/16
✓ Branch 1 taken 1000 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1000 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1000 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1000 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1000 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1000 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1000 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 1000 times.
2000 BOOST_CHECK(
79 computeCollisions(model, data_broadphase, broadphase_manager, q_rand)
80 == computeCollisions(model, data, geom_model, geom_data, q_rand));
81 2000 }
82 2 }
83
84 BOOST_AUTO_TEST_SUITE_END()
85