control_setting.h
Go to the documentation of this file.
1 #ifndef DXL_CONTROL_CONTROL_SETTING_H
2 #define DXL_CONTROL_CONTROL_SETTING_H
3 
4 #include <ros/ros.h>
5 #include <std_msgs/String.h>
6 #include <ros/console.h>
7 #include <string>
8 #include <sstream>
9 #include <map>
10 
11 /* Operating Mode value */
12 #define OPE_CURRENT_MODE (0)
13 #define OPE_VELOCITY_MODE (1)
14 #define OPE_POSITION_MODE (3)
15 #define OPE_EXT_POS_MODE (4)
16 #define OPE_CURR_POS_MODE (5)
17 #define OPE_PWM_MODE (16)
18 
19 /* SETTING KEY STRINGS */
20 #define KEY_DXL_PORT ("dynamixel_port")
21 #define KEY_PORTNAME ("/port_name")
22 #define KEY_BAUDRATE ("/baud_rate")
23 #define KEY_JOINTS ("/joints")
24 #define KEY_JPARAM_ID ("/id")
25 #define KEY_JPARAM_CENTER ("/center")
26 #define KEY_JPARAM_HOME ("/home")
27 #define KEY_JPARAM_EFFCNST ("/effort_const")
28 #define KEY_JPARAM_OPEMODE ("/mode")
29 
30 #define DEFAULT_CENTER (2048)
31 #define DEFAULT_EFF_CNST (1.0)
32 #define DEFAULT_OPE_MODE (OPE_POSITION_MODE)
33 
34 
35 typedef struct SERVO_PARAM {
37  name = "";
38  id = 0;
42  }
43  std::string name;
44  uint8_t id;
45  uint16_t center;
46  uint16_t home;
47  double eff_cnst;
48  uint8_t mode;
50 
52 {
53 public:
55  ~CONTROL_SETTING();
56  bool load( void );
57  std::string getPortName( void ){ return port_name; }
58  std::string loadPortName( void );
59  std::vector<ST_SERVO_PARAM> getServoParam( void ){ return joint_list; }
60  uint32_t getjointNum( void ){ return joint_num; }
61  uint32_t getBaudrate( void ){ return port_baud_rate; }
62 
63 private:
65  uint8_t port_num;
66  std::string port_name;
67  uint32_t port_baud_rate;
68  uint32_t joint_num;
69  std::vector<ST_SERVO_PARAM> joint_list;
70 
71  bool isPortDefine( void );
72  uint32_t loadBaudRate( void );
73  bool loadJointList( void );
74  bool loadJointParam( void );
75 };
76 
77 #endif/* DXL_CONTROL_CONTROL_SETTING_H */
uint32_t port_baud_rate
std::string name
uint32_t getjointNum(void)
ros::NodeHandle node_handle
uint16_t center
std::vector< ST_SERVO_PARAM > getServoParam(void)
struct SERVO_PARAM ST_SERVO_PARAM
#define DEFAULT_OPE_MODE
std::string getPortName(void)
uint16_t home
std::vector< ST_SERVO_PARAM > joint_list
uint32_t getBaudrate(void)
#define DEFAULT_CENTER
#define DEFAULT_EFF_CNST
std::string port_name


crane_x7_control
Author(s): Hiroyuki Nomura , Geoffrey Biggs
autogenerated on Mon Mar 1 2021 03:18:36