6 #ifndef __pinocchio_parsers_urdf_hpp__ 7 #define __pinocchio_parsers_urdf_hpp__ 9 #include "pinocchio/multibody/model.hpp" 10 #include "pinocchio/multibody/geometry.hpp" 11 #include "pinocchio/parsers/urdf/types.hpp" 19 typedef boost::shared_ptr<MeshLoader> MeshLoaderPtr;
39 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
40 ModelTpl<Scalar,Options,JointCollectionTpl> &
42 const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
43 ModelTpl<Scalar,Options,JointCollectionTpl> & model,
44 const bool verbose =
false);
55 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
56 ModelTpl<Scalar,Options,JointCollectionTpl> &
58 ModelTpl<Scalar,Options,JointCollectionTpl> & model,
59 const bool verbose =
false);
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);
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);
108 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
109 ModelTpl<Scalar,Options,JointCollectionTpl> &
111 const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
112 ModelTpl<Scalar,Options,JointCollectionTpl> & model,
113 const bool verbose =
false);
125 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
126 ModelTpl<Scalar,Options,JointCollectionTpl> &
128 ModelTpl<Scalar,Options,JointCollectionTpl> & model,
129 const bool verbose =
false);
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());
181 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
183 const std::string & filename,
184 const GeometryType type,
186 const std::string & packageDir,
187 hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr())
190 const std::vector<std::string> dirs(1,packageDir);
191 return buildGeom(model,filename,type,geomModel,dirs,meshLoader);
215 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
217 const std::istream & xmlStream,
218 const GeometryType type,
220 const std::vector<std::string> & packageDirs = std::vector<std::string> (),
221 hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr());
243 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
245 const std::istream & xmlStream,
246 const GeometryType type,
248 const std::string & packageDir,
249 hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr())
252 const std::vector<std::string> dirs(1,packageDir);
253 return buildGeom(model,xmlStream,type,geomModel,dirs, meshLoader);
260 #include "pinocchio/parsers/urdf/model.hxx" 261 #include "pinocchio/parsers/urdf/geometry.hxx" 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...
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.
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 ...