pinocchio  2.2.1-dirty
srdf.hpp
1 //
2 // Copyright (c) 2016-2018 CNRS
3 //
4 
5 #ifndef __pinocchio_parser_srdf_hpp__
6 #define __pinocchio_parser_srdf_hpp__
7 
8 #include "pinocchio/multibody/model.hpp"
9 #include "pinocchio/multibody/geometry.hpp"
10 
11 namespace pinocchio
12 {
13  namespace srdf
14  {
15 
16 #ifdef PINOCCHIO_WITH_HPP_FCL
17 
28  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
29  void removeCollisionPairs(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
30  GeometryModel & geomModel,
31  const std::string & filename,
32  const bool verbose = false);
33 
43  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
44  void removeCollisionPairsFromXML(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
45  GeometryModel & geomModel,
46  const std::string & xmlString,
47  const bool verbose = false);
48 
49 #endif // ifdef PINOCCHIO_WITH_HPP_FCL
50 
59  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
60  void
61  loadReferenceConfigurations(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
62  const std::string & filename,
63  const bool verbose = false);
64 
73  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
74  void
75  loadReferenceConfigurationsFromXML(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
76  std::istream & xmlStream,
77  const bool verbose = false);
78 
79 
90  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
91  bool loadRotorParameters(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
92  const std::string & filename,
93  const bool verbose = false);
94 
95  }
96 } // namespace pinocchio
97 
98 #include "pinocchio/parsers/srdf.hxx"
99 
100 #endif // ifndef __pinocchio_parser_srdf_hpp__
void loadReferenceConfigurations(ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const bool verbose=false)
Get the reference configurations of a given model associated to a SRDF file. It throws if the SRDF fi...
void removeCollisionPairsFromXML(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, GeometryModel &geomModel, const std::string &xmlString, const bool verbose=false)
Deactive all possible collision pairs mentioned in the SRDF file.
void removeCollisionPairs(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, GeometryModel &geomModel, const std::string &filename, const bool verbose=false)
Deactive all possible collision pairs mentioned in the SRDF file. It throws if the SRDF file is incor...
bool loadRotorParameters(ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const bool verbose=false)
Load the rotor params of a given model associated to a SRDF file. It throws if the SRDF file is incor...
void loadReferenceConfigurationsFromXML(ModelTpl< Scalar, Options, JointCollectionTpl > &model, std::istream &xmlStream, const bool verbose=false)
Get the reference configurations of a given model associated to a SRDF file. It throws if the SRDF fi...
Main pinocchio namespace.
Definition: treeview.dox:24