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"
38 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
40 const std::string & filename,
43 const bool verbose =
false);
53 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
55 const std::string & filename,
57 const bool verbose =
false);
71 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
73 const std::shared_ptr<::urdf::ModelInterface> urdfTree,
76 const bool verbose =
false);
88 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
90 const std::shared_ptr<::urdf::ModelInterface> urdfTree,
92 const bool verbose =
false);
106 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
108 const std::string & xml_stream,
111 const bool verbose =
false);
123 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
125 const std::string & xml_stream,
127 const bool verbose =
false);
153 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
156 const std::string & filename,
157 const GeometryType type,
159 const std::vector<std::string> & package_paths = std::vector<std::string>(),
160 ::hpp::fcl::MeshLoaderPtr mesh_loader = ::hpp::fcl::MeshLoaderPtr());
185 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
188 const std::string & filename,
189 const GeometryType type,
191 const std::string & package_path,
192 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr())
195 const std::vector<std::string> dirs(1, package_path);
196 return buildGeom(model, filename, type, geom_model, dirs, mesh_loader);
223 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
226 const std::istream & xml_stream,
227 const GeometryType type,
229 const std::vector<std::string> & package_paths = std::vector<std::string>(),
230 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr());
255 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
258 const std::istream & xml_stream,
259 const GeometryType type,
261 const std::string & package_path,
262 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr())
265 const std::vector<std::string> dirs(1, package_path);
266 return buildGeom(model, xml_stream, type, geom_model, dirs, mesh_loader);
272 #include "pinocchio/parsers/urdf/model.hxx"
273 #include "pinocchio/parsers/urdf/geometry.hxx"
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModelFromXML(const std::string &xml_stream, 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...
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, 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.