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/meshloader-fwd.hpp"
40 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
42 const std::string & filename,
44 const std::string & rootJointName,
46 const bool verbose =
false,
47 const bool mimic =
false);
60 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
62 const std::string & filename,
65 const bool verbose =
false,
66 const bool mimic =
false);
77 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
79 const std::string & filename,
81 const bool verbose =
false,
82 const bool mimic =
false);
97 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
99 const std::shared_ptr<::urdf::ModelInterface> urdfTree,
102 const bool verbose =
false,
103 const bool mimic =
false);
119 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
121 const std::shared_ptr<::urdf::ModelInterface> urdfTree,
123 const std::string & rootJointName,
125 const bool verbose =
false,
126 const bool mimic =
false);
139 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
141 const std::shared_ptr<::urdf::ModelInterface> urdfTree,
143 const bool verbose =
false,
144 const bool mimic =
false);
160 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
162 const std::string & xml_stream,
164 const std::string & rootJointName,
166 const bool verbose =
false,
167 const bool mimic =
false);
182 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
184 const std::string & xml_stream,
187 const bool verbose =
false,
188 const bool mimic =
false);
201 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
203 const std::string & xml_stream,
205 const bool verbose =
false,
206 const bool mimic =
false);
232 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
235 const std::string & filename,
236 const GeometryType type,
238 const std::vector<std::string> & package_paths = std::vector<std::string>(),
239 ::hpp::fcl::MeshLoaderPtr mesh_loader = ::hpp::fcl::MeshLoaderPtr());
264 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
267 const std::string & filename,
268 const GeometryType type,
270 const std::string & package_path,
271 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr())
274 const std::vector<std::string> dirs(1, package_path);
275 return buildGeom(model, filename, type, geom_model, dirs, mesh_loader);
302 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
305 const std::istream & xml_stream,
306 const GeometryType type,
308 const std::vector<std::string> & package_paths = std::vector<std::string>(),
309 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr());
334 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
337 const std::istream & xml_stream,
338 const GeometryType type,
340 const std::string & package_path,
341 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr())
344 const std::vector<std::string> dirs(1, package_path);
345 return buildGeom(model, xml_stream, type, geom_model, dirs, mesh_loader);
351 #include "pinocchio/parsers/urdf/model.hxx"
352 #include "pinocchio/parsers/urdf/geometry.hxx"
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModelFromXML(const std::string &xml_stream, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, const std::string &rootJointName, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false, const bool mimic=false)
Build the model from an XML stream with a particular joint as root of the model tree inside the model...
GeometryModel & buildGeom(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const GeometryType type, GeometryModel &geom_model, const std::vector< std::string > &package_paths=std::vector< std::string >(), ::hpp::fcl::MeshLoaderPtr mesh_loader=::hpp::fcl::MeshLoaderPtr())
Build The GeometryModel from a URDF file. Search for meshes in the directories specified by the user ...
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, const std::string &rootJointName, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false, const bool mimic=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.