geometry-model.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2022 CNRS INRIA
3 //
4 
5 #include <iostream>
6 
9 
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 BOOST_AUTO_TEST_CASE(manage_collision_pairs)
21 {
22  std::string filename =
24  + std::string("/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
25  std::vector<std::string> package_dirs;
26  std::string mesh_dir = PINOCCHIO_MODEL_DIR;
27  package_dirs.push_back(mesh_dir);
28 
29  Model model;
33  geom_model.addAllCollisionPairs();
34 
35  for (Eigen::DenseIndex i = 0; i < (Eigen::DenseIndex)geom_model.ngeoms; ++i)
36  {
37  for (Eigen::DenseIndex j = i + 1; j < (Eigen::DenseIndex)geom_model.ngeoms; ++j)
38  {
39  BOOST_CHECK(geom_model.collisionPairMapping(i, j) < (int)geom_model.collisionPairs.size());
40  BOOST_CHECK(geom_model.collisionPairMapping(j, i) < (int)geom_model.collisionPairs.size());
41  BOOST_CHECK(geom_model.collisionPairMapping(j, i) == geom_model.collisionPairMapping(i, j));
42 
43  if (geom_model.collisionPairMapping(i, j) != -1)
44  {
45  const PairIndex pair_index = (PairIndex)geom_model.collisionPairMapping(i, j);
46  const CollisionPair & cp_ref = geom_model.collisionPairs[pair_index];
47  const CollisionPair cp((size_t)i, (size_t)j);
48  BOOST_CHECK(cp == cp_ref);
49  }
50  }
51  }
52 
53  GeometryModel::MatrixXb collision_map(GeometryModel::MatrixXb::Zero(
54  (Eigen::DenseIndex)geom_model.ngeoms, (Eigen::DenseIndex)geom_model.ngeoms));
55 
56  for (size_t k = 0; k < geom_model.collisionPairs.size(); ++k)
57  {
58  const CollisionPair & cp = geom_model.collisionPairs[k];
59  collision_map((Eigen::DenseIndex)cp.first, (Eigen::DenseIndex)cp.second) = true;
60  }
61  GeometryModel::MatrixXb collision_map_lower = collision_map.transpose();
62 
63  GeometryModel geom_model_copy, geom_model_copy_lower;
66  model, filename, pinocchio::COLLISION, geom_model_copy_lower, package_dirs);
67  geom_model_copy.setCollisionPairs(collision_map);
68  geom_model_copy_lower.setCollisionPairs(collision_map_lower, false);
69 
70  BOOST_CHECK(geom_model_copy.collisionPairs.size() == geom_model.collisionPairs.size());
71  BOOST_CHECK(geom_model_copy_lower.collisionPairs.size() == geom_model.collisionPairs.size());
72  for (size_t k = 0; k < geom_model_copy.collisionPairs.size(); ++k)
73  {
74  BOOST_CHECK(geom_model.existCollisionPair(geom_model_copy.collisionPairs[k]));
75  BOOST_CHECK(geom_model.existCollisionPair(geom_model_copy_lower.collisionPairs[k]));
76  }
77  for (size_t k = 0; k < geom_model.collisionPairs.size(); ++k)
78  {
79  BOOST_CHECK(geom_model_copy.existCollisionPair(geom_model.collisionPairs[k]));
80  BOOST_CHECK(geom_model_copy_lower.existCollisionPair(geom_model.collisionPairs[k]));
81  }
82 
83  {
85  geom_data.activateAllCollisionPairs();
86 
87  for (size_t k = 0; k < geom_data.activeCollisionPairs.size(); ++k)
88  BOOST_CHECK(geom_data.activeCollisionPairs[k]);
89  }
90 
91  {
93  geom_data.deactivateAllCollisionPairs();
94 
95  for (size_t k = 0; k < geom_data.activeCollisionPairs.size(); ++k)
96  BOOST_CHECK(!geom_data.activeCollisionPairs[k]);
97  }
98 
99  {
100  GeometryData geom_data(geom_model), geom_data_copy(geom_model),
101  geom_data_copy_lower(geom_model);
102  geom_data_copy.deactivateAllCollisionPairs();
103  geom_data_copy_lower.deactivateAllCollisionPairs();
104 
105  GeometryData::MatrixXb collision_map(GeometryModel::MatrixXb::Zero(
106  (Eigen::DenseIndex)geom_model.ngeoms, (Eigen::DenseIndex)geom_model.ngeoms));
107  for (size_t k = 0; k < geom_data.activeCollisionPairs.size(); ++k)
108  {
109  const CollisionPair & cp = geom_model.collisionPairs[k];
110  collision_map((Eigen::DenseIndex)cp.first, (Eigen::DenseIndex)cp.second) =
111  geom_data.activeCollisionPairs[k];
112  }
113  GeometryData::MatrixXb collision_map_lower = collision_map.transpose();
114 
115  geom_data_copy.setActiveCollisionPairs(geom_model, collision_map);
116  BOOST_CHECK(geom_data_copy.activeCollisionPairs == geom_data.activeCollisionPairs);
117 
118  geom_data_copy_lower.setActiveCollisionPairs(geom_model, collision_map_lower, false);
119  BOOST_CHECK(geom_data_copy_lower.activeCollisionPairs == geom_data.activeCollisionPairs);
120  }
121 
122  // Test security margins
123  {
124  GeometryData geom_data_upper(geom_model), geom_data_lower(geom_model);
125 
126  const GeometryData::MatrixXs security_margin_map(GeometryData::MatrixXs::Ones(
127  (Eigen::DenseIndex)geom_model.ngeoms, (Eigen::DenseIndex)geom_model.ngeoms));
128  GeometryData::MatrixXs security_margin_map_upper(security_margin_map);
129  security_margin_map_upper.triangularView<Eigen::Lower>().fill(0.);
130 
131  geom_data_upper.setSecurityMargins(geom_model, security_margin_map, true, true);
132  for (size_t k = 0; k < geom_data_upper.collisionRequests.size(); ++k)
133  {
134  BOOST_CHECK(geom_data_upper.collisionRequests[k].security_margin == 1.);
135  BOOST_CHECK(
136  geom_data_upper.collisionRequests[k].security_margin
137  == geom_data_upper.collisionRequests[k].distance_upper_bound);
138  }
139 
140  geom_data_lower.setSecurityMargins(geom_model, security_margin_map, false);
141  for (size_t k = 0; k < geom_data_lower.collisionRequests.size(); ++k)
142  {
143  BOOST_CHECK(geom_data_lower.collisionRequests[k].security_margin == 1.);
144  }
145  }
146 
147  // Test enableGeometryCollision
148  {
150  geom_data.deactivateAllCollisionPairs();
151  geom_data.setGeometryCollisionStatus(geom_model, 0, true);
152 
153  for (size_t k = 0; k < geom_data.activeCollisionPairs.size(); ++k)
154  {
155  const CollisionPair & cp = geom_model.collisionPairs[k];
156  if (cp.first == 0 || cp.second == 0)
157  {
158  BOOST_CHECK(geom_data.activeCollisionPairs[k]);
159  }
160  else
161  {
162  BOOST_CHECK(!geom_data.activeCollisionPairs[k]);
163  }
164  }
165  }
166 
167  // Test disableGeometryCollision
168  {
170  geom_data.activateAllCollisionPairs();
171  geom_data.setGeometryCollisionStatus(geom_model, 0, false);
172 
173  for (size_t k = 0; k < geom_data.activeCollisionPairs.size(); ++k)
174  {
175  const CollisionPair & cp = geom_model.collisionPairs[k];
176  if (cp.first == 0 || cp.second == 0)
177  {
178  BOOST_CHECK(!geom_data.activeCollisionPairs[k]);
179  }
180  else
181  {
182  BOOST_CHECK(geom_data.activeCollisionPairs[k]);
183  }
184  }
185  }
186 }
187 
189 {
190  std::string filename =
192  + std::string("/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
193  std::vector<std::string> package_dirs;
194  std::string mesh_dir = PINOCCHIO_MODEL_DIR;
195  package_dirs.push_back(mesh_dir);
196 
197  Model model;
201  geom_model.addAllCollisionPairs();
202 
203  geom_model.geometryObjects[0].geometry =
205  GeometryModel geom_model_clone = geom_model.clone();
206  GeometryModel geom_model_copy = geom_model;
207 
208  BOOST_CHECK(geom_model_clone == geom_model);
209  BOOST_CHECK(geom_model_copy == geom_model);
210 
211  static_cast<::hpp::fcl::Sphere *>(geom_model.geometryObjects[0].geometry.get())->radius = 1.;
212  BOOST_CHECK(geom_model_clone != geom_model);
213  BOOST_CHECK(geom_model_copy == geom_model);
214 }
215 
216 BOOST_AUTO_TEST_SUITE_END()
pinocchio::GeometryData::MatrixXs
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
Definition: multibody/geometry.hpp:248
pinocchio::GeometryData::setActiveCollisionPairs
void setActiveCollisionPairs(const GeometryModel &geom_model, const MatrixXb &collision_map, const bool upper=true)
Set the collision pair association from a given input array. Each entry of the input matrix defines t...
pinocchio::GeometryData::MatrixXb
Eigen::Matrix< bool, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXb
Definition: multibody/geometry.hpp:247
inverse-kinematics.i
int i
Definition: inverse-kinematics.py:17
model.hpp
hpp::fcl::Sphere
pinocchio::JointModelFreeFlyerTpl
Definition: multibody/joint/fwd.hpp:110
append-urdf-model-with-another-model.mesh_dir
string mesh_dir
Definition: append-urdf-model-with-another-model.py:15
pinocchio::GeometryData
Definition: multibody/geometry.hpp:233
pinocchio::GeometryModel::existCollisionPair
bool existCollisionPair(const CollisionPair &pair) const
Check if a collision pair exists in collisionPairs. See also findCollisitionPair(const CollisionPair ...
Sphere
Sphere()
pinocchio::CollisionPair
Definition: multibody/geometry.hpp:21
append-urdf-model-with-another-model.package_dirs
package_dirs
Definition: append-urdf-model-with-another-model.py:20
pinocchio::GeometryData::activeCollisionPairs
std::vector< bool > activeCollisionPairs
Vector of collision pairs.
Definition: multibody/geometry.hpp:267
filename
filename
urdf.hpp
data.hpp
pinocchio::PairIndex
Index PairIndex
Definition: multibody/fwd.hpp:29
geometry.hpp
pinocchio::urdf::buildModel
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, const std::string &rootJointName, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
Build the model from a URDF file with a particular joint as root of the model tree inside the model g...
pinocchio::GeometryData::deactivateAllCollisionPairs
void deactivateAllCollisionPairs()
Deactivate all collision pairs.
pinocchio::urdf::buildGeom
GeometryModel & buildGeom(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const GeometryType type, GeometryModel &geom_model, const std::vector< std::string > &package_paths=std::vector< std::string >(), ::hpp::fcl::MeshLoaderPtr mesh_loader=::hpp::fcl::MeshLoaderPtr())
Build The GeometryModel from a URDF file. Search for meshes in the directories specified by the user ...
append-urdf-model-with-another-model.geom_model
geom_model
Definition: append-urdf-model-with-another-model.py:26
collisions.cp
cp
Definition: collisions.py:51
collisions.geom_data
geom_data
Definition: collisions.py:42
fill
fill
pinocchio::GeometryModel::collisionPairs
CollisionPairVector collisionPairs
Vector of collision pairs.
Definition: multibody/geometry.hpp:220
pinocchio::GeometryModel::MatrixXb
Eigen::Matrix< bool, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXb
Definition: multibody/geometry.hpp:67
pinocchio::GeometryModel
Definition: multibody/geometry.hpp:50
pinocchio::COLLISION
@ COLLISION
Definition: multibody/geometry-object.hpp:27
pinocchio::GeometryObject::CollisionGeometryPtr
std::shared_ptr< fcl::CollisionGeometry > CollisionGeometryPtr
Definition: multibody/geometry-object.hpp:102
pinocchio::GeometryModel::setCollisionPairs
void setCollisionPairs(const MatrixXb &collision_map, const bool upper=true)
Set the collision pairs from a given input array. Each entry of the input matrix defines the activati...
pinocchio::ModelTpl
Definition: context/generic.hpp:20
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(manage_collision_pairs)
Definition: geometry-model.cpp:20
radius
FCL_REAL radius
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1082
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
PINOCCHIO_MODEL_DIR
#define PINOCCHIO_MODEL_DIR
Definition: build-reduced-model.cpp:11


pinocchio
Author(s):
autogenerated on Thu Dec 19 2024 03:41:29