joint_control.h
Go to the documentation of this file.
1 #ifndef DXL_JOINT_CONTROL_H
2 #define DXL_JOINT_CONTROL_H
3 
4 #include <cstdio>
5 #include <string>
9 #include <dynamic_reconfigure/server.h>
10 #include <sciurus17_msgs/ServoParameterConfig.h>
11 
12 // Protocol version
13 #define PROTOCOL_VERSION (2.0) // See which protocol version is used in the Dynamixel
14 
15 // DYNAMIXEL REGISTER TABLE (Dynamixel X)
16 typedef enum {
20 typedef struct {
21  std::string name; /* データ名称 */
22  uint32_t address; /* アドレス */
23  uint32_t length; /* データ長 */
24  uint32_t init_value; /* 初期値 */
25  EN_DXL_MEMTYPE type; /* メモリ種別 */
26  bool selfcheck; /* セルフチェック対象 */
28 
29 #define REG_LENGTH_BYTE (1)
30 #define REG_LENGTH_WORD (2)
31 #define REG_LENGTH_DWORD (4)
32 
33 typedef enum {
58 } EN_TABLE_ID;
59 
61  /* NAME ADDR LEN INIT TYPE */
62  { "RETURN_DELAY_TIME", 9, REG_LENGTH_BYTE, 250, enDXL_ROM, false },
63  { "DRIVE_MODE", 10, REG_LENGTH_BYTE, 0, enDXL_ROM, false },
64  { "OPERATION_MODE", 11, REG_LENGTH_BYTE, 3, enDXL_ROM, false },
65  { "HOMING_OFFSET", 20, REG_LENGTH_DWORD, 0, enDXL_ROM, false },
66  { "MOVING_THRESHOLD", 24, REG_LENGTH_DWORD, 10, enDXL_ROM, false },
67  { "TEMPRATURE_LIMIT", 31, REG_LENGTH_BYTE, 80, enDXL_ROM, false },
68  { "MAX_VOL_LIMIT", 32, REG_LENGTH_WORD, 160, enDXL_ROM, false },
69  { "MIN_VOL_LIMIT", 34, REG_LENGTH_WORD, 95, enDXL_ROM, false },
70  { "CURRENT_LIMIT", 38, REG_LENGTH_WORD, 1193, enDXL_ROM, false },
71  { "SHUTDOWN", 63, REG_LENGTH_BYTE, 52, enDXL_ROM, false },
72  { "TORQUE_ENABLE", 64, REG_LENGTH_BYTE, 0, enDXL_RAM, false },
73  { "VELOCITY_I_GAIN", 76, REG_LENGTH_WORD, 1920, enDXL_RAM, true },
74  { "VELOCITY_P_GAIN", 78, REG_LENGTH_WORD, 100, enDXL_RAM, true },
75  { "POSITION_D_GAIN", 80, REG_LENGTH_WORD, 0, enDXL_RAM, true },
76  { "POSITION_I_GAIN", 82, REG_LENGTH_WORD, 0, enDXL_RAM, true },
77  { "POSITION_P_GAIN", 84, REG_LENGTH_WORD, 800, enDXL_RAM, false },
78  { "BUS_WATCHDOG", 98, REG_LENGTH_BYTE, 0, enDXL_RAM, false },
79  { "GOAL_CURRENT", 102, REG_LENGTH_WORD, 0, enDXL_RAM, false },
80  { "GOAL_VELOCITY", 104, REG_LENGTH_DWORD, 0, enDXL_RAM, false },
81  { "GOAL_POSITION", 116, REG_LENGTH_DWORD, 0, enDXL_RAM, false },
82  { "PRESENT_CURRENT", 126, REG_LENGTH_WORD, 0, enDXL_RAM, false },
83  { "PRESENT_VELOCITY", 128, REG_LENGTH_DWORD, 0, enDXL_RAM, false },
84  { "PRESENT_POSITION", 132, REG_LENGTH_DWORD, 0, enDXL_RAM, false },
85  { "PRESENT_TEMPRATURE", 146, REG_LENGTH_BYTE, 0, enDXL_RAM, false },
86 };
87 
88 typedef struct ST_JOINT_PARAM
89 {
90  uint8_t dxl_id;
92  uint8_t drive_mode;
93  uint8_t operation_mode;
94  uint16_t moving_threshold;
95  int32_t homing_offset;
97  uint8_t max_vol_limit;
98  uint8_t min_vol_limit;
99  uint16_t current_limit;
100  uint8_t torque_enable;
101  uint16_t velocity_i_gain;
102  uint16_t velocity_p_gain;
103  uint16_t position_d_gain;
104  uint16_t position_i_gain;
105  uint16_t position_p_gain;
107 
108 // Parameter
109 #define BAUDRATE (3000000) // 通信速度
110 #define ADDR_RETURN_DELAY (RegTable[enTableId_ReturnDelay].address)
111 #define LEN_PRETURN_DELAY (RegTable[enTableId_ReturnDelay].length)
112 #define ADDR_DRIVE_MODE (RegTable[enTableId_DriveMode].address)
113 #define LEN_DRIVE_MODE (RegTable[enTableId_DriveMode].length)
114 #define ADDR_OPE_MODE (RegTable[enTableId_OpeMode].address)
115 #define LEN_OPE_MODE (RegTable[enTableId_OpeMode].length)
116 #define ADDR_HOMING_OFFSET (RegTable[enTableId_HomingOffset].address)
117 #define LEN_HOMING_OFFSET (RegTable[enTableId_HomingOffset].length)
118 #define ADDR_MOVING_THRESHOLD (RegTable[enTableId_MovingThreshold].address)
119 #define LEN_MOVING_THRESHOLD (RegTable[enTableId_MovingThreshold].length)
120 #define ADDR_TEMPRATURE_LIMIT (RegTable[enTableId_TempLimit].address)
121 #define LEN_TEMPRATURE_LIMIT (RegTable[enTableId_TempLimit].length)
122 #define ADDR_MAX_VOL_LIMIT (RegTable[enTableId_MaxVolLimit].address)
123 #define LEN_MAX_VOL_LIMIT (RegTable[enTableId_MaxVolLimit].length)
124 #define ADDR_MIN_VOL_LIMIT (RegTable[enTableId_MinVolLimit].address)
125 #define LEN_MIN_VOL_LIMIT (RegTable[enTableId_MinVolLimit].length)
126 #define ADDR_CURRENT_LIMIT (RegTable[enTableId_CurrentLimit].address)
127 #define LEN_CURRENT_LIMIT (RegTable[enTableId_CurrentLimit].length)
128 #define ADDR_TORQUE_ENABLE (RegTable[enTableId_TorqueEnable].address) // Control table address is different in Dynamixel model
129 #define ADDR_VELOCITY_IGAIN (RegTable[enTableId_VelocityIGain].address)
130 #define LEN_VELOCITY_IGAIN (RegTable[enTableId_VelocityIGain].length)
131 #define ADDR_VELOCITY_PGAIN (RegTable[enTableId_VelocityPGain].address)
132 #define LEN_VELOCITY_PGAIN (RegTable[enTableId_VelocityPGain].length)
133 #define ADDR_POSITION_DGAIN (RegTable[enTableId_PositionDGain].address)
134 #define LEN_POSITION_DGAIN (RegTable[enTableId_PositionDGain].length)
135 #define ADDR_POSITION_IGAIN (RegTable[enTableId_PositionIGain].address)
136 #define LEN_POSITION_IGAIN (RegTable[enTableId_PositionIGain].length)
137 #define ADDR_POSITION_PGAIN (RegTable[enTableId_PositionPGain].address)
138 #define LEN_POSITION_PGAIN (RegTable[enTableId_PositionPGain].length)
139 #define ADDR_BUS_WATCHDOG (RegTable[enTableId_BusWatchdog].address)
140 #define LEN_BUS_WATCHDOG (RegTable[enTableId_BusWatchdog].length)
141 #define ADDR_GOAL_CURRENT (RegTable[enTableId_GoalCurrent].address) // ゴールカレントアドレス
142 #define LEN_GOAL_CURRENT (RegTable[enTableId_GoalCurrent].length) // ゴールカレント
143 #define ADDR_GOAL_POSITION (RegTable[enTableId_GoalPosition].address) // ゴールポジションアドレス
144 #define LEN_GOAL_POSITION (RegTable[enTableId_GoalPosition].length) // ゴールポジション
145 #define ADDR_PRESENT_CURRENT (RegTable[enTableId_PresentCurrent].address)
146 #define LEN_PRESENT_CURRENT (RegTable[enTableId_PresentCurrent].length)
147 #define ADDR_PRESENT_VEL (RegTable[enTableId_PresentVelocity].address)
148 #define LEN_PRESENT_VEL (RegTable[enTableId_PresentVelocity].length)
149 #define ADDR_PRESENT_POSITION (RegTable[enTableId_PresentPosition].address)
150 #define LEN_PRESENT_POSITION (RegTable[enTableId_PresentPosition].length)
151 #define ADDR_PRESENT_TEMP (RegTable[enTableId_PresentTemp].address)
152 #define LEN_PRESENT_TEMP (RegTable[enTableId_PresentTemp].length)
153 
154 #define ADDR_INDIRECT_TOP (168)
155 #define DATA_INDIRECT_TOP (224)
156 #define LEN_INDIRECT_GROUP (12)
157 #define ADDR_INDIRECT_DXLID (DATA_INDIRECT_TOP)
158 #define LEN_INDIRECT_DXLID (1)
159 #define ADDR_INDIRECT_CURRENT (DATA_INDIRECT_TOP+1)
160 #define ADDR_INDIRECT_VELOCITY (DATA_INDIRECT_TOP+3)
161 #define ADDR_INDIRECT_POSITION (DATA_INDIRECT_TOP+7)
162 #define ADDR_INDIRECT_TEMP (DATA_INDIRECT_TOP+11)
163 
164 #define TORQUE_ENABLE (1) // Value for enabling the torque
165 #define TORQUE_DISABLE (0) // Value for disabling the torque
166 
167 #define POSITION_STEP (4096.0)
168 #define DXL_MIN_LIMIT (0.0)
169 #define DXL_MAX_LIMIT (4095.0)
170 #define DXL_CURRENT_UNIT (2.69) // mA
171 #define DXL_EFFORT_CONST (1.79)
172 #define DXL_TEMP_READ_DURATION (5)
173 #define DXL_PGAIN_MAX (16383)
174 #define DXL_DEFAULT_PGAIN (800)
175 #define DXL_FREE_PGAIN (0)
176 #define DXL_FREE_IGAIN (0)
177 #define DXL_FREE_DGAIN (0)
178 
179 #define DXL_OFFSET_DEFAULT (2048)
180 
181 #define DXL_TORQUE_ON_TIME (5*1000) // msec
182 #define DXL_TORQUR_ON_STEP (20) // Hz
183 #define DXL_TORQUE_ON_STEP_MAX (DXL_TORQUE_ON_TIME / (1000 / DXL_TORQUR_ON_STEP))
184 
185 #define DXL_CURRENT2EFFORT(c,coef) (DXL_CURRENT_UNIT * (c) * (coef) * 0.001)// (mA*CONST*0.001)=Nm
186 #define EFFORT2DXL_CURRENT(e,coef) ((e) / (coef) / 0.001 / DXL_CURRENT_UNIT)// (Nm/CONST/0.001)=mA
187 #define DEFAULT_MAX_EFFORT (5.0)
188 #define EFFORT_LIMITING_CNT (10)
189 #define DXL_VELOCITY2RAD_S(v) ((v) * 0.229 * 0.1047)
190 
191 #define DXL_WATCHDOG_RESET_VALUE (0)
192 #define MSEC2DXL_WATCHDOG(msec) ((uint8_t)(msec) / 20)
193 
194 #define OPERATING_MODE_CURRENT (0)
195 #define OPERATING_MODE_VELOCITY (1)
196 #define OPERATING_MODE_POSITION (3)
197 #define OPERATING_MODE_EXT_POS (4)
198 #define OPERATING_MODE_CURR_POS (5)
199 #define OPERATING_MODE_PWM (16)
200 
201 
202 // Joint control class
204 {
205 public:
206  JOINT_CONTROL(void);
207  JOINT_CONTROL( std::string init_name, uint8_t init_dxlid, uint16_t init_center, uint16_t init_home, double init_eff_const, uint8_t init_mode );
208  JOINT_CONTROL( const JOINT_CONTROL &src );
209  ~JOINT_CONTROL(void){ /* Nothing todo... */ }
210  void init_parameter( std::string init_name, uint8_t init_dxlid, uint16_t init_center, uint16_t init_home, double init_eff_const, uint8_t init_mode );
211  void set_joint_name( std::string set_name ) { name = set_name; }
212  void set_dxl_id( uint8_t set_id ){ id = set_id; }
213  void set_position( double set_rad ){ pos = set_rad; }
214  void set_velocity( double set_vel ){ vel = set_vel; }
215  void set_effort( double set_eff ){ eff = set_eff; }
216  void set_command( double set_cmd ){ cmd = set_cmd; }
217  void set_torque( bool set_trq ){ torque = set_trq; }
218  void set_center( uint16_t set_center ){ center = set_center; }
219  void set_home( uint16_t set_home ){ home = set_home; }
220  void set_current( double set_curr ){ curr = set_curr; }
221  void set_temprature( double set_temp ){ temp = set_temp; }
227  void set_eff_limiting( bool set_limiting ){ eff_limiting = set_limiting; }
228  void inc_eff_over( void ){ ++eff_over_cnt; }
229  void clear_eff_over( void ){ eff_over_cnt = 0; }
230  void set_joint_param( ST_JOINT_PARAM set_param){ param = set_param; }
231 
232  std::string get_joint_name( void ) { return name; }
233  uint8_t get_dxl_id( void ){ return id; }
234  double get_position( void ){ return pos; }
235  double* get_position_addr( void ){ return &pos; }
236  double get_velocity( void ){ return vel; }
237  double* get_velocity_addr( void ){ return &vel; }
238  double get_effort( void ){ return eff; }
240  double* get_effort_addr( void ){ return &eff; }
241  double get_command( void ){ return cmd; }
242  double* get_command_addr( void ){ return &cmd; }
243  bool get_torque( void ){ return torque; }
244  uint16_t get_center( void ){ return center; }
245  uint16_t get_home( void ){ return home; }
246  double get_current( void ){ return curr; }
247  double get_temprature( void ){ return temp; }
248  bool is_connect( void ){ return connect; }
249  uint32_t get_dxl_pos( void ){ return dxl_pos; }
250  uint16_t get_dxl_curr( void ){ return dxl_curr; }
251  uint8_t get_dxl_temp( void ){ return dxl_temp; }
252  uint8_t get_dxl_goal( void ){ return (uint32_t)(dxl_goal[0]&0x000000FF)
253  | (uint32_t)((dxl_goal[1]<<8)&0x0000FF00)
254  | (uint32_t)((dxl_goal[2]<<16)&0x00FF0000)
255  | (uint32_t)((dxl_goal[3]<<24)&0xFF0000FF); }
256  uint8_t* get_dxl_goal_addr( void ){ return dxl_goal; }
257  bool is_effort_limiting( void ){ return eff_limiting; }
258  uint8_t get_eff_over_cnt( void ){ return eff_over_cnt; }
259  double get_eff_const( void ){ return eff_const; }
260  uint8_t get_ope_mode( void ){ return ope_mode; }
262  void updt_d_command( double val ){ d_cmd = (val - prev_cmd); prev_cmd = val; }
263  double get_d_command( void ){ return d_cmd; }
264 
265 private:
266  std::string name; // ROS joint name
267  uint8_t id; // Dynamixel ServoID
268  double pos; // Present position
269  double vel; // Present verocity
270  double eff; // Present effort
271  double cmd; // ROS HwInterface value
272  double d_cmd; // cmd value delta
273  double prev_cmd; // Previous cmd value
274  double curr; // Present current[mA]
275  double temp; // Present temprature
276  bool torque; // Servo torque
277  uint16_t center; // Servo center position offset( dynamixel position value, default:2048 )
278  uint16_t home; // Servo home position( dynamixel position value )
279  bool connect; // Servo connect status
280  double eff_const; // Servo effort constant
281  bool eff_limiting;// Effort limiting status
282  uint8_t eff_over_cnt;// Effort limiting status
283  uint8_t ope_mode; // Operating mode
284 
285  double goal_pos; // Goal position[rad]
286  double goal_vel; // Goal velocity
287  double goal_eff; // Goal effort
288 
289  uint32_t dxl_pos; // Dynamixel present position
290  uint16_t dxl_curr; // Dynamixel current
291  uint8_t dxl_temp; // Dynamixel temprature
292  uint8_t dxl_goal[4];// Dynamixel goal position
293 
294  joint_limits_interface::JointLimits limits;// Joint limit parameters
295 
297 };
298 #endif /*DXL_JOINT_CONTROL_H */
JOINT_CONTROL::get_center
uint16_t get_center(void)
Definition: joint_control.h:244
ST_JOINT_PARAM::current_limit
uint16_t current_limit
Definition: joint_control.h:99
enTableId_DriveMode
@ enTableId_DriveMode
Definition: joint_control.h:35
ST_DYNAMIXEL_REG_TABLE::type
EN_DXL_MEMTYPE type
Definition: joint_control.h:25
JOINT_CONTROL::get_temprature
double get_temprature(void)
Definition: joint_control.h:247
JOINT_CONTROL::param
ST_JOINT_PARAM param
Definition: joint_control.h:296
JOINT_CONTROL::get_joint_param
ST_JOINT_PARAM get_joint_param(void)
Definition: joint_control.h:261
joint_limits_interface::JointLimits
JOINT_CONTROL::is_effort_limiting
bool is_effort_limiting(void)
Definition: joint_control.h:257
enTableId_MinVolLimit
@ enTableId_MinVolLimit
Definition: joint_control.h:41
JOINT_CONTROL::set_center
void set_center(uint16_t set_center)
Definition: joint_control.h:218
JOINT_CONTROL::get_dxl_goal_addr
uint8_t * get_dxl_goal_addr(void)
Definition: joint_control.h:256
JOINT_CONTROL::get_torque
bool get_torque(void)
Definition: joint_control.h:243
JOINT_CONTROL::set_position
void set_position(double set_rad)
Definition: joint_control.h:213
JOINT_CONTROL::get_dxl_pos
uint32_t get_dxl_pos(void)
Definition: joint_control.h:249
ST_JOINT_PARAM::temprature_limit
uint8_t temprature_limit
Definition: joint_control.h:96
JOINT_CONTROL::init_parameter
void init_parameter(std::string init_name, uint8_t init_dxlid, uint16_t init_center, uint16_t init_home, double init_eff_const, uint8_t init_mode)
Definition: joint_control.cpp:6
JOINT_CONTROL::set_velocity
void set_velocity(double set_vel)
Definition: joint_control.h:214
JOINT_CONTROL::get_dxl_temp
uint8_t get_dxl_temp(void)
Definition: joint_control.h:251
JOINT_CONTROL::get_eff_over_cnt
uint8_t get_eff_over_cnt(void)
Definition: joint_control.h:258
JOINT_CONTROL::set_dxl_id
void set_dxl_id(uint8_t set_id)
Definition: joint_control.h:212
JOINT_CONTROL::limits
joint_limits_interface::JointLimits limits
Definition: joint_control.h:294
JOINT_CONTROL::goal_eff
double goal_eff
Definition: joint_control.h:287
joint_limits_interface.h
JOINT_CONTROL
Definition: joint_control.h:203
JOINT_CONTROL::pos
double pos
Definition: joint_control.h:268
ST_JOINT_PARAM::torque_enable
uint8_t torque_enable
Definition: joint_control.h:100
JOINT_CONTROL::temp
double temp
Definition: joint_control.h:275
JOINT_CONTROL::set_joint_name
void set_joint_name(std::string set_name)
Definition: joint_control.h:211
enTableId_PositionPGain
@ enTableId_PositionPGain
Definition: joint_control.h:49
JOINT_CONTROL::inc_eff_over
void inc_eff_over(void)
Definition: joint_control.h:228
JOINT_CONTROL::eff
double eff
Definition: joint_control.h:270
JOINT_CONTROL::prev_cmd
double prev_cmd
Definition: joint_control.h:273
JOINT_CONTROL::d_cmd
double d_cmd
Definition: joint_control.h:272
enTableId_MaxVolLimit
@ enTableId_MaxVolLimit
Definition: joint_control.h:40
enTableId_VelocityIGain
@ enTableId_VelocityIGain
Definition: joint_control.h:45
JOINT_CONTROL::set_current
void set_current(double set_curr)
Definition: joint_control.h:220
JOINT_CONTROL::get_dxl_goal
uint8_t get_dxl_goal(void)
Definition: joint_control.h:252
enTableId_GoalVelocity
@ enTableId_GoalVelocity
Definition: joint_control.h:52
REG_LENGTH_DWORD
#define REG_LENGTH_DWORD
Definition: joint_control.h:31
enTableId_HomingOffset
@ enTableId_HomingOffset
Definition: joint_control.h:37
joint_limits.h
JOINT_CONTROL::ope_mode
uint8_t ope_mode
Definition: joint_control.h:283
ST_JOINT_PARAM::homing_offset
int32_t homing_offset
Definition: joint_control.h:95
JOINT_CONTROL::get_effort_addr
double * get_effort_addr(void)
Definition: joint_control.h:240
REG_LENGTH_BYTE
#define REG_LENGTH_BYTE
Definition: joint_control.h:29
ST_DYNAMIXEL_REG_TABLE::address
uint32_t address
Definition: joint_control.h:22
RegTable
static const ST_DYNAMIXEL_REG_TABLE RegTable[]
Definition: joint_control.h:60
JOINT_CONTROL::get_effort
double get_effort(void)
Definition: joint_control.h:238
JOINT_CONTROL::set_dxl_curr
void set_dxl_curr(uint16_t set_dxl_curr)
Definition: joint_control.h:224
enTableId_Shutdown
@ enTableId_Shutdown
Definition: joint_control.h:43
enTableId_TempLimit
@ enTableId_TempLimit
Definition: joint_control.h:39
JOINT_CONTROL::set_temprature
void set_temprature(double set_temp)
Definition: joint_control.h:221
JOINT_CONTROL::get_command
double get_command(void)
Definition: joint_control.h:241
JOINT_CONTROL::is_connect
bool is_connect(void)
Definition: joint_control.h:248
enDXL_RAM
@ enDXL_RAM
Definition: joint_control.h:18
joint_limits_interface::JointLimits::max_effort
double max_effort
ST_JOINT_PARAM::moving_threshold
uint16_t moving_threshold
Definition: joint_control.h:94
ST_JOINT_PARAM::position_p_gain
uint16_t position_p_gain
Definition: joint_control.h:105
JOINT_CONTROL::set_eff_limiting
void set_eff_limiting(bool set_limiting)
Definition: joint_control.h:227
enTableId_BusWatchdog
@ enTableId_BusWatchdog
Definition: joint_control.h:50
JOINT_CONTROL::goal_pos
double goal_pos
Definition: joint_control.h:285
JOINT_CONTROL::set_joint_param
void set_joint_param(ST_JOINT_PARAM set_param)
Definition: joint_control.h:230
JOINT_CONTROL::get_joint_name
std::string get_joint_name(void)
Definition: joint_control.h:232
JOINT_CONTROL::get_ope_mode
uint8_t get_ope_mode(void)
Definition: joint_control.h:260
JOINT_CONTROL::id
uint8_t id
Definition: joint_control.h:267
JOINT_CONTROL::set_torque
void set_torque(bool set_trq)
Definition: joint_control.h:217
JOINT_CONTROL::set_dxl_pos
void set_dxl_pos(uint32_t set_dxl_pos)
Definition: joint_control.h:223
enTableId_GoalCurrent
@ enTableId_GoalCurrent
Definition: joint_control.h:51
JOINT_CONTROL::set_connect
void set_connect(bool set_connect)
Definition: joint_control.h:222
ST_DYNAMIXEL_REG_TABLE::init_value
uint32_t init_value
Definition: joint_control.h:24
ST_JOINT_PARAM
struct ST_JOINT_PARAM ST_JOINT_PARAM
enTableId_PositionIGain
@ enTableId_PositionIGain
Definition: joint_control.h:48
ST_JOINT_PARAM::max_vol_limit
uint8_t max_vol_limit
Definition: joint_control.h:97
JOINT_CONTROL::get_eff_const
double get_eff_const(void)
Definition: joint_control.h:259
ST_DYNAMIXEL_REG_TABLE
Definition: joint_control.h:20
JOINT_CONTROL::dxl_temp
uint8_t dxl_temp
Definition: joint_control.h:291
ST_JOINT_PARAM::velocity_p_gain
uint16_t velocity_p_gain
Definition: joint_control.h:102
joint_limits_rosparam.h
ST_DYNAMIXEL_REG_TABLE::name
std::string name
Definition: joint_control.h:21
JOINT_CONTROL::vel
double vel
Definition: joint_control.h:269
EN_DXL_MEMTYPE
EN_DXL_MEMTYPE
Definition: joint_control.h:16
enTableId_PresentPosition
@ enTableId_PresentPosition
Definition: joint_control.h:56
ST_JOINT_PARAM::position_i_gain
uint16_t position_i_gain
Definition: joint_control.h:104
enTableId_PositionDGain
@ enTableId_PositionDGain
Definition: joint_control.h:47
JOINT_CONTROL::dxl_curr
uint16_t dxl_curr
Definition: joint_control.h:290
enTableId_TorqueEnable
@ enTableId_TorqueEnable
Definition: joint_control.h:44
JOINT_CONTROL::goal_vel
double goal_vel
Definition: joint_control.h:286
JOINT_CONTROL::updt_d_command
void updt_d_command(double val)
Definition: joint_control.h:262
JOINT_CONTROL::set_home
void set_home(uint16_t set_home)
Definition: joint_control.h:219
JOINT_CONTROL::dxl_pos
uint32_t dxl_pos
Definition: joint_control.h:289
EN_TABLE_ID
EN_TABLE_ID
Definition: joint_control.h:33
JOINT_CONTROL::get_command_addr
double * get_command_addr(void)
Definition: joint_control.h:242
ST_JOINT_PARAM::operation_mode
uint8_t operation_mode
Definition: joint_control.h:93
enTableId_PresentVelocity
@ enTableId_PresentVelocity
Definition: joint_control.h:55
JOINT_CONTROL::home
uint16_t home
Definition: joint_control.h:278
enTableId_MovingThreshold
@ enTableId_MovingThreshold
Definition: joint_control.h:38
ST_DYNAMIXEL_REG_TABLE::length
uint32_t length
Definition: joint_control.h:23
enTableId_PresentCurrent
@ enTableId_PresentCurrent
Definition: joint_control.h:54
ST_DYNAMIXEL_REG_TABLE::selfcheck
bool selfcheck
Definition: joint_control.h:26
ST_JOINT_PARAM::min_vol_limit
uint8_t min_vol_limit
Definition: joint_control.h:98
JOINT_CONTROL::connect
bool connect
Definition: joint_control.h:279
JOINT_CONTROL::set_effort
void set_effort(double set_eff)
Definition: joint_control.h:215
JOINT_CONTROL::eff_over_cnt
uint8_t eff_over_cnt
Definition: joint_control.h:282
enTableId_OpeMode
@ enTableId_OpeMode
Definition: joint_control.h:36
JOINT_CONTROL::cmd
double cmd
Definition: joint_control.h:271
ST_JOINT_PARAM::return_delay_time
uint8_t return_delay_time
Definition: joint_control.h:91
JOINT_CONTROL::set_limits
void set_limits(joint_limits_interface::JointLimits &set_limits)
Definition: joint_control.h:226
JOINT_CONTROL::eff_const
double eff_const
Definition: joint_control.h:280
JOINT_CONTROL::get_max_effort
double get_max_effort(void)
Definition: joint_control.h:239
enTableId_CurrentLimit
@ enTableId_CurrentLimit
Definition: joint_control.h:42
enTableId_ReturnDelay
@ enTableId_ReturnDelay
Definition: joint_control.h:34
JOINT_CONTROL::get_dxl_curr
uint16_t get_dxl_curr(void)
Definition: joint_control.h:250
JOINT_CONTROL::set_dxl_temp
void set_dxl_temp(uint8_t set_dxl_temp)
Definition: joint_control.h:225
JOINT_CONTROL::~JOINT_CONTROL
~JOINT_CONTROL(void)
Definition: joint_control.h:209
JOINT_CONTROL::get_current
double get_current(void)
Definition: joint_control.h:246
enTableId_PresentTemp
@ enTableId_PresentTemp
Definition: joint_control.h:57
JOINT_CONTROL::get_home
uint16_t get_home(void)
Definition: joint_control.h:245
JOINT_CONTROL::dxl_goal
uint8_t dxl_goal[4]
Definition: joint_control.h:292
JOINT_CONTROL::get_d_command
double get_d_command(void)
Definition: joint_control.h:263
JOINT_CONTROL::get_velocity_addr
double * get_velocity_addr(void)
Definition: joint_control.h:237
JOINT_CONTROL::center
uint16_t center
Definition: joint_control.h:277
JOINT_CONTROL::get_position
double get_position(void)
Definition: joint_control.h:234
JOINT_CONTROL::name
std::string name
Definition: joint_control.h:266
JOINT_CONTROL::curr
double curr
Definition: joint_control.h:274
JOINT_CONTROL::JOINT_CONTROL
JOINT_CONTROL(void)
Definition: joint_control.cpp:41
ST_JOINT_PARAM::drive_mode
uint8_t drive_mode
Definition: joint_control.h:92
JOINT_CONTROL::clear_eff_over
void clear_eff_over(void)
Definition: joint_control.h:229
JOINT_CONTROL::get_position_addr
double * get_position_addr(void)
Definition: joint_control.h:235
JOINT_CONTROL::eff_limiting
bool eff_limiting
Definition: joint_control.h:281
JOINT_CONTROL::get_dxl_id
uint8_t get_dxl_id(void)
Definition: joint_control.h:233
JOINT_CONTROL::set_command
void set_command(double set_cmd)
Definition: joint_control.h:216
REG_LENGTH_WORD
#define REG_LENGTH_WORD
Definition: joint_control.h:30
ST_JOINT_PARAM::velocity_i_gain
uint16_t velocity_i_gain
Definition: joint_control.h:101
DEFAULT_MAX_EFFORT
#define DEFAULT_MAX_EFFORT
Definition: joint_control.h:187
JOINT_CONTROL::torque
bool torque
Definition: joint_control.h:276
enTableId_GoalPosition
@ enTableId_GoalPosition
Definition: joint_control.h:53
ST_JOINT_PARAM
Definition: joint_control.h:88
ST_JOINT_PARAM::dxl_id
uint8_t dxl_id
Definition: joint_control.h:90
ST_JOINT_PARAM::position_d_gain
uint16_t position_d_gain
Definition: joint_control.h:103
joint_limits_interface::JointLimits::has_effort_limits
bool has_effort_limits
JOINT_CONTROL::get_velocity
double get_velocity(void)
Definition: joint_control.h:236
enTableId_VelocityPGain
@ enTableId_VelocityPGain
Definition: joint_control.h:46
enDXL_ROM
@ enDXL_ROM
Definition: joint_control.h:17


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