pinocchio  2.1.3
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 // Commented because this is needed in function prototypes.
15 //#ifdef PINOCCHIO_WITH_HPP_FCL
16 namespace hpp
17 {
18 namespace fcl
19 {
20  class MeshLoader;
21  typedef boost::shared_ptr<MeshLoader> MeshLoaderPtr;
22 }
23 }
24 //#endif // PINOCCHIO_WITH_HPP_FCL
26 
27 namespace pinocchio
28 {
29  namespace urdf
30  {
31 
42  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
43  ModelTpl<Scalar,Options,JointCollectionTpl> &
44  buildModel(const std::string & filename,
45  const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
46  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
47  const bool verbose = false);
48 
49 
58  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
59  ModelTpl<Scalar,Options,JointCollectionTpl> &
60  buildModel(const std::string & filename,
61  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
62  const bool verbose = false);
63 
76  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
77  ModelTpl<Scalar,Options,JointCollectionTpl> &
78  buildModel(const ::urdf::ModelInterfaceSharedPtr & urdfTree,
79  const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
80  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
81  const bool verbose = false);
82 
93  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
94  ModelTpl<Scalar,Options,JointCollectionTpl> &
95  buildModel(const ::urdf::ModelInterfaceSharedPtr & urdfTree,
96  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
97  const bool verbose = false);
98 
111  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
112  ModelTpl<Scalar,Options,JointCollectionTpl> &
113  buildModelFromXML(const std::string & xmlStream,
114  const JointModelVariant & rootJoint,
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> &
130  buildModelFromXML(const std::string & xmlStream,
131  ModelTpl<Scalar,Options,JointCollectionTpl> & model,
132  const bool verbose = false);
133 
134 
156  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
157  GeometryModel & buildGeom(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
158  const std::string & filename,
159  const GeometryType type,
160  GeometryModel & geomModel,
161  const std::vector<std::string> & packageDirs = std::vector<std::string> (),
162  ::hpp::fcl::MeshLoaderPtr meshLoader = ::hpp::fcl::MeshLoaderPtr());
163 
184  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
186  const std::string & filename,
187  const GeometryType type,
188  GeometryModel & geomModel,
189  const std::string & packageDir,
190  hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr())
191 
192  {
193  const std::vector<std::string> dirs(1,packageDir);
194  return buildGeom(model,filename,type,geomModel,dirs,meshLoader);
195  }
196 
218  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
220  const std::istream & xmlStream,
221  const GeometryType type,
222  GeometryModel & geomModel,
223  const std::vector<std::string> & packageDirs = std::vector<std::string> (),
224  hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr());
225 
246  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
248  const std::istream & xmlStream,
249  const GeometryType type,
250  GeometryModel & geomModel,
251  const std::string & packageDir,
252  hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr())
253 
254  {
255  const std::vector<std::string> dirs(1,packageDir);
256  return buildGeom(model,xmlStream,type,geomModel,dirs, meshLoader);
257  }
258 
259 
260  } // namespace urdf
261 } // namespace pinocchio
262 
263 #include "pinocchio/parsers/urdf/model.hxx"
264 #include "pinocchio/parsers/urdf/geometry.hxx"
265 
266 #endif // ifndef __pinocchio_parsers_urdf_hpp__
Definition: types.hpp:29
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 ...
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModelFromXML(const std::string &xmlStream, const JointModelVariant &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...