bindings/python/parsers/urdf/geometry.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2022 CNRS INRIA
3 //
4 
5 #ifdef PINOCCHIO_WITH_URDFDOM
7 #endif
11 
12 #include <boost/python.hpp>
13 
14 namespace pinocchio
15 {
16  namespace python
17  {
18 
19  namespace bp = boost::python;
20 
21 #ifdef PINOCCHIO_WITH_URDFDOM
23 
24  void buildGeomFromUrdf_existing(
25  const Model & model,
26  const std::istream & stream,
27  const GeometryType type,
28  GeometryModel & geometry_model,
29  bp::object py_pkg_dirs,
30  bp::object py_mesh_loader)
31  {
32  MeshLoaderPtr mesh_loader = MeshLoaderPtr();
33  if (!py_mesh_loader.is_none())
34  {
35  #ifdef PINOCCHIO_WITH_HPP_FCL
38  mesh_loader = bp::extract<::hpp::fcl::MeshLoaderPtr>(py_mesh_loader);
40  #else
41  PyErr_WarnEx(
42  PyExc_UserWarning, "Mesh loader is ignored because Pinocchio is not built with hpp-fcl",
43  1);
44  #endif
45  }
46 
47  std::vector<std::string> pkg_dirs;
48  if (py_pkg_dirs.ptr() == Py_None)
49  {
50  }
51  else if (PyList_Check(py_pkg_dirs.ptr()))
52  {
53  pkg_dirs = pathList(py_pkg_dirs);
54  }
55  else
56  {
57  pkg_dirs.push_back(path(py_pkg_dirs));
58  }
59 
60  pinocchio::urdf::buildGeom(model, stream, type, geometry_model, pkg_dirs, mesh_loader);
61  }
62 
63  // This function is complex in order to keep backward compatibility.
64  GeometryModel * buildGeomFromUrdfStream(
65  const Model & model,
66  const std::istream & stream,
67  const GeometryType type,
68  bp::object py_geom_model,
69  bp::object package_dirs,
70  bp::object mesh_loader)
71  {
72  GeometryModel * geom_model;
73  if (py_geom_model.is_none())
74  geom_model = new GeometryModel;
75  else
76  {
77  bp::extract<GeometryModel *> geom_model_extract(py_geom_model);
78  if (geom_model_extract.check())
79  geom_model = geom_model_extract();
80  else
81  {
82  // When backward compat is removed, the code in this `else` section
83  // can be removed and the argument py_geom_model changed into a GeometryModel*
84  PyErr_WarnEx(
85  PyExc_UserWarning,
86  "You passed package dir(s) via argument geometry_model and provided package_dirs.", 1);
87 
88  // At this stage, py_geom_model contains the package dir(s). mesh_loader can
89  // be passed either by package_dirs or mesh_loader
90  bp::object new_pkg_dirs = py_geom_model;
91  if (!package_dirs.is_none() && !mesh_loader.is_none())
92  throw std::invalid_argument(
93  "package_dirs and mesh_loader cannot be both provided since you passed the package "
94  "dirs via argument geometry_model.");
95  if (mesh_loader.is_none())
96  mesh_loader = package_dirs;
97  try
98  {
99  // If geom_model is not a valid package_dir(s), then rethrow with clearer message
100  geom_model = new GeometryModel;
101  buildGeomFromUrdf_existing(model, stream, type, *geom_model, new_pkg_dirs, mesh_loader);
102  return geom_model;
103  }
104  catch (std::invalid_argument const & e)
105  {
106  std::cout << "Caught: " << e.what() << std::endl;
107  throw std::invalid_argument("Argument geometry_model should be a GeometryModel");
108  }
109  }
110  }
111  buildGeomFromUrdf_existing(model, stream, type, *geom_model, package_dirs, mesh_loader);
112  return geom_model;
113  }
114 
115  GeometryModel * buildGeomFromUrdfFile(
116  const Model & model,
117  const bp::object & filename,
118  const GeometryType type,
119  bp::object geom_model,
120  bp::object package_dirs,
121  bp::object mesh_loader)
122  {
123  const std::string filename_s = path(filename);
124  std::ifstream stream(filename_s.c_str());
125  if (!stream.is_open())
126  {
127  throw std::invalid_argument(filename_s + " does not seem to be a valid file.");
128  }
129  return buildGeomFromUrdfStream(model, stream, type, geom_model, package_dirs, mesh_loader);
130  }
131 
132  GeometryModel * buildGeomFromUrdfString(
133  const Model & model,
134  const std::string & xmlString,
135  const GeometryType type,
136  bp::object geom_model,
137  bp::object package_dirs,
138  bp::object mesh_loader)
139  {
140  std::istringstream stream(xmlString);
141  return buildGeomFromUrdfStream(model, stream, type, geom_model, package_dirs, mesh_loader);
142  }
143 
144  #ifdef PINOCCHIO_WITH_HPP_FCL
145  #define MESH_LOADER_DOC \
146  "\tmesh_loader: an hpp-fcl mesh loader (to load only once the related geometries).\n"
147  #else // #ifdef PINOCCHIO_WITH_HPP_FCL
148  #define MESH_LOADER_DOC "\tmesh_loader: unused because the Pinocchio is built without hpp-fcl\n"
149  #endif // #ifdef PINOCCHIO_WITH_HPP_FCL
150  template<std::size_t owner_arg = 1>
151  struct return_value_policy : bp::return_internal_reference<owner_arg>
152  {
153  public:
154  template<class ArgumentPackage>
155  static PyObject * postcall(ArgumentPackage const & args_, PyObject * result)
156  {
157  // If owner_arg exists, we run bp::return_internal_reference postcall
158  // result lifetime will be tied to the owner_arg lifetime
159  PyObject * patient = bp::detail::get_prev<owner_arg>::execute(args_, result);
160  if (patient != Py_None)
161  return bp::return_internal_reference<owner_arg>::postcall(args_, result);
162  // If owner_arg doesn't exist, then Python will have to manage the result lifetime
163  bp::extract<GeometryModel *> geom_model_extract(result);
164  if (geom_model_extract.check())
165  {
166  return bp::to_python_indirect<GeometryModel, bp::detail::make_owning_holder>()(
167  geom_model_extract());
168  }
169  // If returned value is not a GeometryModel*, then raise an error
170  PyErr_SetString(
171  PyExc_RuntimeError,
172  "pinocchio::python::return_value_policy only works on GeometryModel* data type");
173  return 0;
174  }
175  };
176 
177  template<typename F>
178  void defBuildUrdf(const char * name, F f, const char * urdf_arg, const char * urdf_doc)
179  {
180  std::ostringstream doc;
181  doc << "Parse the URDF file given as input looking for the geometry of the given input model "
182  "and\n"
183  "and store either the collision geometries (GeometryType.COLLISION) or the visual "
184  "geometries (GeometryType.VISUAL) in a GeometryModel object.\n"
185  "Parameters:\n"
186  "\tmodel: model of the robot\n"
187  "\n"
188  << urdf_arg << ": " << urdf_doc
189  << "\n"
190  "\tgeom_type: type of geometry to extract from the URDF file (either the VISUAL for "
191  "display or the COLLISION for collision detection).\n"
192  "\tgeometry_model: if provided, this geometry model will be used to store the parsed "
193  "information instead of creating a new one\n"
194  "\tpackage_dirs: either a single path or a vector of paths pointing to folders "
195  "containing the model of the robot\n" MESH_LOADER_DOC "\n"
196  "Retuns:\n"
197  "\ta new GeometryModel if `geometry_model` is None else `geometry_model` (that has "
198  "been updated).\n";
199 
200  bp::def(
201  name, f,
202  (bp::arg("model"), bp::arg(urdf_arg), bp::arg("geom_type"),
203  bp::arg("geometry_model") = static_cast<GeometryModel *>(NULL),
204  bp::arg("package_dirs") = bp::object(), bp::arg("mesh_loader") = bp::object()),
205  doc.str().c_str(), return_value_policy<4>());
206  }
207 
208 #endif
209 
211  {
212 #ifdef PINOCCHIO_WITH_URDFDOM
213  defBuildUrdf(
214  "buildGeomFromUrdf", buildGeomFromUrdfFile, "urdf_filename",
215  "path to the URDF file containing the model of the robot");
216  defBuildUrdf(
217  "buildGeomFromUrdfString", buildGeomFromUrdfString, "urdf_string",
218  "a string containing the URDF model of the robot");
219 #endif // #ifdef PINOCCHIO_WITH_URDFDOM
220  }
221  } // namespace python
222 } // namespace pinocchio
pinocchio::python::path
std::string path(const bp::object &path)
python pathlib.Path | str -> C++ std::string
Definition: path.cpp:13
common_symbols.type
type
Definition: common_symbols.py:35
boost::python
path.hpp
pinocchio::name
std::string name(const LieGroupGenericTpl< LieGroupCollection > &lg)
Visit a LieGroupVariant to get the name of it.
PINOCCHIO_COMPILER_DIAGNOSTIC_POP
#define PINOCCHIO_COMPILER_DIAGNOSTIC_POP
Definition: include/pinocchio/macros.hpp:130
autodiff-rnea.f
f
Definition: autodiff-rnea.py:24
PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED
#define PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED
Definition: include/pinocchio/macros.hpp:134
hpp::fcl::MeshLoaderPtr
std::shared_ptr< MeshLoader > MeshLoaderPtr
Definition: meshloader-fwd.hpp:25
list.hpp
append-urdf-model-with-another-model.package_dirs
package_dirs
Definition: append-urdf-model-with-another-model.py:20
python
urdf.hpp
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 ...
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
#define PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
macros for pragma push/pop/ignore deprecated warnings
Definition: include/pinocchio/macros.hpp:129
append-urdf-model-with-another-model.geom_model
geom_model
Definition: append-urdf-model-with-another-model.py:26
pinocchio::GeometryType
GeometryType
Definition: multibody/geometry-object.hpp:24
pinocchio::python::exposeURDFGeometry
void exposeURDFGeometry()
Definition: bindings/python/parsers/urdf/geometry.cpp:210
pinocchio::python::pathList
std::vector< std::string > pathList(const bp::object &path_list)
python typing.List[pathlib.Path] | typing.List[str] -> C++ std::vector<std::string>
Definition: path.cpp:31
urdf.hpp
pinocchio::Model
ModelTpl< context::Scalar, context::Options > Model
Definition: multibody/fwd.hpp:33
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1082
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Sun Dec 22 2024 03:41:09