pinocchio  2.3.1-dirty
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 #include "pinocchio/parsers/urdf/types.hpp"
12 
14 namespace hpp
15 {
16  namespace fcl
17  {
18  class MeshLoader;
19  typedef boost::shared_ptr<MeshLoader> MeshLoaderPtr;
20  }
21 }
23 
24 namespace pinocchio
25 {
26  namespace urdf
27  {
28 
39  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
40  ModelTpl<Scalar,Options,JointCollectionTpl> &
41  buildModel(const std::string & filename,
42  const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
43  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
44  const bool verbose = false);
45 
46 
55  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
56  ModelTpl<Scalar,Options,JointCollectionTpl> &
57  buildModel(const std::string & filename,
58  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
59  const bool verbose = false);
60 
73  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
74  ModelTpl<Scalar,Options,JointCollectionTpl> &
75  buildModel(const ::urdf::ModelInterfaceSharedPtr & urdfTree,
76  const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
77  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
78  const bool verbose = false);
79 
90  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
91  ModelTpl<Scalar,Options,JointCollectionTpl> &
92  buildModel(const ::urdf::ModelInterfaceSharedPtr & urdfTree,
93  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
94  const bool verbose = false);
95 
108  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
109  ModelTpl<Scalar,Options,JointCollectionTpl> &
110  buildModelFromXML(const std::string & xmlStream,
111  const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
112  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
113  const bool verbose = false);
114 
125  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
126  ModelTpl<Scalar,Options,JointCollectionTpl> &
127  buildModelFromXML(const std::string & xmlStream,
128  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
129  const bool verbose = false);
130 
131 
153  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
154  GeometryModel & buildGeom(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
155  const std::string & filename,
156  const GeometryType type,
157  GeometryModel & geomModel,
158  const std::vector<std::string> & packageDirs = std::vector<std::string> (),
159  ::hpp::fcl::MeshLoaderPtr meshLoader = ::hpp::fcl::MeshLoaderPtr());
160 
181  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
183  const std::string & filename,
184  const GeometryType type,
185  GeometryModel & geomModel,
186  const std::string & packageDir,
187  hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr())
188 
189  {
190  const std::vector<std::string> dirs(1,packageDir);
191  return buildGeom(model,filename,type,geomModel,dirs,meshLoader);
192  }
193 
215  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
217  const std::istream & xmlStream,
218  const GeometryType type,
219  GeometryModel & geomModel,
220  const std::vector<std::string> & packageDirs = std::vector<std::string> (),
221  hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr());
222 
243  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
245  const std::istream & xmlStream,
246  const GeometryType type,
247  GeometryModel & geomModel,
248  const std::string & packageDir,
249  hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr())
250 
251  {
252  const std::vector<std::string> dirs(1,packageDir);
253  return buildGeom(model,xmlStream,type,geomModel,dirs, meshLoader);
254  }
255 
256 
257  } // namespace urdf
258 } // namespace pinocchio
259 
260 #include "pinocchio/parsers/urdf/model.hxx"
261 #include "pinocchio/parsers/urdf/geometry.hxx"
262 
263 #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 ...