hebiros_model.h
Go to the documentation of this file.
1 #ifndef HEBIROS_MODEL_H
2 #define HEBIROS_MODEL_H
3 
4 #include "ros/ros.h"
5 #include "urdf/model.h"
6 #include "robot_model.hpp"
7 
8 class HebirosModel {
9 
10  public:
11  // Tries to read the model from the robot description parameter. Add to the
12  // set of models and returns true on success, otherwise returns false.
13  static bool load(const std::string& name, const std::string& description_param);
14 
15  // Technically, this is only used by this class, but it is used by the
16  // std::map contained herein, so it has to be public
17  HebirosModel(std::unique_ptr<hebi::robot_model::RobotModel> model_);
18 
19  static HebirosModel* getModel(const std::string& model_name);
20 
22 
23  private:
24  // Name to imported model map; filled in by "load"
25  static std::map<std::string, HebirosModel> models;
26 
27  // The underlying C++ API model that is "owned" by this HebirosModel
28  std::unique_ptr<hebi::robot_model::RobotModel> model;
29 
30  // Loads any model on the given parameter name into the URDF model
31  static bool loadURDF(const std::string& description_param, urdf::Model& model);
32 
33  // Create a hebi robot model from the URDF; return object on success, empty
34  // pointer on failure.
35  static std::unique_ptr<hebi::robot_model::RobotModel> parseURDF(const urdf::Model& model);
36 };
37 
38 #endif
Represents a chain or tree of robot elements (rigid bodies and joints).
Definition: robot_model.hpp:86
HebirosModel(std::unique_ptr< hebi::robot_model::RobotModel > model_)
static std::map< std::string, HebirosModel > models
Definition: hebiros_model.h:25
static bool loadURDF(const std::string &description_param, urdf::Model &model)
hebi::robot_model::RobotModel & getModel()
static bool load(const std::string &name, const std::string &description_param)
std::unique_ptr< hebi::robot_model::RobotModel > model
Definition: hebiros_model.h:28
static std::unique_ptr< hebi::robot_model::RobotModel > parseURDF(const urdf::Model &model)


hebiros
Author(s): Xavier Artache , Matthew Tesch
autogenerated on Thu Sep 3 2020 04:08:14