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"
39 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
41 const std::string & filename,
43 const std::string & rootJointName,
45 const bool verbose =
false);
57 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
59 const std::string & filename,
62 const bool verbose =
false);
72 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
74 const std::string & filename,
76 const bool verbose =
false);
90 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
92 const std::shared_ptr<::urdf::ModelInterface> urdfTree,
95 const bool verbose =
false);
110 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
112 const std::shared_ptr<::urdf::ModelInterface> urdfTree,
114 const std::string & rootJointName,
116 const bool verbose =
false);
128 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
130 const std::shared_ptr<::urdf::ModelInterface> urdfTree,
132 const bool verbose =
false);
147 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
149 const std::string & xml_stream,
151 const std::string & rootJointName,
153 const bool verbose =
false);
167 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
169 const std::string & xml_stream,
172 const bool verbose =
false);
184 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
186 const std::string & xml_stream,
188 const bool verbose =
false);
214 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
217 const std::string & filename,
218 const GeometryType type,
220 const std::vector<std::string> & package_paths = std::vector<std::string>(),
221 ::hpp::fcl::MeshLoaderPtr mesh_loader = ::hpp::fcl::MeshLoaderPtr());
246 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
249 const std::string & filename,
250 const GeometryType type,
252 const std::string & package_path,
253 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr())
256 const std::vector<std::string> dirs(1, package_path);
257 return buildGeom(model, filename, type, geom_model, dirs, mesh_loader);
284 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
287 const std::istream & xml_stream,
288 const GeometryType type,
290 const std::vector<std::string> & package_paths = std::vector<std::string>(),
291 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr());
316 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
319 const std::istream & xml_stream,
320 const GeometryType type,
322 const std::string & package_path,
323 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr())
326 const std::vector<std::string> dirs(1, package_path);
327 return buildGeom(model, xml_stream, type, geom_model, dirs, mesh_loader);
333 #include "pinocchio/parsers/urdf/model.hxx"
334 #include "pinocchio/parsers/urdf/geometry.hxx"
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)
Build the model from a URDF file with a particular joint as root of the model tree inside the model g...
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)
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 ...
Main pinocchio namespace.