Directory: | ./ |
---|---|
File: | unittest/broadphase.cpp |
Date: | 2025-02-12 21:03:38 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 91 | 91 | 100.0% |
Branches: | 359 | 714 | 50.3% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | // | ||
2 | // Copyright (c) 2022 INRIA | ||
3 | // | ||
4 | |||
5 | #include <iostream> | ||
6 | |||
7 | #include "pinocchio/algorithm/geometry.hpp" | ||
8 | #include "pinocchio/parsers/urdf.hpp" | ||
9 | #include "pinocchio/parsers/srdf.hpp" | ||
10 | |||
11 | #include "pinocchio/collision/collision.hpp" | ||
12 | #include "pinocchio/collision/distance.hpp" | ||
13 | #include "pinocchio/collision/broadphase-manager.hpp" | ||
14 | #include "pinocchio/collision/broadphase.hpp" | ||
15 | |||
16 | #include <hpp/fcl/broadphase/broadphase_dynamic_AABB_tree.h> | ||
17 | |||
18 | #include <vector> | ||
19 | #include <boost/test/unit_test.hpp> | ||
20 | |||
21 | using namespace pinocchio; | ||
22 | |||
23 | BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) | ||
24 | |||
25 |
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_broadphase_with_empty_models) |
26 | { | ||
27 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Model model; |
28 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | GeometryModel geom_model; |
29 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | GeometryData geom_data(geom_model); |
30 | |||
31 | BroadPhaseManagerTpl<hpp::fcl::DynamicAABBTreeCollisionManager> broadphase_manager( | ||
32 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | &model, &geom_model, &geom_data); |
33 | |||
34 |
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()); |
35 | 2 | } | |
36 | |||
37 |
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_broadphase) |
38 | { | ||
39 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Model model; |
40 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Data data(model); |
41 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | GeometryModel geom_model; |
42 | |||
43 |
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 | hpp::fcl::CollisionGeometryPtr_t sphere_ptr(new hpp::fcl::Sphere(0.5)); |
44 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | sphere_ptr->computeLocalAABB(); |
45 |
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 | hpp::fcl::CollisionGeometryPtr_t box_ptr(new hpp::fcl::Box(0.5, 0.5, 0.5)); |
46 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | box_ptr->computeLocalAABB(); |
47 | |||
48 |
9/18✓ 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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 25 taken 1 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 1 times.
✗ Branch 29 not taken.
|
4 | GeometryObject obj1("obj1", 0, SE3::Identity(), sphere_ptr); |
49 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | const GeomIndex obj1_index = geom_model.addGeometryObject(obj1); |
50 | |||
51 |
9/18✓ 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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 25 taken 1 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 1 times.
✗ Branch 29 not taken.
|
4 | GeometryObject obj2("obj2", 0, SE3::Identity(), box_ptr); |
52 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | const GeomIndex obj2_index = geom_model.addGeometryObject(obj2); |
53 | |||
54 | 2 | GeometryObject & go = geom_model.geometryObjects[obj1_index]; | |
55 | |||
56 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | GeometryData geom_data(geom_model); |
57 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | updateGeometryPlacements(model, data, geom_model, geom_data); |
58 | |||
59 | BroadPhaseManagerTpl<hpp::fcl::DynamicAABBTreeCollisionManager> broadphase_manager( | ||
60 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | &model, &geom_model, &geom_data); |
61 |
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()); |
62 |
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(sphere_ptr.get() == go.geometry.get()); |
63 | |||
64 |
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 | hpp::fcl::CollisionGeometryPtr_t sphere_new_ptr(new hpp::fcl::Sphere(5.)); |
65 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | sphere_new_ptr->computeLocalAABB(); |
66 | 2 | go.geometry = sphere_new_ptr; | |
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(!broadphase_manager.check()); |
68 |
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(sphere_ptr.get() != go.geometry.get()); |
69 |
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 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK( |
70 | broadphase_manager.getCollisionObjects()[obj1_index].collisionGeometry().get() | ||
71 | == sphere_ptr.get()); | ||
72 |
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 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK( |
73 | broadphase_manager.getCollisionObjects()[obj2_index].collisionGeometry().get() | ||
74 | == box_ptr.get()); | ||
75 | // BOOST_CHECK(broadphase_manager.getObjects()[obj1_index]->collisionGeometry().get() == | ||
76 | // sphere_ptr.get()); | ||
77 |
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 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK( |
78 | broadphase_manager.getCollisionObjects()[obj1_index].collisionGeometry().get() | ||
79 | != go.geometry.get()); | ||
80 |
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(sphere_new_ptr.get() == go.geometry.get()); |
81 | |||
82 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | broadphase_manager.update(false); |
83 |
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 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK( |
84 | broadphase_manager.getCollisionObjects()[obj1_index].collisionGeometry().get() | ||
85 | != sphere_ptr.get()); | ||
86 |
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 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK( |
87 | broadphase_manager.getCollisionObjects()[obj1_index].collisionGeometry().get() | ||
88 | == go.geometry.get()); | ||
89 | // BOOST_CHECK(broadphase_manager.getObjects()[obj_index]->collisionGeometry().get() == | ||
90 | // go.geometry.get()); | ||
91 | |||
92 |
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()); |
93 | 2 | } | |
94 | |||
95 |
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_advanced_filters) |
96 | { | ||
97 | const std::string filename = | ||
98 | PINOCCHIO_MODEL_DIR | ||
99 |
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"); |
100 | 2 | std::vector<std::string> packageDirs; | |
101 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | const std::string meshDir = PINOCCHIO_MODEL_DIR; |
102 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | packageDirs.push_back(meshDir); |
103 | const std::string srdf_filename = | ||
104 | PINOCCHIO_MODEL_DIR | ||
105 |
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"); |
106 | |||
107 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Model model; |
108 |
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); |
109 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | GeometryModel geom_model; |
110 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | pinocchio::urdf::buildGeom(model, filename, pinocchio::COLLISION, geom_model, packageDirs); |
111 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_model.addAllCollisionPairs(); |
112 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::srdf::removeCollisionPairs(model, geom_model, srdf_filename, false); |
113 | |||
114 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | GeometryData geom_data(geom_model); |
115 | |||
116 | typedef BroadPhaseManagerTpl<hpp::fcl::DynamicAABBTreeCollisionManager> BroadPhaseManager; | ||
117 |
2/2✓ Branch 0 taken 33 times.
✓ Branch 1 taken 1 times.
|
68 | for (size_t joint_id = 0; joint_id < (size_t)model.njoints; ++joint_id) |
118 | { | ||
119 | 66 | const GeometryObjectFilterSelectByJoint filter(joint_id); | |
120 |
1/2✓ Branch 1 taken 33 times.
✗ Branch 2 not taken.
|
66 | BroadPhaseManager manager(&model, &geom_model, &geom_data, filter); |
121 |
7/14✓ Branch 1 taken 33 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 33 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 33 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 33 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 33 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 33 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 33 times.
|
66 | BOOST_CHECK(manager.check()); |
122 | 66 | } | |
123 | 2 | } | |
124 | |||
125 |
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) |
126 | { | ||
127 | const std::string filename = | ||
128 | PINOCCHIO_MODEL_DIR | ||
129 |
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"); |
130 | 2 | std::vector<std::string> packageDirs; | |
131 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | const std::string meshDir = PINOCCHIO_MODEL_DIR; |
132 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | packageDirs.push_back(meshDir); |
133 | const std::string srdf_filename = | ||
134 | PINOCCHIO_MODEL_DIR | ||
135 |
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"); |
136 | |||
137 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Model model; |
138 |
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); |
139 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | GeometryModel geom_model; |
140 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | pinocchio::urdf::buildGeom(model, filename, pinocchio::COLLISION, geom_model, packageDirs); |
141 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | geom_model.addAllCollisionPairs(); |
142 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::srdf::removeCollisionPairs(model, geom_model, srdf_filename, false); |
143 | |||
144 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Data data(model); |
145 |
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); |
146 | |||
147 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::srdf::loadReferenceConfigurations(model, srdf_filename, false); |
148 |
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"]; |
149 | |||
150 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::updateGeometryPlacements(model, data, geom_model, geom_data, q); |
151 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::updateGeometryPlacements(model, data, geom_model, geom_data_broadphase, q); |
152 | |||
153 |
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); |
154 |
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); |
155 | |||
156 | BroadPhaseManagerTpl<hpp::fcl::DynamicAABBTreeCollisionManager> broadphase_manager( | ||
157 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | &model, &geom_model, &geom_data_broadphase); |
158 |
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 | std::cout << "map:\n" << geom_model.collisionPairMapping << std::endl; |
159 |
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); |
160 |
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); |
161 |
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_manager, q) == false); |
162 |
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_manager, q, false) == false); |
163 | |||
164 | 2 | const int num_configs = 1000; | |
165 |
2/2✓ Branch 0 taken 1000 times.
✓ Branch 1 taken 1 times.
|
2002 | for (int i = 0; i < num_configs; ++i) |
166 | { | ||
167 |
1/2✓ Branch 1 taken 1000 times.
✗ Branch 2 not taken.
|
2000 | Eigen::VectorXd q_rand = randomConfiguration(model); |
168 |
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>(); |
169 | |||
170 |
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( |
171 | computeCollisions(model, data, broadphase_manager, q_rand) | ||
172 | == computeCollisions(model, data, geom_model, geom_data, q_rand)); | ||
173 | 2000 | } | |
174 | 2 | } | |
175 | |||
176 | BOOST_AUTO_TEST_SUITE_END() | ||
177 |