GCC Code Coverage Report


Directory: ./
File: unittest/geometry-algorithms.cpp
Date: 2025-02-12 21:03:38
Exec Total Coverage
Lines: 197 197 100.0%
Branches: 703 1400 50.2%

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/algorithm/kinematics.hpp"
12 #include "pinocchio/collision/collision.hpp"
13 #include "pinocchio/algorithm/geometry.hpp"
14 #include "pinocchio/parsers/urdf.hpp"
15 #include "pinocchio/parsers/srdf.hpp"
16
17 #include <vector>
18 #include <boost/test/unit_test.hpp>
19
20 using namespace pinocchio;
21
22 typedef std::map<std::string, pinocchio::SE3> PositionsMap_t;
23 typedef std::map<std::string, pinocchio::SE3> JointPositionsMap_t;
24 typedef std::map<std::string, pinocchio::SE3> GeometryPositionsMap_t;
25 typedef std::map<std::pair<std::string, std::string>, fcl::DistanceResult> PairDistanceMap_t;
26 JointPositionsMap_t
27 fillPinocchioJointPositions(const pinocchio::Model & model, const pinocchio::Data & data);
28 GeometryPositionsMap_t fillPinocchioGeometryPositions(
29 const pinocchio::GeometryModel & geomModel, const pinocchio::GeometryData & geomData);
30
31 std::vector<std::string> getBodiesList();
32
33 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
34
35
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_simple_boxes)
36 {
37 using namespace pinocchio;
38
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model model;
39
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 GeometryModel geomModel;
40
41 Model::JointIndex idx;
42
5/10
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
6 idx = model.addJoint(
43
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
4 model.getJointId("universe"), JointModelPlanar(), SE3::Identity(), "planar1_joint");
44
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 model.addJointFrame(idx);
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 model.appendBodyToJoint(idx, Inertia::Random(), SE3::Identity());
46
3/6
✓ 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.
2 model.addBodyFrame("planar1_body", idx, SE3::Identity());
47
48
5/10
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
6 idx = model.addJoint(
49
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
4 model.getJointId("universe"), JointModelPlanar(), SE3::Identity(), "planar2_joint");
50
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 model.addJointFrame(idx);
51
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 model.appendBodyToJoint(idx, Inertia::Random(), SE3::Identity());
52
3/6
✓ 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.
2 model.addBodyFrame("planar2_body", idx, SE3::Identity());
53
54
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::shared_ptr<fcl::Box> sample(new fcl::Box(1, 1, 1));
55
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 Model::FrameIndex body_id_1 = model.getBodyId("planar1_body");
56 2 Model::JointIndex joint_parent_1 = model.frames[body_id_1].parentJoint;
57
10/20
✓ 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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 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.
10 Model::JointIndex idx_geom1 = geomModel.addGeometryObject(GeometryObject(
58
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
4 "ff1_collision_object", joint_parent_1, model.getBodyId("planar1_body"), SE3::Identity(),
59
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
4 sample, "", Eigen::Vector3d::Ones()));
60 2 geomModel.geometryObjects[idx_geom1].parentJoint = model.frames[body_id_1].parentJoint;
61
62
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::shared_ptr<fcl::Box> sample2(new fcl::Box(1, 1, 1));
63
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 Model::FrameIndex body_id_2 = model.getBodyId("planar2_body");
64 2 Model::JointIndex joint_parent_2 = model.frames[body_id_2].parentJoint;
65
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model::JointIndex idx_geom2 = geomModel.addGeometryObject(
66
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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 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.
12 GeometryObject(
67
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
4 "ff2_collision_object", joint_parent_2, model.getBodyId("planar2_body"), SE3::Identity(),
68
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
4 sample2, "", Eigen::Vector3d::Ones()),
69 model);
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(
71 geomModel.geometryObjects[idx_geom2].parentJoint == model.frames[body_id_2].parentJoint);
72
73
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::shared_ptr<fcl::Box> universe_body_geometry(new fcl::Box(1, 1, 1));
74
3/6
✓ 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.
2 model.addBodyFrame("universe_body", 0, SE3::Identity());
75
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 Model::FrameIndex body_id_3 = model.getBodyId("universe_body");
76 2 Model::JointIndex joint_parent_3 = model.frames[body_id_3].parentJoint;
77
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 SE3 universe_body_placement = SE3::Random();
78
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model::JointIndex idx_geom3 = geomModel.addGeometryObject(
79
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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 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.
8 GeometryObject(
80 "universe_collision_object", joint_parent_3, model.getBodyId("universe_body"),
81
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
4 universe_body_placement, universe_body_geometry, "", Eigen::Vector3d::Ones()),
82 model);
83
84
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(
85 geomModel.geometryObjects[idx_geom3].parentJoint == model.frames[body_id_3].parentJoint);
86
87
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 geomModel.addAllCollisionPairs();
88
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::Data data(model);
89
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::GeometryData geomData(geomModel);
90
91
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 15 taken 1 times.
✗ Branch 16 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(CollisionPair(0, 1) == geomModel.collisionPairs[0]);
92
93
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 std::cout << "------ Model ------ " << std::endl;
94
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 std::cout << model;
95
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 std::cout << "------ Geom ------ " << std::endl;
96
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 std::cout << geomModel;
97
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 std::cout << "------ DataGeom ------ " << std::endl;
98
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 std::cout << geomData;
99
100
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Eigen::VectorXd q(model.nq);
101
8/16
✓ 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.
✓ 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.
2 q << 0, 0, 1, 0, 0, 0, 1, 0;
102
103
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::updateGeometryPlacements(model, data, geomModel, geomData, q);
104
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 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 27 not taken.
✓ Branch 28 taken 1 times.
2 BOOST_CHECK(geomData.oMg[idx_geom3].isApprox(universe_body_placement));
105
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(computeCollision(geomModel, geomData, 0) == true);
106
107
8/16
✓ 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.
✓ 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.
2 q << 2, 0, 1, 0, 0, 0, 1, 0;
108
109
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::updateGeometryPlacements(model, data, geomModel, geomData, q);
110
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(computeCollision(geomModel, geomData, 0) == false);
111
112
8/16
✓ 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.
✓ 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.
2 q << 0.99, 0, 1, 0, 0, 0, 1, 0;
113
114
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::updateGeometryPlacements(model, data, geomModel, geomData, q);
115
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(computeCollision(geomModel, geomData, 0) == true);
116
117
8/16
✓ 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.
✓ 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.
2 q << 1.01, 0, 1, 0, 0, 0, 1, 0;
118
119
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::updateGeometryPlacements(model, data, geomModel, geomData, q);
120
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(computeCollision(geomModel, geomData, 0) == false);
121
122
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 geomModel.removeGeometryObject("ff2_collision_object");
123
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 geomData = pinocchio::GeometryData(geomModel);
124
125
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_CHECK(geomModel.ngeoms == 2);
126
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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 1 times.
2 BOOST_CHECK(geomModel.geometryObjects.size() == 2);
127
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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 1 times.
2 BOOST_CHECK(geomModel.collisionPairs.size() == 1);
128
8/20
✓ 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 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 20 not taken.
✗ Branch 21 not taken.
✗ Branch 23 not taken.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 1 times.
✗ Branch 30 not taken.
✗ Branch 34 not taken.
✓ Branch 35 taken 1 times.
2 BOOST_CHECK(
129 (geomModel.collisionPairs[0].first == 0 && geomModel.collisionPairs[0].second == 1)
130 || (geomModel.collisionPairs[0].first == 1 && geomModel.collisionPairs[0].second == 0));
131
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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 1 times.
2 BOOST_CHECK(geomData.activeCollisionPairs.size() == 1);
132
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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 1 times.
2 BOOST_CHECK(geomData.distanceRequests.size() == 1);
133
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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 1 times.
2 BOOST_CHECK(geomData.distanceResults.size() == 1);
134
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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 1 times.
2 BOOST_CHECK(geomData.distanceResults.size() == 1);
135
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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 1 times.
2 BOOST_CHECK(geomData.collisionResults.size() == 1);
136 2 }
137
138 #if defined(PINOCCHIO_WITH_URDFDOM)
139
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(loading_model_and_check_distance)
140 {
141 typedef pinocchio::Model Model;
142 typedef pinocchio::GeometryModel GeometryModel;
143 typedef pinocchio::Data Data;
144 typedef pinocchio::GeometryData GeometryData;
145
146 std::string filename =
147 PINOCCHIO_MODEL_DIR
148
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");
149 2 std::vector<std::string> packageDirs;
150
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 std::string meshDir = PINOCCHIO_MODEL_DIR;
151
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 packageDirs.push_back(meshDir);
152
153
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model model;
154
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);
155
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 GeometryModel geomModel;
156
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 pinocchio::urdf::buildGeom(model, filename, pinocchio::COLLISION, geomModel, packageDirs);
157
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 geomModel.addAllCollisionPairs();
158
159 GeometryModel geomModelOther =
160
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
4 pinocchio::urdf::buildGeom(model, filename, pinocchio::COLLISION, geomModel, packageDirs);
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(geomModelOther == geomModel);
162
163
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data(model);
164
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 GeometryData geomData(geomModel);
165
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 fcl::CollisionResult result;
166
167
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Eigen::VectorXd q(model.nq);
168
16/32
✓ 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.
✓ 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 25 taken 1 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 1 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 1 times.
✗ Branch 32 not taken.
✓ Branch 34 taken 1 times.
✗ Branch 35 not taken.
✓ Branch 37 taken 1 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 1 times.
✗ Branch 41 not taken.
✓ Branch 43 taken 1 times.
✗ Branch 44 not taken.
✓ Branch 46 taken 1 times.
✗ Branch 47 not taken.
2 q << 0, 0, 0.840252, 0, 0, 0, 1, 0, 0, -0.3490658, 0.6981317, -0.3490658, 0, 0, 0, -0.3490658,
169
17/34
✓ 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.
✓ 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 25 taken 1 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 1 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 1 times.
✗ Branch 32 not taken.
✓ Branch 34 taken 1 times.
✗ Branch 35 not taken.
✓ Branch 37 taken 1 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 1 times.
✗ Branch 41 not taken.
✓ Branch 43 taken 1 times.
✗ Branch 44 not taken.
✓ Branch 46 taken 1 times.
✗ Branch 47 not taken.
✓ Branch 49 taken 1 times.
✗ Branch 50 not taken.
2 0.6981317, -0.3490658, 0, 0, 1.5, 0.6, -0.5, -1.05, -0.4, -0.3, -0.2, 0, 0, 0, 0, 1.5, -0.6,
170
5/10
✓ 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.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
2 0.5, 1.05, -0.4, -0.3, -0.2;
171
172
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::updateGeometryPlacements(model, data, geomModel, geomData, q);
173
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 pinocchio::Index idx = geomModel.findCollisionPair(CollisionPair(1, 10));
174
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(computeCollision(geomModel, geomData, idx) == false);
175
176
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 fcl::DistanceResult distance_res = computeDistance(geomModel, geomData, idx);
177
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_CHECK(distance_res.min_distance > 0.);
178 2 }
179
180
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)
181 {
182 typedef pinocchio::Model Model;
183 typedef pinocchio::GeometryModel GeometryModel;
184 typedef pinocchio::Data Data;
185 typedef pinocchio::GeometryData GeometryData;
186
187 const std::string filename =
188 PINOCCHIO_MODEL_DIR
189
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");
190 2 std::vector<std::string> packageDirs;
191
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 const std::string meshDir = PINOCCHIO_MODEL_DIR;
192
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 packageDirs.push_back(meshDir);
193 const std::string srdf_filename =
194 PINOCCHIO_MODEL_DIR
195
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");
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, packageDirs);
201
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 geom_model.addAllCollisionPairs();
202
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::srdf::removeCollisionPairs(model, geom_model, srdf_filename, false);
203
204
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data(model);
205
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 GeometryData geom_data(geom_model);
206
207
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::srdf::loadReferenceConfigurations(model, srdf_filename, false);
208
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"];
209
210
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::updateGeometryPlacements(model, data, geom_model, geom_data, q);
211
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(computeCollisions(geom_model, geom_data) == false);
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(computeCollisions(geom_model, geom_data, false) == false);
214
215
2/2
✓ Branch 1 taken 70 times.
✓ Branch 2 taken 1 times.
142 for (size_t cp_index = 0; cp_index < geom_model.collisionPairs.size(); ++cp_index)
216 {
217 140 const CollisionPair & cp = geom_model.collisionPairs[cp_index];
218 140 const GeometryObject & obj1 = geom_model.geometryObjects[cp.first];
219 140 const GeometryObject & obj2 = geom_model.geometryObjects[cp.second];
220
221
1/2
✓ Branch 1 taken 70 times.
✗ Branch 2 not taken.
140 hpp::fcl::CollisionResult other_res;
222
1/2
✓ Branch 1 taken 70 times.
✗ Branch 2 not taken.
140 computeCollision(geom_model, geom_data, cp_index);
223
224
1/2
✓ Branch 2 taken 70 times.
✗ Branch 3 not taken.
140 fcl::Transform3f oM1(toFclTransform3f(geom_data.oMg[cp.first])),
225
1/2
✓ Branch 2 taken 70 times.
✗ Branch 3 not taken.
140 oM2(toFclTransform3f(geom_data.oMg[cp.second]));
226
227
1/2
✓ Branch 1 taken 70 times.
✗ Branch 2 not taken.
140 fcl::collide(
228 140 obj1.geometry.get(), oM1, obj2.geometry.get(), oM2, geom_data.collisionRequests[cp_index],
229 other_res);
230
231 140 const hpp::fcl::CollisionResult & res = geom_data.collisionResults[cp_index];
232
233
6/12
✓ Branch 1 taken 70 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 70 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 70 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 70 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 70 times.
✗ Branch 20 not taken.
✗ Branch 24 not taken.
✓ Branch 25 taken 70 times.
140 BOOST_CHECK(res.isCollision() == other_res.isCollision());
234
6/12
✓ Branch 1 taken 70 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 70 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 70 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 70 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 70 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 70 times.
140 BOOST_CHECK(!res.isCollision());
235 140 }
236
237 // test other signatures
238 {
239
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data(model);
240
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 GeometryData geom_data(geom_model);
241
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, geom_model, geom_data, q) == false);
242 2 }
243 2 }
244
245
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_distances)
246 {
247 typedef pinocchio::Model Model;
248 typedef pinocchio::GeometryModel GeometryModel;
249 typedef pinocchio::Data Data;
250 typedef pinocchio::GeometryData GeometryData;
251
252 const std::string filename =
253 PINOCCHIO_MODEL_DIR
254
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");
255 2 std::vector<std::string> packageDirs;
256
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 const std::string meshDir = PINOCCHIO_MODEL_DIR;
257
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 packageDirs.push_back(meshDir);
258 const std::string srdf_filename =
259 PINOCCHIO_MODEL_DIR
260
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");
261
262
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model model;
263
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);
264
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 GeometryModel geom_model;
265
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 pinocchio::urdf::buildGeom(model, filename, pinocchio::COLLISION, geom_model, packageDirs);
266
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 geom_model.addAllCollisionPairs();
267
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::srdf::removeCollisionPairs(model, geom_model, srdf_filename, false);
268
269
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data(model);
270
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 GeometryData geom_data(geom_model);
271
272
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::srdf::loadReferenceConfigurations(model, srdf_filename, false);
273
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"];
274
275
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::updateGeometryPlacements(model, data, geom_model, geom_data, q);
276
277
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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
2 BOOST_CHECK(computeDistances(geom_model, geom_data) < geom_model.collisionPairs.size());
278
279 {
280
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data(model);
281
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 GeometryData geom_data(geom_model);
282
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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
2 BOOST_CHECK(
283 computeDistances(model, data, geom_model, geom_data, q) < geom_model.collisionPairs.size());
284 2 }
285 2 }
286
287
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_append_geom_models)
288 {
289 typedef pinocchio::Model Model;
290 typedef pinocchio::GeometryModel GeometryModel;
291
292 const std::string filename =
293 PINOCCHIO_MODEL_DIR
294
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");
295 2 std::vector<std::string> packageDirs;
296
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 const std::string meshDir = PINOCCHIO_MODEL_DIR;
297
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 packageDirs.push_back(meshDir);
298
299
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model model;
300
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);
301
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 GeometryModel geom_model1;
302
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 pinocchio::urdf::buildGeom(model, filename, pinocchio::COLLISION, geom_model1, packageDirs);
303
304
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 GeometryModel geom_model2;
305
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 pinocchio::urdf::buildGeom(model, filename, pinocchio::COLLISION, geom_model2, packageDirs);
306
307
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 appendGeometryModel(geom_model2, geom_model1);
308
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_CHECK(geom_model2.ngeoms == 2 * geom_model1.ngeoms);
309
310 // Check that collision pairs between geoms on the same joint are discarded.
311
2/2
✓ Branch 1 taken 380 times.
✓ Branch 2 taken 1 times.
762 for (pinocchio::Index i = 0; i < geom_model2.collisionPairs.size(); ++i)
312 {
313 760 pinocchio::CollisionPair cp = geom_model2.collisionPairs[i];
314
5/10
✓ Branch 1 taken 380 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 380 times.
✗ Branch 6 not taken.
✓ Branch 12 taken 380 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 380 times.
✗ Branch 16 not taken.
✗ Branch 19 not taken.
✓ Branch 20 taken 380 times.
760 BOOST_CHECK_NE(
315 geom_model2.geometryObjects[cp.first].parentJoint,
316 geom_model2.geometryObjects[cp.second].parentJoint);
317 }
318
319 {
320
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 GeometryModel geom_model_empty;
321
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 GeometryModel geom_model;
322
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_CHECK(geom_model_empty.ngeoms == 0);
323
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 appendGeometryModel(geom_model, geom_model_empty);
324
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_CHECK(geom_model.ngeoms == 0);
325 2 }
326 2 }
327
328
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_compute_body_radius)
329 {
330 2 std::vector<std::string> packageDirs;
331
332 std::string filename =
333 PINOCCHIO_MODEL_DIR
334
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");
335
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 std::string meshDir = PINOCCHIO_MODEL_DIR;
336
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 packageDirs.push_back(meshDir);
337
338
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::Model model;
339
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);
340
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::GeometryModel geom;
341
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 pinocchio::urdf::buildGeom(model, filename, pinocchio::COLLISION, geom, packageDirs);
342
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data(model);
343
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 GeometryData geomData(geom);
344
345 // Test that the algorithm does not crash
346
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::computeBodyRadius(model, geom, geomData);
347
18/30
✓ 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.
✓ 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 33 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 33 times.
✗ Branch 23 not taken.
✓ Branch 24 taken 33 times.
✓ Branch 25 taken 33 times.
✓ Branch 26 taken 33 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 33 times.
✗ Branch 30 not taken.
✓ Branch 31 taken 34 times.
✗ Branch 32 not taken.
✓ Branch 34 taken 34 times.
✗ Branch 35 not taken.
✓ Branch 36 taken 33 times.
✓ Branch 37 taken 1 times.
✓ Branch 38 taken 33 times.
✓ Branch 39 taken 1 times.
134 BOOST_FOREACH (double radius, geomData.radius)
348
6/12
✓ 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 22 not taken.
✓ Branch 23 taken 33 times.
66 BOOST_CHECK(radius >= 0.);
349 2 }
350 #endif // if defined(PINOCCHIO_WITH_URDFDOM)
351
352 BOOST_AUTO_TEST_SUITE_END()
353