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" 21 typedef boost::shared_ptr<MeshLoader> MeshLoaderPtr;
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);
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);
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);
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);
111 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
112 ModelTpl<Scalar,Options,JointCollectionTpl> &
114 const JointModelVariant & rootJoint,
115 ModelTpl<Scalar,Options,JointCollectionTpl> & model,
116 const bool verbose =
false);
128 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
129 ModelTpl<Scalar,Options,JointCollectionTpl> &
131 ModelTpl<Scalar,Options,JointCollectionTpl> & model,
132 const bool verbose =
false);
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());
184 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
186 const std::string & filename,
187 const GeometryType type,
189 const std::string & packageDir,
190 hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr())
193 const std::vector<std::string> dirs(1,packageDir);
194 return buildGeom(model,filename,type,geomModel,dirs,meshLoader);
218 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
220 const std::istream & xmlStream,
221 const GeometryType type,
223 const std::vector<std::string> & packageDirs = std::vector<std::string> (),
224 hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr());
246 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
248 const std::istream & xmlStream,
249 const GeometryType type,
251 const std::string & packageDir,
252 hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr())
255 const std::vector<std::string> dirs(1,packageDir);
256 return buildGeom(model,xmlStream,type,geomModel,dirs, meshLoader);
263 #include "pinocchio/parsers/urdf/model.hxx" 264 #include "pinocchio/parsers/urdf/geometry.hxx" 266 #endif // ifndef __pinocchio_parsers_urdf_hpp__
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 ...
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...