6 #ifndef __pinocchio_parsers_urdf_hpp__
7 #define __pinocchio_parsers_urdf_hpp__
12 #ifdef PINOCCHIO_WITH_CXX11_SUPPORT
28 typedef std::shared_ptr<MeshLoader> MeshLoaderPtr;
48 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
49 ModelTpl<Scalar, Options, JointCollectionTpl> &
buildModel(
50 const std::string & filename,
52 ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
53 const bool verbose =
false);
63 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
64 ModelTpl<Scalar, Options, JointCollectionTpl> &
buildModel(
65 const std::string & filename,
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> &
buildModel(
83 const std::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> &
buildModel(
100 const std::shared_ptr<::urdf::ModelInterface> urdfTree,
101 ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
102 const bool verbose =
false);
116 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
118 const std::string & xml_stream,
120 ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
121 const bool verbose =
false);
133 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
135 const std::string & xml_stream,
136 ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
137 const bool verbose =
false);
163 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
165 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
166 const std::string & filename,
169 const std::vector<std::string> & package_paths = std::vector<std::string>(),
170 ::hpp::fcl::MeshLoaderPtr mesh_loader = ::hpp::fcl::MeshLoaderPtr());
195 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
198 const std::string & filename,
201 const std::string & package_path,
202 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr())
205 const std::vector<std::string> dirs(1, package_path);
233 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
236 const std::istream & xml_stream,
239 const std::vector<std::string> & package_paths = std::vector<std::string>(),
240 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr());
265 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
268 const std::istream & xml_stream,
271 const std::string & package_path,
272 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr())
275 const std::vector<std::string> dirs(1, package_path);
282 #include "pinocchio/parsers/urdf/model.hxx"
283 #include "pinocchio/parsers/urdf/geometry.hxx"
285 #endif // ifndef __pinocchio_parsers_urdf_hpp__