6 #ifndef __pinocchio_parsers_urdf_hpp__ 7 #define __pinocchio_parsers_urdf_hpp__ 9 #include "pinocchio/multibody/model.hpp" 10 #include "pinocchio/multibody/geometry.hpp" 12 #ifdef PINOCCHIO_WITH_CXX11_SUPPORT 27 typedef boost::shared_ptr<MeshLoader> MeshLoaderPtr;
47 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
48 ModelTpl<Scalar,Options,JointCollectionTpl> &
51 ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
52 const bool verbose =
false);
63 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
64 ModelTpl<Scalar,Options,JointCollectionTpl> &
66 ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
67 const bool verbose =
false);
81 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
82 ModelTpl<Scalar,Options,JointCollectionTpl> &
83 buildModel(
const boost::shared_ptr< ::urdf::ModelInterface> urdfTree,
85 ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
86 const bool verbose =
false);
98 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
99 ModelTpl<Scalar,Options,JointCollectionTpl> &
100 buildModel(
const boost::shared_ptr< ::urdf::ModelInterface> urdfTree,
101 ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
102 const bool verbose =
false);
104 #ifdef PINOCCHIO_WITH_CXX11_SUPPORT 105 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
107 ModelTpl<Scalar,Options,JointCollectionTpl> &
108 buildModel(
const std::shared_ptr< ::urdf::ModelInterface> urdfTree,
110 ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
111 const bool verbose =
false);
114 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
115 ModelTpl<Scalar,Options,JointCollectionTpl> &
116 buildModel(
const std::shared_ptr< ::urdf::ModelInterface> urdfTree,
117 ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
118 const bool verbose =
false);
133 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
134 ModelTpl<Scalar,Options,JointCollectionTpl> &
137 ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
138 const bool verbose =
false);
150 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
151 ModelTpl<Scalar,Options,JointCollectionTpl> &
153 ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
154 const bool verbose =
false);
178 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
179 GeometryModel &
buildGeom(
const ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
180 const std::string & filename,
183 const std::vector<std::string> & package_paths = std::vector<std::string> (),
184 ::hpp::fcl::MeshLoaderPtr mesh_loader = ::hpp::fcl::MeshLoaderPtr());
206 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
208 const std::string & filename,
211 const std::string & package_path,
212 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr())
215 const std::vector<std::string> dirs(1,package_path);
216 return buildGeom(model,filename,type,geom_model,dirs,mesh_loader);
240 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
242 const std::istream & xml_stream,
245 const std::vector<std::string> & package_paths = std::vector<std::string> (),
246 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr());
268 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
270 const std::istream & xml_stream,
273 const std::string & package_path,
274 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr())
277 const std::vector<std::string> dirs(1,package_path);
278 return buildGeom(model,xml_stream,type,geom_model,dirs,mesh_loader);
285 #include "pinocchio/parsers/urdf/model.hxx" 286 #include "pinocchio/parsers/urdf/geometry.hxx" 288 #endif // ifndef __pinocchio_parsers_urdf_hpp__
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const boost::shared_ptr< ::urdf::ModelInterface > urdfTree, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
Build the model from a URDF model.
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModelFromXML(const std::string &xml_stream, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
Build the model from an XML stream.
GeometryModel & buildGeom(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::istream &xml_stream, const GeometryType type, GeometryModel &geom_model, const std::string &package_path, hpp::fcl::MeshLoaderPtr mesh_loader=hpp::fcl::MeshLoaderPtr())
Build The GeometryModel from a URDF model. Search for meshes in the directories specified by the user...
JointModelTpl< Scalar, Options, JointCollectionTpl > JointModel
Main pinocchio namespace.