pinocchio  2.6.20
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
urdf.hpp
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 
9 #include "pinocchio/multibody/model.hpp"
10 #include "pinocchio/multibody/geometry.hpp"
11 
12 #ifdef PINOCCHIO_WITH_CXX11_SUPPORT
13 #include <memory>
14 #endif
15 
17 // forward declaration of the unique type from urdfdom which is expose.
18 namespace urdf {
19  class ModelInterface;
20 }
21 
22 namespace hpp
23 {
24  namespace fcl
25  {
26  class MeshLoader;
27 #ifdef PINOCCHIO_HPPFCL_USE_STD_SHARED_PTR
28  typedef std::shared_ptr<MeshLoader> MeshLoaderPtr;
29 #else
30  typedef boost::shared_ptr<MeshLoader> MeshLoaderPtr;
31 #endif
32  }
33 }
35 
36 namespace pinocchio
37 {
38  namespace urdf
39  {
40 
51  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
52  ModelTpl<Scalar,Options,JointCollectionTpl> &
53  buildModel(const std::string & filename,
54  const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
55  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
56  const bool verbose = false);
57 
58 
67  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
68  ModelTpl<Scalar,Options,JointCollectionTpl> &
69  buildModel(const std::string & filename,
70  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
71  const bool verbose = false);
72 
85  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
86  ModelTpl<Scalar,Options,JointCollectionTpl> &
87  buildModel(const boost::shared_ptr< ::urdf::ModelInterface> urdfTree,
88  const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
89  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
90  const bool verbose = false);
91 
102  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
103  ModelTpl<Scalar,Options,JointCollectionTpl> &
104  buildModel(const boost::shared_ptr< ::urdf::ModelInterface> urdfTree,
105  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
106  const bool verbose = false);
107 
108 #ifdef PINOCCHIO_WITH_CXX11_SUPPORT
109  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
111  ModelTpl<Scalar,Options,JointCollectionTpl> &
112  buildModel(const std::shared_ptr< ::urdf::ModelInterface> urdfTree,
113  const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
114  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
115  const bool verbose = false);
116 
118  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
119  ModelTpl<Scalar,Options,JointCollectionTpl> &
120  buildModel(const std::shared_ptr< ::urdf::ModelInterface> urdfTree,
121  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
122  const bool verbose = false);
123 #endif
124 
137  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
138  ModelTpl<Scalar,Options,JointCollectionTpl> &
139  buildModelFromXML(const std::string & xml_stream,
140  const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
141  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
142  const bool verbose = false);
143 
154  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
155  ModelTpl<Scalar,Options,JointCollectionTpl> &
156  buildModelFromXML(const std::string & xml_stream,
157  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
158  const bool verbose = false);
159 
160 
182  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
183  GeometryModel & buildGeom(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
184  const std::string & filename,
185  const GeometryType type,
186  GeometryModel & geom_model,
187  const std::vector<std::string> & package_paths = std::vector<std::string> (),
188  ::hpp::fcl::MeshLoaderPtr mesh_loader = ::hpp::fcl::MeshLoaderPtr());
189 
210  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
212  const std::string & filename,
213  const GeometryType type,
214  GeometryModel & geom_model,
215  const std::string & package_path,
216  hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr())
217 
218  {
219  const std::vector<std::string> dirs(1,package_path);
220  return buildGeom(model,filename,type,geom_model,dirs,mesh_loader);
221  }
222 
244  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
246  const std::istream & xml_stream,
247  const GeometryType type,
248  GeometryModel & geom_model,
249  const std::vector<std::string> & package_paths = std::vector<std::string> (),
250  hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr());
251 
272  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
274  const std::istream & xml_stream,
275  const GeometryType type,
276  GeometryModel & geom_model,
277  const std::string & package_path,
278  hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr())
279 
280  {
281  const std::vector<std::string> dirs(1,package_path);
282  return buildGeom(model,xml_stream,type,geom_model,dirs,mesh_loader);
283  }
284 
285 
286  } // namespace urdf
287 } // namespace pinocchio
288 
289 #include "pinocchio/parsers/urdf/model.hxx"
290 #include "pinocchio/parsers/urdf/geometry.hxx"
291 
292 #endif // ifndef __pinocchio_parsers_urdf_hpp__
pinocchio::urdf::buildModel
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, 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 ...
pinocchio::GeometryModel
Definition: geometry.hpp:22
pinocchio::ModelTpl< Scalar, Options, JointCollectionTpl >
pinocchio::urdf::buildModelFromXML
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModelFromXML(const std::string &xml_stream, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, 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...
pinocchio
Main pinocchio namespace.
Definition: treeview.dox:11