pinocchio  2.4.4
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
urdf.hpp
1 //
2 // Copyright (c) 2015-2018 CNRS
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  typedef boost::shared_ptr<MeshLoader> MeshLoaderPtr;
28  }
29 }
31 
32 namespace pinocchio
33 {
34  namespace urdf
35  {
36 
47  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
48  ModelTpl<Scalar,Options,JointCollectionTpl> &
49  buildModel(const std::string & filename,
50  const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
51  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
52  const bool verbose = false);
53 
54 
63  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
64  ModelTpl<Scalar,Options,JointCollectionTpl> &
65  buildModel(const std::string & filename,
66  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
67  const bool verbose = false);
68 
81  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
82  ModelTpl<Scalar,Options,JointCollectionTpl> &
83  buildModel(const boost::shared_ptr< ::urdf::ModelInterface> urdfTree,
84  const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
85  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
86  const bool verbose = false);
87 
98  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
99  ModelTpl<Scalar,Options,JointCollectionTpl> &
100  buildModel(const boost::shared_ptr< ::urdf::ModelInterface> urdfTree,
101  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
102  const bool verbose = false);
103 
104 #ifdef PINOCCHIO_WITH_CXX11_SUPPORT
105  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
107  ModelTpl<Scalar,Options,JointCollectionTpl> &
108  buildModel(const std::shared_ptr< ::urdf::ModelInterface> urdfTree,
109  const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
110  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
111  const bool verbose = false);
112 
114  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
115  ModelTpl<Scalar,Options,JointCollectionTpl> &
116  buildModel(const std::shared_ptr< ::urdf::ModelInterface> urdfTree,
117  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
118  const bool verbose = false);
119 #endif
120 
133  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
134  ModelTpl<Scalar,Options,JointCollectionTpl> &
135  buildModelFromXML(const std::string & xmlStream,
136  const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
137  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
138  const bool verbose = false);
139 
150  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
151  ModelTpl<Scalar,Options,JointCollectionTpl> &
152  buildModelFromXML(const std::string & xmlStream,
153  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
154  const bool verbose = false);
155 
156 
178  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
179  GeometryModel & buildGeom(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
180  const std::string & filename,
181  const GeometryType type,
182  GeometryModel & geomModel,
183  const std::vector<std::string> & packageDirs = std::vector<std::string> (),
184  ::hpp::fcl::MeshLoaderPtr meshLoader = ::hpp::fcl::MeshLoaderPtr());
185 
206  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
208  const std::string & filename,
209  const GeometryType type,
210  GeometryModel & geomModel,
211  const std::string & packageDir,
212  hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr())
213 
214  {
215  const std::vector<std::string> dirs(1,packageDir);
216  return buildGeom(model,filename,type,geomModel,dirs,meshLoader);
217  }
218 
240  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
242  const std::istream & xmlStream,
243  const GeometryType type,
244  GeometryModel & geomModel,
245  const std::vector<std::string> & packageDirs = std::vector<std::string> (),
246  hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr());
247 
268  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
270  const std::istream & xmlStream,
271  const GeometryType type,
272  GeometryModel & geomModel,
273  const std::string & packageDir,
274  hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr())
275 
276  {
277  const std::vector<std::string> dirs(1,packageDir);
278  return buildGeom(model,xmlStream,type,geomModel,dirs, meshLoader);
279  }
280 
281 
282  } // namespace urdf
283 } // namespace pinocchio
284 
285 #include "pinocchio/parsers/urdf/model.hxx"
286 #include "pinocchio/parsers/urdf/geometry.hxx"
287 
288 #endif // ifndef __pinocchio_parsers_urdf_hpp__
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModelFromXML(const std::string &xmlStream, 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...
Definition: types.hpp:29
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...
Main pinocchio namespace.
Definition: treeview.dox:24
GeometryModel & buildGeom(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const GeometryType type, GeometryModel &geomModel, const std::vector< std::string > &packageDirs=std::vector< std::string >(), ::hpp::fcl::MeshLoaderPtr meshLoader=::hpp::fcl::MeshLoaderPtr())
Build The GeometryModel from a URDF file. Search for meshes in the directories specified by the user ...