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:
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 */
CONTROL_SETTING::loadBaudRate
uint32_t loadBaudRate(void)
Definition: control_setting.cpp:69
CONTROL_SETTING::loadPortName
std::string loadPortName(void)
Definition: control_setting.cpp:55
SERVO_PARAM::eff_cnst
double eff_cnst
Definition: control_setting.h:47
DEFAULT_OPE_MODE
#define DEFAULT_OPE_MODE
Definition: control_setting.h:32
CONTROL_SETTING::port_num
uint8_t port_num
Definition: control_setting.h:65
SERVO_PARAM::home
uint16_t home
Definition: control_setting.h:46
CONTROL_SETTING::joint_num
uint32_t joint_num
Definition: control_setting.h:68
CONTROL_SETTING::CONTROL_SETTING
CONTROL_SETTING(ros::NodeHandle handle)
Definition: control_setting.cpp:9
ros.h
CONTROL_SETTING::getBaudrate
uint32_t getBaudrate(void)
Definition: control_setting.h:61
SERVO_PARAM::name
std::string name
Definition: control_setting.h:43
CONTROL_SETTING::loadJointList
bool loadJointList(void)
Definition: control_setting.cpp:83
DEFAULT_CENTER
#define DEFAULT_CENTER
Definition: control_setting.h:30
SERVO_PARAM::SERVO_PARAM
SERVO_PARAM()
Definition: control_setting.h:36
console.h
CONTROL_SETTING::load
bool load(void)
Definition: control_setting.cpp:22
SERVO_PARAM::id
uint8_t id
Definition: control_setting.h:44
SERVO_PARAM::center
uint16_t center
Definition: control_setting.h:45
DEFAULT_EFF_CNST
#define DEFAULT_EFF_CNST
Definition: control_setting.h:31
CONTROL_SETTING::getjointNum
uint32_t getjointNum(void)
Definition: control_setting.h:60
CONTROL_SETTING::isPortDefine
bool isPortDefine(void)
CONTROL_SETTING::port_name
std::string port_name
Definition: control_setting.h:66
CONTROL_SETTING::getServoParam
std::vector< ST_SERVO_PARAM > getServoParam(void)
Definition: control_setting.h:59
CONTROL_SETTING::loadJointParam
bool loadJointParam(void)
Definition: control_setting.cpp:113
CONTROL_SETTING::node_handle
ros::NodeHandle node_handle
Definition: control_setting.h:64
CONTROL_SETTING
Definition: control_setting.h:51
CONTROL_SETTING::port_baud_rate
uint32_t port_baud_rate
Definition: control_setting.h:67
SERVO_PARAM
Definition: control_setting.h:35
CONTROL_SETTING::getPortName
std::string getPortName(void)
Definition: control_setting.h:57
SERVO_PARAM::mode
uint8_t mode
Definition: control_setting.h:48
CONTROL_SETTING::~CONTROL_SETTING
~CONTROL_SETTING()
Definition: control_setting.cpp:17
ST_SERVO_PARAM
struct SERVO_PARAM ST_SERVO_PARAM
ros::NodeHandle
CONTROL_SETTING::joint_list
std::vector< ST_SERVO_PARAM > joint_list
Definition: control_setting.h:69


sciurus17_control
Author(s): Hiroyuki Nomura
autogenerated on Fri Aug 2 2024 08:37:24