parsers/urdf.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2021 CNRS INRIA
3 // Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 
6 #ifndef __pinocchio_parsers_urdf_hpp__
7 #define __pinocchio_parsers_urdf_hpp__
8 
12 
13 #include <memory>
14 
16 // forward declaration of the unique type from urdfdom which is expose.
17 namespace urdf
18 {
19  class ModelInterface;
20 }
22 
23 namespace pinocchio
24 {
25  namespace urdf
26  {
27 
39  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
40  ModelTpl<Scalar, Options, JointCollectionTpl> & buildModel(
41  const std::string & filename,
43  const std::string & rootJointName,
44  ModelTpl<Scalar, Options, JointCollectionTpl> & model,
45  const bool verbose = false);
46 
57  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
58  ModelTpl<Scalar, Options, JointCollectionTpl> & buildModel(
59  const std::string & filename,
61  ModelTpl<Scalar, Options, JointCollectionTpl> & model,
62  const bool verbose = false);
63 
72  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
73  ModelTpl<Scalar, Options, JointCollectionTpl> & buildModel(
74  const std::string & filename,
75  ModelTpl<Scalar, Options, JointCollectionTpl> & model,
76  const bool verbose = false);
77 
90  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
91  ModelTpl<Scalar, Options, JointCollectionTpl> & buildModel(
92  const std::shared_ptr<::urdf::ModelInterface> urdfTree,
94  ModelTpl<Scalar, Options, JointCollectionTpl> & model,
95  const bool verbose = false);
96 
110  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
111  ModelTpl<Scalar, Options, JointCollectionTpl> & buildModel(
112  const std::shared_ptr<::urdf::ModelInterface> urdfTree,
114  const std::string & rootJointName,
115  ModelTpl<Scalar, Options, JointCollectionTpl> & model,
116  const bool verbose = false);
117 
128  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
129  ModelTpl<Scalar, Options, JointCollectionTpl> & buildModel(
130  const std::shared_ptr<::urdf::ModelInterface> urdfTree,
131  ModelTpl<Scalar, Options, JointCollectionTpl> & model,
132  const bool verbose = false);
133 
147  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
148  ModelTpl<Scalar, Options, JointCollectionTpl> & buildModelFromXML(
149  const std::string & xml_stream,
151  const std::string & rootJointName,
152  ModelTpl<Scalar, Options, JointCollectionTpl> & model,
153  const bool verbose = false);
154 
167  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
168  ModelTpl<Scalar, Options, JointCollectionTpl> & buildModelFromXML(
169  const std::string & xml_stream,
171  ModelTpl<Scalar, Options, JointCollectionTpl> & model,
172  const bool verbose = false);
173 
184  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
185  ModelTpl<Scalar, Options, JointCollectionTpl> & buildModelFromXML(
186  const std::string & xml_stream,
187  ModelTpl<Scalar, Options, JointCollectionTpl> & model,
188  const bool verbose = false);
189 
214  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
215  GeometryModel & buildGeom(
216  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
217  const std::string & filename,
218  const GeometryType type,
219  GeometryModel & geom_model,
220  const std::vector<std::string> & package_paths = std::vector<std::string>(),
222 
246  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
249  const std::string & filename,
250  const GeometryType type,
252  const std::string & package_path,
254 
255  {
256  const std::vector<std::string> dirs(1, package_path);
257  return buildGeom(model, filename, type, geom_model, dirs, mesh_loader);
258  }
259 
284  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
287  const std::istream & xml_stream,
288  const GeometryType type,
290  const std::vector<std::string> & package_paths = std::vector<std::string>(),
292 
316  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
319  const std::istream & xml_stream,
320  const GeometryType type,
322  const std::string & package_path,
324 
325  {
326  const std::vector<std::string> dirs(1, package_path);
327  return buildGeom(model, xml_stream, type, geom_model, dirs, mesh_loader);
328  }
329 
330  } // namespace urdf
331 } // namespace pinocchio
332 
333 #include "pinocchio/parsers/urdf/model.hxx"
334 #include "pinocchio/parsers/urdf/geometry.hxx"
335 
336 #endif // ifndef __pinocchio_parsers_urdf_hpp__
model.hpp
pinocchio::urdf::buildModelFromXML
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModelFromXML(const std::string &xml_stream, 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 an XML stream with a particular joint as root of the model tree inside the model...
simulation-pendulum.type
type
Definition: simulation-pendulum.py:19
hpp::fcl::MeshLoaderPtr
std::shared_ptr< MeshLoader > MeshLoaderPtr
Definition: meshloader-fwd.hpp:25
filename
filename
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::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 ...
meshloader-fwd.hpp
append-urdf-model-with-another-model.geom_model
geom_model
Definition: append-urdf-model-with-another-model.py:25
urdf
Definition: types.hpp:29
pinocchio::GeometryType
GeometryType
Definition: multibody/geometry-object.hpp:24
pinocchio::GeometryModel
Definition: multibody/geometry.hpp:50
pinocchio::ModelTpl
Definition: context/generic.hpp:20
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::ModelTpl::JointModel
JointModelTpl< Scalar, Options, JointCollectionTpl > JointModel
Definition: multibody/model.hpp:73


pinocchio
Author(s):
autogenerated on Sat Sep 28 2024 02:41:22