bindings/python/parsers/sdf/geometry.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2020-2021 CNRS INRIA
3 //
4 
5 #ifdef PINOCCHIO_WITH_SDFORMAT
7 #endif
9 
10 #include <boost/python.hpp>
11 
12 namespace pinocchio
13 {
14  namespace python
15  {
16 
17  namespace bp = boost::python;
18 
19 #ifdef PINOCCHIO_WITH_SDFORMAT
20 
21  GeometryModel
22  buildGeomFromSdf(const Model & model, const std::string & filename, const GeometryType type)
23  {
24  GeometryModel geometry_model;
25  const std::string & rootLinkName = "";
26  const std::string & packageDir = "";
27  pinocchio::sdf::buildGeom(model, filename, type, geometry_model, rootLinkName, packageDir);
28  return geometry_model;
29  }
30 
31  GeometryModel buildGeomFromSdf(
32  const Model & model,
33  const std::string & filename,
34  const GeometryType type,
35  const std::string & rootLinkName)
36  {
37  GeometryModel geometry_model;
38  const std::string & packageDir = "";
39  pinocchio::sdf::buildGeom(model, filename, type, geometry_model, rootLinkName, packageDir);
40  return geometry_model;
41  }
42 
43  GeometryModel & buildGeomFromSdf(
44  const Model & model,
45  const std::string & filename,
46  const GeometryType type,
47  GeometryModel & geometry_model,
48  const std::string & rootLinkName)
49  {
50  pinocchio::sdf::buildGeom(model, filename, type, geometry_model, rootLinkName);
51  return geometry_model;
52  }
53 
54  GeometryModel buildGeomFromSdf(
55  const Model & model,
56  const std::string & filename,
57  const GeometryType type,
58  const std::string & rootLinkName,
59  const std::string & packageDir)
60  {
61  GeometryModel geometry_model;
62  const std::vector<std::string> dirs(1, packageDir);
63  pinocchio::sdf::buildGeom(model, filename, type, geometry_model, rootLinkName, dirs);
64 
65  return geometry_model;
66  }
67 
68  GeometryModel buildGeomFromSdf(
69  const Model & model,
70  const std::string & filename,
71  const GeometryType type,
72  const std::string & rootLinkName,
73  const std::vector<std::string> & package_dirs)
74  {
75  GeometryModel geometry_model;
76  pinocchio::sdf::buildGeom(model, filename, type, geometry_model, rootLinkName, package_dirs);
77  return geometry_model;
78  }
79 
80  GeometryModel & buildGeomFromSdf(
81  const Model & model,
82  const std::string & filename,
83  const GeometryType type,
84  GeometryModel & geometry_model,
85  const std::string & rootLinkName,
86  const std::vector<std::string> & package_dirs)
87  {
88  pinocchio::sdf::buildGeom(model, filename, type, geometry_model, rootLinkName, package_dirs);
89  return geometry_model;
90  }
91 
92  GeometryModel & buildGeomFromSdf(
93  const Model & model,
94  const std::string & filename,
95  const GeometryType type,
96  GeometryModel & geometry_model,
97  const std::string & rootLinkName,
98  const std::string & package_dir)
99  {
100  pinocchio::sdf::buildGeom(model, filename, type, geometry_model, rootLinkName, package_dir);
101  return geometry_model;
102  }
103 
104  GeometryModel buildGeomFromSdf(
105  const Model & model,
106  const std::string & filename,
107  const GeometryType type,
108  const std::string & rootLinkName,
109  const hpp::fcl::MeshLoaderPtr & meshLoader)
110  {
111  std::vector<std::string> hints;
112  GeometryModel geometry_model;
114  model, filename, type, geometry_model, rootLinkName, hints, meshLoader);
115  return geometry_model;
116  }
117 
118  GeometryModel & buildGeomFromSdf(
119  const Model & model,
120  const std::string & filename,
121  const GeometryType type,
122  GeometryModel & geometry_model,
123  const std::string & rootLinkName,
124  const hpp::fcl::MeshLoaderPtr & meshLoader)
125  {
126  std::vector<std::string> hints;
128  model, filename, type, geometry_model, rootLinkName, hints, meshLoader);
129  return geometry_model;
130  }
131 
132  GeometryModel buildGeomFromSdf(
133  const Model & model,
134  const std::string & filename,
135  const GeometryType type,
136  const std::string & rootLinkName,
137  const std::vector<std::string> & package_dirs,
138  const hpp::fcl::MeshLoaderPtr & meshLoader)
139  {
140  GeometryModel geometry_model;
142  model, filename, type, geometry_model, rootLinkName, package_dirs, meshLoader);
143  return geometry_model;
144  }
145 
146  GeometryModel & buildGeomFromSdf(
147  const Model & model,
148  const std::string & filename,
149  const GeometryType type,
150  GeometryModel & geometry_model,
151  const std::string & rootLinkName,
152  const std::vector<std::string> & package_dirs,
153  const hpp::fcl::MeshLoaderPtr & meshLoader)
154  {
156  model, filename, type, geometry_model, rootLinkName, package_dirs, meshLoader);
157  return geometry_model;
158  }
159 
160  GeometryModel buildGeomFromSdf(
161  const Model & model,
162  const std::string & filename,
163  const GeometryType type,
164  const std::string & rootLinkName,
165  const std::string & package_dir,
166  const hpp::fcl::MeshLoaderPtr & meshLoader)
167  {
168  GeometryModel geometry_model;
170  model, filename, type, geometry_model, rootLinkName, package_dir, meshLoader);
171  return geometry_model;
172  }
173 
174  GeometryModel & buildGeomFromSdf(
175  const Model & model,
176  const std::string & filename,
177  const GeometryType type,
178  GeometryModel & geometry_model,
179  const std::string & rootLinkName,
180  const std::string & package_dir,
181  const hpp::fcl::MeshLoaderPtr & meshLoader)
182  {
184  model, filename, type, geometry_model, rootLinkName, package_dir, meshLoader);
185  return geometry_model;
186  }
187 
188 #endif // #ifdef PINOCCHIO_WITH_SDFORMAT
189 
191  {
192 #ifdef PINOCCHIO_WITH_SDFORMAT
193 
194  bp::def(
195  "buildGeomFromSdf",
196  static_cast<GeometryModel (*)(const Model &, const std::string &, const GeometryType)>(
197  pinocchio::python::buildGeomFromSdf),
198  bp::args("model", "sdf_filename", "geom_type"),
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 
208  bp::def(
209  "buildGeomFromSdf",
210  static_cast<GeometryModel (*)(
211  const Model &, const std::string &, const GeometryType, const std::string &,
212  const std::string &)>(pinocchio::python::buildGeomFromSdf),
213  bp::args("model", "sdf_filename", "geom_type", "root_link_name", "package_dir"),
214  "Parse the SDF file given as input looking for the geometry of the given input model and\n"
215  "return a GeometryModel containing either the collision geometries "
216  "(GeometryType.COLLISION) or the visual geometries (GeometryType.VISUAL).\n"
217  "Parameters:\n"
218  "\tmodel: model of the robot\n"
219  "\tsdf_filename: path to the SDF file containing the model of the robot\n"
220  "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
221  "or the COLLISION for collision detection).\n"
222  "\tpackage_dir: path pointing to the folder containing the meshes of the robot\n");
223 
224  bp::def(
225  "buildGeomFromSdf",
226  static_cast<GeometryModel (*)(
227  const Model &, const std::string &, const GeometryType, const std::string &,
228  const std::vector<std::string> &)>(pinocchio::python::buildGeomFromSdf),
229  bp::args("model", "sdf_filename", "geom_type", "root_link_name", "package_dirs"),
230  "Parse the SDF file given as input looking for the geometry of the given input model and\n"
231  "return a GeometryModel containing either the collision geometries "
232  "(GeometryType.COLLISION) or the visual geometries (GeometryType.VISUAL).\n"
233  "Parameters:\n"
234  "\tmodel: model of the robot\n"
235  "\tsdf_filename: path to the SDF file containing the model of the robot\n"
236  "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
237  "or the COLLISION for collision detection).\n"
238  "\tpackage_dirs: vector of paths pointing to the folders containing the model of the "
239  "robot\n");
240 
241  bp::def(
242  "buildGeomFromSdf",
243  static_cast<GeometryModel & (*)(const Model &, const std::string &, const GeometryType,
244  GeometryModel &, const std::string &,
245  const std::vector<std::string> &)>(
246  pinocchio::python::buildGeomFromSdf),
247  bp::args(
248  "model", "sdf_filename", "geom_type", "geom_model", "root_link_name", "package_dirs"),
249  "Parse the SDF file given as input looking for the geometry of the given input model and\n"
250  "and store either the collision geometries (GeometryType.COLLISION) or the visual "
251  "geometries (GeometryType.VISUAL) in the geom_model given as input.\n"
252  "Parameters:\n"
253  "\tmodel: model of the robot\n"
254  "\tsdf_filename: path to the SDF file containing the model of the robot\n"
255  "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
256  "or the COLLISION for collision detection).\n"
257  "\tgeom_model: reference where to store the parsed information\n"
258  "\tpackage_dirs: vector of paths pointing to the folders containing the model of the "
259  "robot\n",
260  bp::return_internal_reference<4>());
261 
262  bp::def(
263  "buildGeomFromSdf",
264  static_cast<GeometryModel (*)(
265  const Model &, const std::string &, const GeometryType, const std::string &)>(
266  pinocchio::python::buildGeomFromSdf),
267  bp::args("model", "sdf_filename", "geom_type", "root_link_name"),
268  "Parse the SDF file given as input looking for the geometry of the given input model and\n"
269  "return a GeometryModel containing either the collision geometries "
270  "(GeometryType.COLLISION) or the visual geometries (GeometryType.VISUAL).\n"
271  "Parameters:\n"
272  "\tmodel: model of the robot\n"
273  "\tsdf_filename: path to the SDF file containing the model of the robot\n"
274  "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
275  "or the COLLISION for collision detection).\n"
276  "Note:\n"
277  "This function does not take any hint concerning the location of the meshes of the robot.");
278 
279  bp::def(
280  "buildGeomFromSdf",
281  static_cast<GeometryModel & (*)(const Model &, const std::string &, const GeometryType,
282  GeometryModel &, const std::string &)>(
283  pinocchio::python::buildGeomFromSdf),
284  bp::args("model", "sdf_filename", "geom_type", "geom_model", "root_link_name"),
285  "Parse the SDF file given as input looking for the geometry of the given input model and\n"
286  "and store either the collision geometries (GeometryType.COLLISION) or the visual "
287  "geometries (GeometryType.VISUAL) in the geom_model given as input.\n"
288  "Parameters:\n"
289  "\tmodel: model of the robot\n"
290  "\tsdf_filename: path to the SDF file containing the model of the robot\n"
291  "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
292  "or the COLLISION for collision detection).\n"
293  "\tgeom_model: reference where to store the parsed information\n"
294  "Note:\n"
295  "This function does not take any hint concerning the location of the meshes of the robot.",
296  bp::return_internal_reference<4>());
297 
298  bp::def(
299  "buildGeomFromSdf",
300  static_cast<GeometryModel & (*)(const Model &, const std::string &, const GeometryType,
301  GeometryModel &, const std::string &, const std::string &)>(
302  pinocchio::python::buildGeomFromSdf),
303  bp::args(
304  "model", "sdf_filename", "geom_type", "geom_model", "root_link_name", "package_dir"),
305  "Parse the SDF file given as input looking for the geometry of the given input model and\n"
306  "and store either the collision geometries (GeometryType.COLLISION) or the visual "
307  "geometries (GeometryType.VISUAL) in the geom_model given as input.\n"
308  "Parameters:\n"
309  "\tmodel: model of the robot\n"
310  "\tsdf_filename: path to the SDF file containing the model of the robot\n"
311  "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
312  "or the COLLISION for collision detection).\n"
313  "\tgeom_model: reference where to store the parsed information\n"
314  "\tpackage_dir: path pointing to the folder containing the meshes of the robot\n",
315  bp::return_internal_reference<4>());
316 
317  bp::def(
318  "buildGeomFromSdf",
319  static_cast<GeometryModel (*)(
320  const Model &, const std::string &, const GeometryType, const std::string &,
321  const std::vector<std::string> &, const hpp::fcl::MeshLoaderPtr &)>(
322  pinocchio::python::buildGeomFromSdf),
323  bp::args(
324  "model", "sdf_filename", "geom_type", "root_link_name", "package_dirs", "mesh_loader"),
325  "Parse the SDF file given as input looking for the geometry of the given input model and\n"
326  "return a GeometryModel containing either the collision geometries "
327  "(GeometryType.COLLISION) or the visual geometries (GeometryType.VISUAL).\n"
328  "Parameters:\n"
329  "\tmodel: model of the robot\n"
330  "\tsdf_filename: path to the SDF file containing the model of the robot\n"
331  "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
332  "or the COLLISION for collision detection).\n"
333  "\tpackage_dirs: vector of paths pointing to the folders containing the model of the "
334  "robot\n"
335  "\tmesh_loader: an hpp-fcl mesh loader (to load only once the related geometries).");
336 
337  bp::def(
338  "buildGeomFromSdf",
339  static_cast<GeometryModel & (*)(const Model &, const std::string &, const GeometryType,
340  GeometryModel &, const std::string &,
341  const std::vector<std::string> &,
342  const hpp::fcl::MeshLoaderPtr &)>(
343  pinocchio::python::buildGeomFromSdf),
344  bp::args(
345  "model", "sdf_filename", "geom_type", "geom_model", "root_link_name", "package_dirs",
346  "mesh_loader"),
347  "Parse the SDF file given as input looking for the geometry of the given input model and\n"
348  "and store either the collision geometries (GeometryType.COLLISION) or the visual "
349  "geometries (GeometryType.VISUAL) in the geom_model given as input.\n"
350  "Parameters:\n"
351  "\tmodel: model of the robot\n"
352  "\tsdf_filename: path to the SDF file containing the model of the robot\n"
353  "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
354  "or the COLLISION for collision detection).\n"
355  "\tgeom_model: reference where to store the parsed information\n"
356  "\tpackage_dirs: vector of paths pointing to the folders containing the model of the "
357  "robot\n"
358  "\tmesh_loader: an hpp-fcl mesh loader (to load only once the related geometries).",
359  bp::return_internal_reference<4>());
360 
361  bp::def(
362  "buildGeomFromSdf",
363  static_cast<GeometryModel (*)(
364  const Model &, const std::string &, const GeometryType, const std::string &,
365  const std::string &, const hpp::fcl::MeshLoaderPtr &)>(
366  pinocchio::python::buildGeomFromSdf),
367  bp::args(
368  "model", "sdf_filename", "geom_type", "root_link_name", "package_dir", "mesh_loader"),
369  "Parse the SDF file given as input looking for the geometry of the given input model and\n"
370  "return a GeometryModel containing either the collision geometries "
371  "(GeometryType.COLLISION) or the visual geometries (GeometryType.VISUAL).\n"
372  "Parameters:\n"
373  "\tmodel: model of the robot\n"
374  "\tsdf_filename: path to the SDF file containing the model of the robot\n"
375  "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
376  "or the COLLISION for collision detection).\n"
377  "\tpackage_dir: path pointing to the folder containing the meshes of the robot\n"
378  "\tmesh_loader: an hpp-fcl mesh loader (to load only once the related geometries).");
379 
380  bp::def(
381  "buildGeomFromSdf",
382  static_cast<GeometryModel & (*)(const Model &, const std::string &, const GeometryType,
383  GeometryModel &, const std::string &, const std::string &,
384  const hpp::fcl::MeshLoaderPtr &)>(
385  pinocchio::python::buildGeomFromSdf),
386  bp::args(
387  "model", "sdf_filename", "geom_type", "geom_model", "root_link_name", "package_dir",
388  "mesh_loader"),
389  "Parse the SDF file given as input looking for the geometry of the given input model and\n"
390  "and store either the collision geometries (GeometryType.COLLISION) or the visual "
391  "geometries (GeometryType.VISUAL) in the geom_model given as input.\n"
392  "Parameters:\n"
393  "\tmodel: model of the robot\n"
394  "\tsdf_filename: path to the SDF file containing the model of the robot\n"
395  "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
396  "or the COLLISION for collision detection).\n"
397  "\tgeom_model: reference where to store the parsed information\n"
398  "\tpackage_dir: path pointing to the folder containing the meshes of the robot\n"
399  "\tmesh_loader: an hpp-fcl mesh loader (to load only once the related geometries).",
400  bp::return_internal_reference<4>());
401 
402  bp::def(
403  "buildGeomFromSdf",
404  static_cast<GeometryModel (*)(
405  const Model &, const std::string &, const GeometryType, const std::string &,
406  const hpp::fcl::MeshLoaderPtr &)>(pinocchio::python::buildGeomFromSdf),
407  bp::args("model", "sdf_filename", "geom_type", "root_link_name", "mesh_loader"),
408  "Parse the SDF file given as input looking for the geometry of the given input model and\n"
409  "return a GeometryModel containing either the collision geometries "
410  "(GeometryType.COLLISION) or the visual geometries (GeometryType.VISUAL).\n"
411  "Parameters:\n"
412  "\tmodel: model of the robot\n"
413  "\tsdf_filename: path to the SDF file containing the model of the robot\n"
414  "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
415  "or the COLLISION for collision detection).\n"
416  "\tmesh_loader: an hpp-fcl mesh loader (to load only once the related geometries).\n"
417  "Note:\n"
418  "This function does not take any hint concerning the location of the meshes of the robot.");
419 
420  bp::def(
421  "buildGeomFromSdf",
422  static_cast<GeometryModel & (*)(const Model &, const std::string &, const GeometryType,
423  GeometryModel &, const std::string &,
424  const hpp::fcl::MeshLoaderPtr &)>(
425  pinocchio::python::buildGeomFromSdf),
426  bp::args(
427  "model", "sdf_filename", "geom_type", "geom_model", "root_link_name", "mesh_loader"),
428  "Parse the SDF file given as input looking for the geometry of the given input model and\n"
429  "and store either the collision geometries (GeometryType.COLLISION) or the visual "
430  "geometries (GeometryType.VISUAL) in the geom_model given as input.\n"
431  "Parameters:\n"
432  "\tmodel: model of the robot\n"
433  "\tsdf_filename: path to the SDF file containing the model of the robot\n"
434  "\tgeom_type: type of geometry to extract from the SDF file (either the VISUAL for display "
435  "or the COLLISION for collision detection).\n"
436  "\tgeom_model: reference where to store the parsed information\n"
437  "\tmesh_loader: an hpp-fcl mesh loader (to load only once the related geometries).\n"
438  "Note:\n"
439  "This function does not take any hint concerning the location of the meshes of the robot.",
440  bp::return_internal_reference<4>());
441 #endif
442  }
443  } // namespace python
444 } // namespace pinocchio
boost::python
pinocchio::python::exposeSDFGeometry
void exposeSDFGeometry()
Definition: bindings/python/parsers/sdf/geometry.cpp:190
pinocchio::sdf::buildGeom
GeometryModel & buildGeom(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const GeometryType type, GeometryModel &geomModel, const std::string &rootLinkName="", const std::vector< std::string > &packageDirs=std::vector< std::string >(), ::hpp::fcl::MeshLoaderPtr meshLoader=::hpp::fcl::MeshLoaderPtr())
Build The GeometryModel from a SDF file. Search for meshes in the directories specified by the user f...
sdf.hpp
simulation-pendulum.type
type
Definition: simulation-pendulum.py:18
sdf.hpp
append-urdf-model-with-another-model.package_dirs
package_dirs
Definition: append-urdf-model-with-another-model.py:20
python
pinocchio::GeometryType
GeometryType
Definition: multibody/geometry-object.hpp:24
pinocchio::GeometryModel
Definition: multibody/geometry.hpp:50
pinocchio::ModelTpl
Definition: context/generic.hpp:20
cassie-simulation.package_dir
string package_dir
Definition: cassie-simulation.py:17
pinocchio::Model
ModelTpl< context::Scalar, context::Options > Model
Definition: multibody/fwd.hpp:33
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Wed Jun 19 2024 02:41:13