GCC Code Coverage Report


Directory: ./
File: bindings/python/parsers/sdf/geometry.cpp
Date: 2025-02-12 21:03:38
Exec Total Coverage
Lines: 2 2 100.0%
Branches: 0 0 -%

Line Branch Exec Source
1 //
2 // Copyright (c) 2020-2021 CNRS INRIA
3 //
4
5 #ifdef PINOCCHIO_WITH_SDFORMAT
6 #include "pinocchio/parsers/sdf.hpp"
7 #endif
8 #include "pinocchio/bindings/python/parsers/sdf.hpp"
9 #include "pinocchio/bindings/python/utils/path.hpp"
10
11 #include <boost/python.hpp>
12
13 namespace pinocchio
14 {
15 namespace python
16 {
17
18 namespace bp = boost::python;
19
20 #ifdef PINOCCHIO_WITH_SDFORMAT
21 GeometryModel
22 buildGeomFromSdf(const Model & model, const bp::object & filename, const GeometryType type)
23 {
24 GeometryModel geometry_model;
25 const std::string & rootLinkName = "";
26 const std::string & packageDir = "";
27 pinocchio::sdf::buildGeom(
28 model, path(filename), type, geometry_model, rootLinkName, packageDir);
29 return geometry_model;
30 }
31
32 GeometryModel buildGeomFromSdf(
33 const Model & model,
34 const bp::object & filename,
35 const GeometryType type,
36 const std::string & rootLinkName)
37 {
38 GeometryModel geometry_model;
39 const std::string & packageDir = "";
40 pinocchio::sdf::buildGeom(
41 model, path(filename), type, geometry_model, rootLinkName, packageDir);
42 return geometry_model;
43 }
44
45 GeometryModel & buildGeomFromSdf(
46 const Model & model,
47 const bp::object & filename,
48 const GeometryType type,
49 GeometryModel & geometry_model,
50 const std::string & rootLinkName)
51 {
52 pinocchio::sdf::buildGeom(model, path(filename), type, geometry_model, rootLinkName);
53 return geometry_model;
54 }
55
56 GeometryModel buildGeomFromSdf(
57 const Model & model,
58 const bp::object & filename,
59 const GeometryType type,
60 const std::string & rootLinkName,
61 const bp::object & package_dirs)
62 {
63 GeometryModel geometry_model;
64 if (PyList_Check(package_dirs.ptr()))
65 {
66 pinocchio::sdf::buildGeom(
67 model, path(filename), type, geometry_model, rootLinkName, pathList(package_dirs));
68 }
69 else
70 {
71 const std::vector<std::string> dirs(1, path(package_dirs));
72 pinocchio::sdf::buildGeom(model, path(filename), type, geometry_model, rootLinkName, dirs);
73 }
74
75 return geometry_model;
76 }
77
78 GeometryModel & buildGeomFromSdf(
79 const Model & model,
80 const bp::object & filename,
81 const GeometryType type,
82 GeometryModel & geometry_model,
83 const std::string & rootLinkName,
84 const bp::object & package_dir)
85 {
86 if (PyList_Check(package_dir.ptr()))
87 {
88 pinocchio::sdf::buildGeom(
89 model, path(filename), type, geometry_model, rootLinkName, pathList(package_dir));
90 }
91 else
92 {
93 pinocchio::sdf::buildGeom(
94 model, path(filename), type, geometry_model, rootLinkName, path(package_dir));
95 }
96 return geometry_model;
97 }
98
99 GeometryModel buildGeomFromSdf(
100 const Model & model,
101 const bp::object & filename,
102 const GeometryType type,
103 const std::string & rootLinkName,
104 const hpp::fcl::MeshLoaderPtr & meshLoader)
105 {
106 std::vector<std::string> hints;
107 GeometryModel geometry_model;
108 pinocchio::sdf::buildGeom(
109 model, path(filename), type, geometry_model, rootLinkName, hints, meshLoader);
110 return geometry_model;
111 }
112
113 GeometryModel & buildGeomFromSdf(
114 const Model & model,
115 const bp::object & filename,
116 const GeometryType type,
117 GeometryModel & geometry_model,
118 const std::string & rootLinkName,
119 const hpp::fcl::MeshLoaderPtr & meshLoader)
120 {
121 std::vector<std::string> hints;
122 pinocchio::sdf::buildGeom(
123 model, path(filename), type, geometry_model, rootLinkName, hints, meshLoader);
124 return geometry_model;
125 }
126
127 GeometryModel buildGeomFromSdf(
128 const Model & model,
129 const bp::object & filename,
130 const GeometryType type,
131 const std::string & rootLinkName,
132 const bp::object & package_dir,
133 const hpp::fcl::MeshLoaderPtr & meshLoader)
134 {
135 GeometryModel geometry_model;
136 if (PyList_Check(package_dir.ptr()))
137 {
138 pinocchio::sdf::buildGeom(
139 model, path(filename), type, geometry_model, rootLinkName, pathList(package_dir),
140 meshLoader);
141 }
142 else
143 {
144 pinocchio::sdf::buildGeom(
145 model, path(filename), type, geometry_model, rootLinkName, path(package_dir), meshLoader);
146 }
147 return geometry_model;
148 }
149
150 GeometryModel & buildGeomFromSdf(
151 const Model & model,
152 const bp::object & filename,
153 const GeometryType type,
154 GeometryModel & geometry_model,
155 const std::string & rootLinkName,
156 const bp::object & package_dir,
157 const hpp::fcl::MeshLoaderPtr & meshLoader)
158 {
159 if (PyList_Check(package_dir.ptr()))
160 {
161 pinocchio::sdf::buildGeom(
162 model, path(filename), type, geometry_model, rootLinkName, pathList(package_dir),
163 meshLoader);
164 }
165 else
166 {
167 pinocchio::sdf::buildGeom(
168 model, path(filename), type, geometry_model, rootLinkName, path(package_dir), meshLoader);
169 }
170 return geometry_model;
171 }
172
173 #endif // #ifdef PINOCCHIO_WITH_SDFORMAT
174
175 65 void exposeSDFGeometry()
176 {
177 #ifdef PINOCCHIO_WITH_SDFORMAT
178
179 bp::def(
180 "buildGeomFromSdf",
181 static_cast<GeometryModel (*)(const Model &, const bp::object &, const GeometryType)>(
182 pinocchio::python::buildGeomFromSdf),
183 bp::args("model", "sdf_filename", "geom_type"),
184 "Parse the SDF file given as input looking for the geometry of the given input model and\n"
185 "return a GeometryModel containing either the collision geometries "
186 "(GeometryType.COLLISION) or the visual geometries (GeometryType.VISUAL).\n"
187 "Parameters:\n"
188 "\tmodel: model of the robot\n"
189 "\tsdf_filename: path to the SDF file containing the model of the robot\n"
190 "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
191 "or the COLLISION for collision detection).\n");
192
193 bp::def(
194 "buildGeomFromSdf",
195 static_cast<GeometryModel (*)(
196 const Model &, const bp::object &, const GeometryType, const std::string &,
197 const bp::object &)>(pinocchio::python::buildGeomFromSdf),
198 bp::args("model", "sdf_filename", "geom_type", "root_link_name", "package_dir"),
199 "Parse the SDF file given as input looking for the geometry of the given input model and\n"
200 "return a GeometryModel containing either the collision geometries "
201 "(GeometryType.COLLISION) or the visual geometries (GeometryType.VISUAL).\n"
202 "Parameters:\n"
203 "\tmodel: model of the robot\n"
204 "\tsdf_filename: path to the SDF file containing the model of the robot\n"
205 "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
206 "or the COLLISION for collision detection).\n"
207 "\tpackage_dir: path or vector of path pointing to the folder containing the meshes of the "
208 "robot\n");
209
210 bp::def(
211 "buildGeomFromSdf",
212 static_cast<GeometryModel (*)(
213 const Model &, const bp::object &, const GeometryType, const std::string &)>(
214 pinocchio::python::buildGeomFromSdf),
215 bp::args("model", "sdf_filename", "geom_type", "root_link_name"),
216 "Parse the SDF file given as input looking for the geometry of the given input model and\n"
217 "return a GeometryModel containing either the collision geometries "
218 "(GeometryType.COLLISION) or the visual geometries (GeometryType.VISUAL).\n"
219 "Parameters:\n"
220 "\tmodel: model of the robot\n"
221 "\tsdf_filename: path to the SDF file containing the model of the robot\n"
222 "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
223 "or the COLLISION for collision detection).\n"
224 "Note:\n"
225 "This function does not take any hint concerning the location of the meshes of the robot.");
226
227 bp::def(
228 "buildGeomFromSdf",
229 static_cast<GeometryModel & (*)(const Model &, const bp::object &, const GeometryType,
230 GeometryModel &, const std::string &)>(
231 pinocchio::python::buildGeomFromSdf),
232 bp::args("model", "sdf_filename", "geom_type", "geom_model", "root_link_name"),
233 "Parse the SDF file given as input looking for the geometry of the given input model and\n"
234 "and store either the collision geometries (GeometryType.COLLISION) or the visual "
235 "geometries (GeometryType.VISUAL) in the geom_model given as input.\n"
236 "Parameters:\n"
237 "\tmodel: model of the robot\n"
238 "\tsdf_filename: path to the SDF file containing the model of the robot\n"
239 "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
240 "or the COLLISION for collision detection).\n"
241 "\tgeom_model: reference where to store the parsed information\n"
242 "Note:\n"
243 "This function does not take any hint concerning the location of the meshes of the robot.",
244 bp::return_internal_reference<4>());
245
246 bp::def(
247 "buildGeomFromSdf",
248 static_cast<GeometryModel & (*)(const Model &, const bp::object &, const GeometryType,
249 GeometryModel &, const std::string &, const bp::object &)>(
250 pinocchio::python::buildGeomFromSdf),
251 bp::args(
252 "model", "sdf_filename", "geom_type", "geom_model", "root_link_name", "package_dir"),
253 "Parse the SDF file given as input looking for the geometry of the given input model and\n"
254 "and store either the collision geometries (GeometryType.COLLISION) or the visual "
255 "geometries (GeometryType.VISUAL) in the geom_model given as input.\n"
256 "Parameters:\n"
257 "\tmodel: model of the robot\n"
258 "\tsdf_filename: path to the SDF file containing the model of the robot\n"
259 "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
260 "or the COLLISION for collision detection).\n"
261 "\tgeom_model: reference where to store the parsed information\n"
262 "\tpackage_dir: path or vector of path pointing to the folder containing the meshes of the "
263 "robot\n",
264 bp::return_internal_reference<4>());
265
266 bp::def(
267 "buildGeomFromSdf",
268 static_cast<GeometryModel (*)(
269 const Model &, const bp::object &, const GeometryType, const std::string &,
270 const bp::object &, const hpp::fcl::MeshLoaderPtr &)>(
271 pinocchio::python::buildGeomFromSdf),
272 bp::args(
273 "model", "sdf_filename", "geom_type", "root_link_name", "package_dir", "mesh_loader"),
274 "Parse the SDF file given as input looking for the geometry of the given input model and\n"
275 "return a GeometryModel containing either the collision geometries "
276 "(GeometryType.COLLISION) or the visual geometries (GeometryType.VISUAL).\n"
277 "Parameters:\n"
278 "\tmodel: model of the robot\n"
279 "\tsdf_filename: path to the SDF file containing the model of the robot\n"
280 "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
281 "or the COLLISION for collision detection).\n"
282 "\tpackage_dir: path pointing to the folder containing the meshes of the robot\n"
283 "\tmesh_loader: an hpp-fcl mesh loader (to load only once the related geometries).");
284
285 bp::def(
286 "buildGeomFromSdf",
287 static_cast<GeometryModel & (*)(const Model &, const bp::object &, const GeometryType,
288 GeometryModel &, const std::string &, const bp::object &,
289 const hpp::fcl::MeshLoaderPtr &)>(
290 pinocchio::python::buildGeomFromSdf),
291 bp::args(
292 "model", "sdf_filename", "geom_type", "geom_model", "root_link_name", "package_dir",
293 "mesh_loader"),
294 "Parse the SDF file given as input looking for the geometry of the given input model and\n"
295 "and store either the collision geometries (GeometryType.COLLISION) or the visual "
296 "geometries (GeometryType.VISUAL) in the geom_model given as input.\n"
297 "Parameters:\n"
298 "\tmodel: model of the robot\n"
299 "\tsdf_filename: path to the SDF file containing the model of the robot\n"
300 "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
301 "or the COLLISION for collision detection).\n"
302 "\tgeom_model: reference where to store the parsed information\n"
303 "\tpackage_dir: path or vector of path pointing to the folder containing the meshes of the "
304 "robot\n"
305 "\tmesh_loader: an hpp-fcl mesh loader (to load only once the related geometries).",
306 bp::return_internal_reference<4>());
307
308 bp::def(
309 "buildGeomFromSdf",
310 static_cast<GeometryModel (*)(
311 const Model &, const bp::object &, const GeometryType, const std::string &,
312 const hpp::fcl::MeshLoaderPtr &)>(pinocchio::python::buildGeomFromSdf),
313 bp::args("model", "sdf_filename", "geom_type", "root_link_name", "mesh_loader"),
314 "Parse the SDF file given as input looking for the geometry of the given input model and\n"
315 "return a GeometryModel containing either the collision geometries "
316 "(GeometryType.COLLISION) or the visual geometries (GeometryType.VISUAL).\n"
317 "Parameters:\n"
318 "\tmodel: model of the robot\n"
319 "\tsdf_filename: path to the SDF file containing the model of the robot\n"
320 "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
321 "or the COLLISION for collision detection).\n"
322 "\tmesh_loader: an hpp-fcl mesh loader (to load only once the related geometries).\n"
323 "Note:\n"
324 "This function does not take any hint concerning the location of the meshes of the robot.");
325
326 bp::def(
327 "buildGeomFromSdf",
328 static_cast<GeometryModel & (*)(const Model &, const bp::object &, const GeometryType,
329 GeometryModel &, const std::string &,
330 const hpp::fcl::MeshLoaderPtr &)>(
331 pinocchio::python::buildGeomFromSdf),
332 bp::args(
333 "model", "sdf_filename", "geom_type", "geom_model", "root_link_name", "mesh_loader"),
334 "Parse the SDF file given as input looking for the geometry of the given input model and\n"
335 "and store either the collision geometries (GeometryType.COLLISION) or the visual "
336 "geometries (GeometryType.VISUAL) in the geom_model given as input.\n"
337 "Parameters:\n"
338 "\tmodel: model of the robot\n"
339 "\tsdf_filename: path to the SDF file containing the model of the robot\n"
340 "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
341 "or the COLLISION for collision detection).\n"
342 "\tgeom_model: reference where to store the parsed information\n"
343 "\tmesh_loader: an hpp-fcl mesh loader (to load only once the related geometries).\n"
344 "Note:\n"
345 "This function does not take any hint concerning the location of the meshes of the robot.",
346 bp::return_internal_reference<4>());
347 #endif
348 65 }
349 } // namespace python
350 } // namespace pinocchio
351