seed_r7_upper_controller.h
Go to the documentation of this file.
1 #ifndef _UPPER_CONTROLLER_H_
2 #define _UPPER_CONTROLLER_H_
3 
4 #include <ros/ros.h>
6 
7 
8 namespace robot_hardware
9 {
10 
12 {
13  public:
14  UpperController(const std::string& _port);
16 
17  void getPosition();
18  void sendPosition(uint16_t _time, std::vector<int16_t>& _data);
19  void remapAeroToRos(std::vector<int16_t>& _ros, std::vector<int16_t>& _aero);
20  void remapRosToAero(std::vector<int16_t>& _aero, std::vector<int16_t>& _ros);
21  void setCurrent(uint8_t _number, uint8_t _max, uint8_t _down);
22  void runScript(uint8_t _number, uint16_t _script);
23  std::string getFirmwareVersion();
24  void checkRobotStatus();
25 
26  bool is_open_;
27  std::vector<int16_t> raw_data_;
28 
29  std::vector<std::string> name_;
30  std::vector<int> aero_index_;
31  std::vector<std::pair<int,std::string>> aero_table_;
32 
33  bool comm_err_;
34  struct RobotStatus {
36  bool calib_err_;
37  bool motor_err_;
38  bool temp_err_;
39  bool res_err_;
42  bool power_err_;
43  } robot_status_;
44 
45  protected:
47  const static uint32_t BAUDRATE = 1000000;
48 
65  can1_power = 15,
66  };
67 };
68 
69 }
70 
71 #endif
std::vector< std::pair< int, std::string > > aero_table_
UpperController(const std::string &_port)
void setCurrent(uint8_t _number, uint8_t _max, uint8_t _down)
struct robot_hardware::UpperController::RobotStatus robot_status_
aero::controller::AeroCommand * upper_
void runScript(uint8_t _number, uint16_t _script)
void remapAeroToRos(std::vector< int16_t > &_ros, std::vector< int16_t > &_aero)
void remapRosToAero(std::vector< int16_t > &_aero, std::vector< int16_t > &_ros)
void sendPosition(uint16_t _time, std::vector< int16_t > &_data)


seed_r7_ros_controller
Author(s): Yohei Kakiuchi
autogenerated on Sun Apr 18 2021 02:40:34