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 #ifdef PINOCCHIO_HPPFCL_USE_STD_SHARED_PTR 28 typedef std::shared_ptr<MeshLoader> MeshLoaderPtr;
30 typedef boost::shared_ptr<MeshLoader> MeshLoaderPtr;
51 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
52 ModelTpl<Scalar,Options,JointCollectionTpl> &
55 ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
56 const bool verbose =
false);
67 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
68 ModelTpl<Scalar,Options,JointCollectionTpl> &
70 ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
71 const bool verbose =
false);
85 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
86 ModelTpl<Scalar,Options,JointCollectionTpl> &
87 buildModel(
const boost::shared_ptr< ::urdf::ModelInterface> urdfTree,
89 ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
90 const bool verbose =
false);
102 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
103 ModelTpl<Scalar,Options,JointCollectionTpl> &
104 buildModel(
const boost::shared_ptr< ::urdf::ModelInterface> urdfTree,
105 ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
106 const bool verbose =
false);
108 #ifdef PINOCCHIO_WITH_CXX11_SUPPORT 109 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
111 ModelTpl<Scalar,Options,JointCollectionTpl> &
112 buildModel(
const std::shared_ptr< ::urdf::ModelInterface> urdfTree,
114 ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
115 const bool verbose =
false);
118 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
119 ModelTpl<Scalar,Options,JointCollectionTpl> &
120 buildModel(
const std::shared_ptr< ::urdf::ModelInterface> urdfTree,
121 ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
122 const bool verbose =
false);
137 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
138 ModelTpl<Scalar,Options,JointCollectionTpl> &
141 ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
142 const bool verbose =
false);
154 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
155 ModelTpl<Scalar,Options,JointCollectionTpl> &
157 ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
158 const bool verbose =
false);
182 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
183 GeometryModel &
buildGeom(
const ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
184 const std::string & filename,
187 const std::vector<std::string> & package_paths = std::vector<std::string> (),
188 ::hpp::fcl::MeshLoaderPtr mesh_loader = ::hpp::fcl::MeshLoaderPtr());
210 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
212 const std::string & filename,
215 const std::string & package_path,
216 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr())
219 const std::vector<std::string> dirs(1,package_path);
220 return buildGeom(model,filename,type,geom_model,dirs,mesh_loader);
244 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
246 const std::istream & xml_stream,
249 const std::vector<std::string> & package_paths = std::vector<std::string> (),
250 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr());
272 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
274 const std::istream & xml_stream,
277 const std::string & package_path,
278 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr())
281 const std::vector<std::string> dirs(1,package_path);
282 return buildGeom(model,xml_stream,type,geom_model,dirs,mesh_loader);
289 #include "pinocchio/parsers/urdf/model.hxx" 290 #include "pinocchio/parsers/urdf/geometry.hxx" 292 #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.