dxlport_control.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <ros/package.h>
3 #include <angles/angles.h>
5 #include <math.h>
6 #include <stdio.h>
7 
8 #define EFFORT_LIMIT_COEF (0.95)
9 
10 /* MACRO */
11 #define DXLPOS2RAD(pos) (( ((pos)*(360.0/POSITION_STEP) )/360) *2*M_PI)
12 #define RAD2DXLPOS(rad) (( ((rad)/2.0/M_PI)*360.0 ) * (POSITION_STEP / 360.0))
13 #define INIT_EFFCNST_UNIT(c) ((c)*0.001)
14 
15 
17 {
18  int jj;
21  int position_mode_joint_num = 0;
22  int current_mode_joint_num = 0;
23 
24  init_stat = false;
25  tx_err = rx_err = 0;
26  tempCount = 0;
27  tempTime = getTime();
28 
29  portHandler = NULL;
30  writeGoalGroup = NULL;
31  readTempGroup = NULL;
32  readMovementGroup= NULL;
33 
34  joint_num = setting.getjointNum();
35  std::vector<ST_SERVO_PARAM> list = setting.getServoParam();
36  for( jj=0 ; jj<joint_num ; ++jj ){
37  JOINT_CONTROL work( list[jj].name, list[jj].id, list[jj].center, list[jj].home, list[jj].eff_cnst, list[jj].mode );
38  joints.push_back( work );
39  }
40 
41  /* DynamixelSDKとros_controlへの接続初期化 */
47 
48  for( jj=0 ; jj<joint_num ; ++jj ){
49  uint8_t dxl_id = joints[jj].get_dxl_id();
50  if( joints[jj].get_ope_mode() == OPERATING_MODE_CURRENT ){
51  //CURRENT MODE
52  if( !writeGoalGroup->addParam( dxl_id, ADDR_GOAL_CURRENT, LEN_GOAL_CURRENT, joints[jj].get_dxl_goal_addr() ) ){// [TODO]
53  error_queue.push("Bulk current write setting failed.");
54  return;
55  }
56  }else{
57  //POSITION MODE
58  if( !writeGoalGroup->addParam( dxl_id, ADDR_GOAL_POSITION, LEN_GOAL_POSITION, joints[jj].get_dxl_goal_addr() ) ){// [TODO]
59  error_queue.push("Bulk pos write setting failed.");
60  return;
61  }
62  }
64  error_queue.push("Bulk temp read setting failed.");
65  return;
66  }
68  error_queue.push("Bulk group read setting failed.");
69  return;
70  }
71  }
72 
73  // Open port
74  if( !portHandler->openPort() ){
75  error_queue.push("Port open failed.");
76  port_stat = false;
77  }else{
78  // Set port baudrate
79  if( !portHandler->setBaudRate( setting.getBaudrate() ) ){
80  error_queue.push("Setup baudrate failed.");
81  port_stat = false;
82  }else{
83  port_stat = true; // 有効と仮定してread
84  if( !read( ros::Time::now(), ros::Duration(0) ) ){
85  error_queue.push("Initialize communication failed.");
86  port_stat = false;
87  }
88  }
89  }
90  for( jj=0 ; jj<joint_num ; ++jj ){
91  hardware_interface::JointStateHandle reg_state_handle( joints[jj].get_joint_name(), joints[jj].get_position_addr(), joints[jj].get_velocity_addr(), joints[jj].get_effort_addr() );
92  joint_stat_if.registerHandle( reg_state_handle );
93  }
95 
96  for( jj=0 ; jj<joint_num ; ++jj ){
97  hardware_interface::JointHandle reg_joint_handle( joint_stat_if.getHandle(joints[jj].get_joint_name()), joints[jj].get_command_addr() );
98  if( joints[jj].get_ope_mode() == OPERATING_MODE_CURRENT ){
99  joint_eff_if.registerHandle( reg_joint_handle );
100  ++current_mode_joint_num;
101  }else{
102  joint_pos_if.registerHandle( reg_joint_handle );
103  ++position_mode_joint_num;
104  }
105  // Get limits
106  if( joint_limits_interface::getJointLimits( joints[jj].get_joint_name(), handle, limits ) ){
107  joints[jj].set_limits( limits );
108  soft_limits.k_position = 1.0;
109  soft_limits.k_velocity = 1.0;
110  soft_limits.max_position = limits.max_position;
111  soft_limits.min_position = limits.min_position;
113  reg_limits_handle( reg_joint_handle, limits, soft_limits );
114  joint_limits_if.registerHandle( reg_limits_handle );
115  }
116  }
117  if( position_mode_joint_num > 0 ){
119  }
120  if( current_mode_joint_num > 0 ){
122  }
123 
124  init_stat = true;
125 }
126 
128 {
130  delete( portHandler );
131  /* packetHandlerはdeleteしないほうが良さそう */
132  if(readTempGroup!=NULL) delete( readTempGroup );
133  if(writeGoalGroup!=NULL) delete( writeGoalGroup );
134  if(readMovementGroup!=NULL) delete( readMovementGroup );
135 }
136 
138 {
139  bool result = false;
140 
141  if( !port_stat ){
142  return true;
143  }
144 
145  int dxl_comm_result = readMovementGroup->txRxPacket();
146  if (dxl_comm_result != COMM_SUCCESS){
147  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
148  ++rx_err;
149  }else{
150  readCurrent( time, period );
151  readVel( time, period );
152  readPos( time, period );
153  result = true;
154  }
155  if( (time - tempTime).toSec() > DXL_TEMP_READ_DURATION ){
156  readTemp( time, period );
157  tempTime = time;
158  }
159  return result;
160 }
161 
163 {
164  for( int jj=0 ; jj<joint_num ; ++jj ){
165  int32_t present_pos = 0;
166  uint8_t dxl_id = joints[jj].get_dxl_id();
167  bool dxl_getdata_result = readMovementGroup->isAvailable( dxl_id, ADDR_PRESENT_POSITION, LEN_PRESENT_POSITION );
168  if( !dxl_getdata_result ){
169  ++rx_err;
170  break;
171  }else{
173  joints[jj].set_dxl_pos( present_pos );
174  present_pos = (present_pos - joints[jj].get_center());
175  joints[jj].set_position( DXLPOS2RAD( present_pos ) );
176  }
177  }
178 }
179 
181 {
182  for( int jj=0 ; jj<joint_num ; ++jj ){
183  int16_t present_current = 0;
184  uint8_t dxl_id = joints[jj].get_dxl_id();
185  bool dxl_getdata_result = readMovementGroup->isAvailable( dxl_id, ADDR_PRESENT_CURRENT, LEN_PRESENT_CURRENT );
186  if( !dxl_getdata_result ){
187  ++rx_err;
188  break;
189  }else{
190  present_current = readMovementGroup->getData( dxl_id, ADDR_PRESENT_CURRENT, LEN_PRESENT_CURRENT );
191  joints[jj].set_dxl_curr( present_current );
192  joints[jj].set_current( (DXL_CURRENT_UNIT * present_current) );
193  joints[jj].set_effort( DXL_CURRENT2EFFORT( present_current, joints[jj].get_eff_const() ) );
194  }
195  }
196 }
197 
199 {
200  int dxl_comm_result = readTempGroup->txRxPacket();
201  if (dxl_comm_result != COMM_SUCCESS){
202  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
203  ++rx_err;
204  }else{
205  for( int jj=0 ; jj<joint_num ; ++jj ){
206  uint8_t dxl_id = joints[jj].get_dxl_id();
207  bool dxl_getdata_result = readTempGroup->isAvailable( dxl_id, ADDR_PRESENT_TEMP, LEN_PRESENT_TEMP );
208  if( !dxl_getdata_result ){
209  ++rx_err;
210  break;
211  }else{
212  uint8_t present_temp = readTempGroup->getData( dxl_id, ADDR_PRESENT_TEMP, LEN_PRESENT_TEMP );
213  joints[jj].set_dxl_temp( present_temp );
214  joints[jj].set_temprature( present_temp );
215  }
216  }
217  ++tempCount;
218  }
219 }
220 
222 {
223  for( int jj=0 ; jj<joint_num ; ++jj ){
224  uint8_t dxl_id = joints[jj].get_dxl_id();
225  bool dxl_getdata_result = readMovementGroup->isAvailable( dxl_id, ADDR_PRESENT_VEL, LEN_PRESENT_VEL );
226  if( !dxl_getdata_result ){
227  ++rx_err;
228  break;
229  }else{
230  int32_t present_velocity = readMovementGroup->getData( dxl_id, ADDR_PRESENT_VEL, LEN_PRESENT_VEL );
231  joints[jj].set_velocity( DXL_VELOCITY2RAD_S(present_velocity) );
232  }
233  }
234 }
235 
237 {
238  double get_cmd;
239 
240  if( !port_stat){
241  for( int jj=0 ; jj<joint_num ; ++jj ){
242  get_cmd = joints[jj].get_command();
243  joints[jj].updt_d_command( get_cmd );
244  joints[jj].set_position( get_cmd );
245  }
246  return;
247  }
248  for( int jj=0 ; jj<joint_num ; ++jj ){
249  get_cmd = joints[jj].get_command();
250  if( joints[jj].get_ope_mode() == OPERATING_MODE_CURRENT ){
251  // Current control
252  double work_cur = EFFORT2DXL_CURRENT( get_cmd, joints[jj].get_eff_const() );
253  joints[jj].updt_d_command( 0.0 );
254 
255  uint16_t dxl_cur = (uint32_t)round( work_cur );
256  uint8_t* goal_data = joints[jj].get_dxl_goal_addr();
257  goal_data[0] = (uint8_t)(dxl_cur&0x000000FF);
258  goal_data[1] = (uint8_t)((dxl_cur&0x0000FF00)>>8);
259 
260  writeGoalGroup->changeParam( joints[jj].get_dxl_id(), ADDR_GOAL_CURRENT, LEN_GOAL_CURRENT, goal_data );
261  }else{
262  // Position control
263  double work_pos = RAD2DXLPOS( get_cmd );
264  joints[jj].updt_d_command( get_cmd );
265  work_pos += joints[jj].get_center(); // ROS(-180 <=> +180) => DXL(0 <=> 4095)
266  if( work_pos < DXL_MIN_LIMIT ){
267  work_pos = DXL_MIN_LIMIT;
268  }
269  if( work_pos > DXL_MAX_LIMIT ){
270  work_pos = DXL_MAX_LIMIT;
271  }
272 
273  uint32_t dxl_pos = (uint32_t)round( work_pos );
274  uint8_t* goal_data = joints[jj].get_dxl_goal_addr();
275 
276  goal_data[0] = (uint8_t)(dxl_pos&0x000000FF);
277  goal_data[1] = (uint8_t)((dxl_pos&0x0000FF00)>>8);
278  goal_data[2] = (uint8_t)((dxl_pos&0x00FF0000)>>16);
279  goal_data[3] = (uint8_t)((dxl_pos&0xFF000000)>>24);
280 
281  writeGoalGroup->changeParam( joints[jj].get_dxl_id(), ADDR_GOAL_POSITION, LEN_GOAL_POSITION, goal_data );
282  }
283  }
284  int dxl_comm_result = writeGoalGroup->txPacket();
285  if( dxl_comm_result != COMM_SUCCESS ){
286  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
287  ++tx_err;
288  }
289 }
290 
292 {
293  bool result = false;
294 
295  for( int jj=0 ; jj<joint_num ; ++jj ){
296  if( fabs( joints[jj].get_d_command() ) > 0.0 ){
297  result = true;
298  }
299  }
300  return result;
301 }
302 
303 void DXLPORT_CONTROL::set_gain_all( uint16_t gain )
304 {
305  if( !port_stat ){
306  return;
307  }
308  for( int jj=0 ; jj<joint_num ; ++jj ){
309  if( joints[jj].get_ope_mode() == OPERATING_MODE_CURRENT ){
310  continue;
311  }
312  set_gain( joints[jj].get_dxl_id(), gain );
313  }
314 }
315 
316 void DXLPORT_CONTROL::set_gain( uint8_t dxl_id, uint16_t gain )
317 {
318  uint8_t dxl_error = 0; // Dynamixel error
319 
320  int dxl_comm_result = packetHandler->write2ByteTxRx( portHandler, dxl_id, ADDR_POSITION_PGAIN, gain, &dxl_error );
321  if( dxl_comm_result != COMM_SUCCESS ){
322  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
323  ++tx_err;
324  }else if( dxl_error != 0 ){
325  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
326  ++tx_err;
327  }
328 }
329 
331 {
332  if( !port_stat ){
333  return;
334  }
335  for( int jj=0 ; jj<joint_num ; ++jj ){
336  if( joints[jj].get_ope_mode() == OPERATING_MODE_CURRENT ){
337  set_goal_current( joints[jj].get_dxl_id(), current );
338  }
339  }
340 }
341 
342 
343 void DXLPORT_CONTROL::set_goal_current( uint8_t dxl_id, uint16_t current )
344 {
345  uint8_t dxl_error = 0; // Dynamixel error
346 
347  int dxl_comm_result = packetHandler->write2ByteTxRx( portHandler, dxl_id, ADDR_GOAL_CURRENT, current, &dxl_error );
348  if( dxl_comm_result != COMM_SUCCESS ){
349  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
350  ++tx_err;
351  }else if( dxl_error != 0 ){
352  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
353  ++tx_err;
354  }
355 }
356 
357 bool DXLPORT_CONTROL::set_torque( uint8_t dxl_id, bool torque )
358 {
359  uint32_t set_param = torque ? TORQUE_ENABLE:TORQUE_DISABLE;
360  bool result = false;
361 
362  if( !port_stat ){
363  return true;
364  }
365 
366  uint8_t dxl_error = 0; // Dynamixel error
367  int dxl_comm_result = packetHandler->write1ByteTxRx( portHandler, dxl_id, ADDR_TORQUE_ENABLE, set_param, &dxl_error );
368  if( dxl_comm_result != COMM_SUCCESS ){
369  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
370  ++tx_err;
371  }else if( dxl_error != 0 ){
372  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
373  ++tx_err;
374  }else{
375  result = true;
376  }
377  return result;
378 }
380 {
381  for( uint8_t jj=0 ; jj<joint_num; ++jj ){
382  if( set_torque( joints[jj].get_dxl_id(), torque ) ){
383  joints[jj].set_torque( torque );
384  }
385  }
386 }
387 
388 void DXLPORT_CONTROL::set_watchdog( uint8_t dxl_id, uint8_t value )
389 {
390  if( !port_stat ){
391  return;
392  }
393 
394  uint8_t dxl_error = 0; // Dynamixel error
395  int dxl_comm_result = packetHandler->write1ByteTxRx( portHandler, dxl_id, ADDR_BUS_WATCHDOG, value, &dxl_error );
396  if( dxl_comm_result != COMM_SUCCESS ){
397  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
398  ++tx_err;
399  }else if( dxl_error != 0 ){
400  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
401  ++tx_err;
402  }
403 }
404 
406 {
407  for( uint8_t jj=0 ; jj<joint_num; ++jj ){
408  set_watchdog( joints[jj].get_dxl_id(), value );
409  }
410 }
411 
412 /* 起動時モーション */
414 {
416  int step_max = DXL_TORQUE_ON_STEP_MAX;
417  ros::Time t = getTime();
419  std::vector<ST_HOME_MOTION_DATA> home_motion_data;
420 
421  /* 開始位置取り込みと差分計算 */
422  read( t, d );
423 
424  for( int jj=0 ; jj<joint_num ; ++jj ){
425  ST_HOME_MOTION_DATA motion_work;
426  motion_work.home = joints[jj].get_home();
427  motion_work.home_rad = DXLPOS2RAD( motion_work.home ) - DXLPOS2RAD( joints[jj].get_center() );
428  motion_work.start_rad = joints[jj].get_position();
429  motion_work.start = RAD2DXLPOS( motion_work.start_rad ) + joints[jj].get_center();
430  motion_work.step_rad =
431  (motion_work.home > motion_work.start) ? ((motion_work.home_rad - motion_work.start_rad)/step_max)
432  : -((motion_work.start_rad - motion_work.home_rad)/step_max);
433  if( joints[jj].get_ope_mode() == OPERATING_MODE_CURRENT ){
434  joints[jj].set_command( 0.0 );
435  }else{
436  joints[jj].set_command( joints[jj].get_position() );
437  }
438  home_motion_data.push_back( motion_work );
439  }
440  write( t, d );
441 
442  set_torque_all( true ); // 全関節トルクON
444 
445  /* ホームポジションへ移動する */
446  for( int step=0 ; step<step_max ; ++step ){
447  d = getDuration(t);
448  t = getTime();
449  read( t, d );
450  if( !port_stat ){
451  for( int jj=0 ; jj<joint_num ; ++jj ){
452  if( joints[jj].get_ope_mode() == OPERATING_MODE_CURRENT ){
453  continue;
454  }
455  joints[jj].set_command( DXLPOS2RAD( joints[jj].get_home() ) - DXLPOS2RAD( joints[jj].get_center() ) );
456  }
457  continue;
458  }
459  for( int jj=0 ; jj<joint_num ; ++jj ){
460  if( joints[jj].get_ope_mode() == OPERATING_MODE_CURRENT ){
461  continue;
462  }
463  joints[jj].set_command( joints[jj].get_command() + home_motion_data[jj].step_rad );
464  }
465  write( t, d );
466  rate.sleep();
467  }
468  for( int jj=0 ; jj<joint_num ; ++jj ){
469  if( joints[jj].get_ope_mode() == OPERATING_MODE_CURRENT ){
470  continue;
471  }
472  joints[jj].set_command( home_motion_data[jj].home_rad );
473  }
474  write( t, d );
475  for( int jj=0 ; jj<joint_num ; ++jj ){
476  joints[jj].updt_d_command( 0.0 );//差分の初期化
477  }
478 }
479 
480 /* セルフチェック */
481 bool DXLPORT_CONTROL::check_servo_param( uint8_t dxl_id, uint32_t test_addr, uint8_t equal, uint8_t& read_val )
482 {
483  uint8_t dxl_error = 0; // Dynamixel error
484  uint8_t read_data;
485  bool result = false;
486 
487  int dxl_comm_result = packetHandler->read1ByteTxRx(portHandler, dxl_id, test_addr, &read_data, &dxl_error);
488  if( dxl_comm_result != COMM_SUCCESS ){
489  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
490  ++rx_err;
491  }else if( dxl_error != 0 ){
492  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
493  ++rx_err;
494  }
495  if( read_data == equal ){
496  result = true;
497  }
498  read_val = read_data;
499  return result;
500 }
501 bool DXLPORT_CONTROL::check_servo_param( uint8_t dxl_id, uint32_t test_addr, uint16_t equal, uint16_t& read_val )
502 {
503  uint8_t dxl_error = 0; // Dynamixel error
504  uint16_t read_data;
505  bool result = false;
506 
507  int dxl_comm_result = packetHandler->read2ByteTxRx(portHandler, dxl_id, test_addr, &read_data, &dxl_error);
508  if( dxl_comm_result != COMM_SUCCESS ){
509  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
510  ++rx_err;
511  }else if( dxl_error != 0 ){
512  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
513  ++rx_err;
514  }
515  if( read_data == equal ){
516  result = true;
517  }
518  read_val = read_data;
519  return result;
520 }
521 bool DXLPORT_CONTROL::check_servo_param( uint8_t dxl_id, uint32_t test_addr, uint32_t equal, uint32_t& read_val )
522 {
523  uint8_t dxl_error = 0; // Dynamixel error
524  uint32_t read_data;
525  bool result = false;
526 
527  int dxl_comm_result = packetHandler->read4ByteTxRx(portHandler, dxl_id, test_addr, &read_data, &dxl_error);
528  if( dxl_comm_result != COMM_SUCCESS ){
529  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
530  ++rx_err;
531  }else if( dxl_error != 0 ){
532  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
533  ++rx_err;
534  }
535  if( read_data == equal ){
536  result = true;
537  }
538  read_val = read_data;
539  return result;
540 }
541 
542 void DXLPORT_CONTROL::init_joint_params( ST_JOINT_PARAM &param, int table_id, int value )
543 {
544  switch( table_id ){
546  param.return_delay_time = (uint8_t)value;
547  break;
548  case enTableId_DriveMode:
549  param.drive_mode = (uint8_t)value;
550  break;
551  case enTableId_OpeMode:
552  param.operation_mode = (uint8_t)value;
553  break;
555  param.homing_offset = (int32_t)value;
556  break;
558  param.moving_threshold = (uint16_t)value;
559  break;
560  case enTableId_TempLimit:
561  param.temprature_limit = (uint8_t)value;
562  break;
564  param.max_vol_limit = (uint8_t)value;
565  break;
567  param.min_vol_limit = (uint8_t)value;
568  break;
570  param.current_limit = (uint16_t)value;
571  break;
573  param.torque_enable = (uint8_t)value;
574  break;
576  param.velocity_i_gain = (uint16_t)value;
577  break;
579  param.velocity_p_gain = (uint16_t)value;
580  break;
582  param.position_d_gain = (uint16_t)value;
583  break;
585  param.position_i_gain = (uint16_t)value;
586  break;
588  param.position_p_gain = (uint16_t)value;
589  break;
597  case enTableId_Shutdown:
598  default:
599  break;
600  }
601 }
602 
603 std::string DXLPORT_CONTROL::self_check( void )
604 {
605  std::string res_str = "[DYNAMIXEL PARAMETER SELF CHECK]\n";
606 
607  if( !port_stat ){
608  res_str = "SKIP SELF CHECK...";
609  return res_str;
610  }
611  for( int ii=0 ; ii<(sizeof(RegTable)/sizeof(ST_DYNAMIXEL_REG_TABLE)) ; ++ii ){
612  bool check_result = true;
613  bool read_result;
614  uint8_t chk_8data, read_8data;
615  uint16_t chk_16data, read_16data;
616  uint32_t chk_32data, read_32data;
617  if( RegTable[ii].selfcheck ){
618  res_str += RegTable[ii].name + " test...\n";
619  }
620  switch( RegTable[ii].length ){
621  case REG_LENGTH_BYTE:
622  chk_8data = (uint8_t)RegTable[ii].init_value;
623  if( RegTable[ii].name == "OPERATION_MODE" ){
624  chk_8data = joints[ii].get_ope_mode();
625  }
626  for( int jj=0 ; jj<joint_num ; ++jj ){
627  read_result = check_servo_param( joints[jj].get_dxl_id(), RegTable[ii].address, chk_8data, read_8data );
628  if( RegTable[ii].selfcheck && !read_result ){
629  res_str += " ID: " + std::to_string(joints[jj].get_dxl_id()) + " check NG\n";
630  check_result = false;
631  }
632  ST_JOINT_PARAM work = joints[jj].get_joint_param();
633  init_joint_params( work, ii, read_8data );
634  joints[jj].set_joint_param( work );
635  }
636  break;
637  case REG_LENGTH_WORD:
638  chk_16data = (uint16_t)RegTable[ii].init_value;
639  for( int jj=0 ; jj<joint_num ; ++jj ){
640  read_result = check_servo_param( joints[jj].get_dxl_id(), RegTable[ii].address, chk_16data, read_16data );
641  if( RegTable[ii].selfcheck && !read_result ){
642  res_str += " ID: " + std::to_string(joints[jj].get_dxl_id()) + " check NG\n";
643  check_result = false;
644  }
645  ST_JOINT_PARAM work = joints[jj].get_joint_param();
646  init_joint_params( work, ii, read_16data );
647  joints[jj].set_joint_param( work );
648  }
649  break;
650  case REG_LENGTH_DWORD:
651  chk_32data = (uint32_t)RegTable[ii].init_value;
652  for( int jj=0 ; jj<joint_num ; ++jj ){
653  read_result = check_servo_param( joints[jj].get_dxl_id(), RegTable[ii].address, chk_32data, read_32data );
654  if( RegTable[ii].selfcheck && !read_result ){
655  res_str += " ID: " + std::to_string(joints[jj].get_dxl_id()) + " check NG\n";
656  check_result = false;
657  }
658  ST_JOINT_PARAM work = joints[jj].get_joint_param();
659  init_joint_params( work, ii, read_32data );
660  joints[jj].set_joint_param( work );
661  }
662  break;
663  }
664  if( RegTable[ii].selfcheck ){
665  if( check_result ){
666  res_str += " CHECK OK\n";
667  }else{
668  res_str += " CHECK NG!\n";
669  }
670  }
671  }
672  return res_str;
673 }
674 
676 {
677  uint8_t dxl_error = 0; // Dynamixel error
678  uint16_t set_pgain = DXL_DEFAULT_PGAIN;
679  uint16_t get_pgain;
680 
681  if( !port_stat ){
682  return;
683  }
684  for( int jj=0 ; jj<joint_num; ++jj ){
685  double now_eff = fabs( joints[jj].get_effort() );
686  double max_eff = joints[jj].get_max_effort();
687  if( now_eff > max_eff ){
688  joints[jj].inc_eff_over();
689  if( joints[jj].get_eff_over_cnt() >= EFFORT_LIMITING_CNT ){
690  // 設計回数以上連続して最大トルクを上回った
691  set_pgain = DXL_DEFAULT_PGAIN;
692  if( joints[jj].is_effort_limiting() ){
693  int dxl_comm_result = packetHandler->read2ByteTxRx(portHandler, joints[jj].get_dxl_id(), ADDR_POSITION_PGAIN, &get_pgain, &dxl_error);
694  if( dxl_comm_result != COMM_SUCCESS ){
695  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
696  ++rx_err;
697  }else if( dxl_error != 0 ){
698  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
699  ++rx_err;
700  }else{
701  set_pgain = get_pgain;
702  }
703  }
704  set_pgain = (uint16_t)(set_pgain * ((max_eff*EFFORT_LIMIT_COEF) / now_eff));
705  set_gain( joints[jj].get_dxl_id(), set_pgain );
706  joints[jj].set_eff_limiting( true );
707  }
708  }else{
709  // 制限中で電流値が下回った
710  if( joints[jj].is_effort_limiting() ){
711  int dxl_comm_result = packetHandler->read2ByteTxRx(portHandler, joints[jj].get_dxl_id(), ADDR_POSITION_PGAIN, &get_pgain, &dxl_error);
712  if( dxl_comm_result != COMM_SUCCESS ){
713  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
714  ++rx_err;
715  }else if( dxl_error != 0 ){
716  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
717  ++rx_err;
718  }else if( get_pgain >= DXL_DEFAULT_PGAIN ){
719  joints[jj].clear_eff_over();
720  joints[jj].set_eff_limiting( false );
721  }else{
722  set_gain( joints[jj].get_dxl_id(), (get_pgain+2) );
723  joints[jj].set_eff_limiting( true );
724  }
725  }
726  }
727 
728  }
729 }
730 
731 
732 
733 void DXLPORT_CONTROL::set_param_delay_time( uint8_t dxl_id, int val )
734 {
735  uint8_t set_param = (uint8_t)val;
736 
737  if( !port_stat ){
738  return;
739  }
740  for( int jj=0 ; jj<joint_num; ++jj ){
741  if( dxl_id == joints[jj].get_dxl_id() ){
742  ST_JOINT_PARAM new_param = joints[jj].get_joint_param();
743  if( new_param.return_delay_time != set_param ){
744  uint8_t dxl_error = 0; // Dynamixel error
745  int dxl_comm_result = packetHandler->write1ByteTxRx( portHandler, dxl_id, ADDR_RETURN_DELAY, set_param, &dxl_error );
746  if( dxl_comm_result != COMM_SUCCESS ){
747  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
748  ++tx_err;
749  }else if( dxl_error != 0 ){
750  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
751  ++tx_err;
752  }
753  }
754  new_param.return_delay_time = set_param;
755  joints[jj].set_joint_param( new_param );
756  break;
757  }
758  }
759 }
760 void DXLPORT_CONTROL::set_param_drive_mode( uint8_t dxl_id, int val )
761 {
762  uint8_t set_param = (uint8_t)val;
763 
764  if( !port_stat ){
765  return;
766  }
767  for( int jj=0 ; jj<joint_num; ++jj ){
768  if( dxl_id == joints[jj].get_dxl_id() ){
769  ST_JOINT_PARAM new_param = joints[jj].get_joint_param();
770  if( new_param.drive_mode != set_param ){
771  uint8_t dxl_error = 0; // Dynamixel error
772  int dxl_comm_result = packetHandler->write1ByteTxRx( portHandler, dxl_id, ADDR_DRIVE_MODE, set_param, &dxl_error );
773  if( dxl_comm_result != COMM_SUCCESS ){
774  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
775  ++tx_err;
776  }else if( dxl_error != 0 ){
777  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
778  ++tx_err;
779  }
780  }
781  new_param.drive_mode = set_param;
782  joints[jj].set_joint_param( new_param );
783  break;
784  }
785  }
786 }
787 void DXLPORT_CONTROL::set_param_ope_mode( uint8_t dxl_id, int val )
788 {
789  uint8_t set_param = (uint8_t)val;
790 
791  if( !port_stat ){
792  return;
793  }
794  for( int jj=0 ; jj<joint_num; ++jj ){
795  if( dxl_id == joints[jj].get_dxl_id() ){
796  ST_JOINT_PARAM new_param = joints[jj].get_joint_param();
797  if( new_param.operation_mode != set_param ){
798  uint8_t dxl_error = 0; // Dynamixel error
799  int dxl_comm_result = packetHandler->write1ByteTxRx( portHandler, dxl_id, ADDR_OPE_MODE, set_param, &dxl_error );
800  if( dxl_comm_result != COMM_SUCCESS ){
801  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
802  ++tx_err;
803  }else if( dxl_error != 0 ){
804  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
805  ++tx_err;
806  }
807  }
808  new_param.operation_mode = set_param;
809  joints[jj].set_joint_param( new_param );
810  break;
811  }
812  }
813 }
814 void DXLPORT_CONTROL::set_param_home_offset( uint8_t dxl_id, int val )
815 {
816  uint32_t set_param = (uint32_t)val;
817 
818  if( !port_stat ){
819  return;
820  }
821  for( int jj=0 ; jj<joint_num; ++jj ){
822  if( dxl_id == joints[jj].get_dxl_id() ){
823  ST_JOINT_PARAM new_param = joints[jj].get_joint_param();
824  if( new_param.homing_offset != set_param ){
825  uint8_t dxl_error = 0; // Dynamixel error
826  int dxl_comm_result = packetHandler->write4ByteTxRx( portHandler, dxl_id, ADDR_MOVING_THRESHOLD, set_param, &dxl_error );
827  if( dxl_comm_result != COMM_SUCCESS ){
828  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
829  ++tx_err;
830  }else if( dxl_error != 0 ){
831  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
832  ++tx_err;
833  }
834  }
835  new_param.homing_offset = (int32_t)set_param;
836  joints[jj].set_joint_param( new_param );
837  break;
838  }
839  }
840 }
841 void DXLPORT_CONTROL::set_param_moving_threshold( uint8_t dxl_id, int val )
842 {
843  uint32_t set_param = (uint32_t)val;
844 
845  if( !port_stat ){
846  return;
847  }
848  for( int jj=0 ; jj<joint_num; ++jj ){
849  if( dxl_id == joints[jj].get_dxl_id() ){
850  ST_JOINT_PARAM new_param = joints[jj].get_joint_param();
851  if( new_param.moving_threshold != set_param ){
852  uint8_t dxl_error = 0; // Dynamixel error
853  int dxl_comm_result = packetHandler->write4ByteTxRx( portHandler, dxl_id, ADDR_MOVING_THRESHOLD, set_param, &dxl_error );
854  if( dxl_comm_result != COMM_SUCCESS ){
855  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
856  ++tx_err;
857  }else if( dxl_error != 0 ){
858  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
859  ++tx_err;
860  }
861  }
862  new_param.moving_threshold = set_param;
863  joints[jj].set_joint_param( new_param );
864  break;
865  }
866  }
867 }
868 void DXLPORT_CONTROL::set_param_temp_limit( uint8_t dxl_id, int val )
869 {
870  uint8_t set_param = (uint8_t)val;
871 
872  if( !port_stat ){
873  return;
874  }
875  for( int jj=0 ; jj<joint_num; ++jj ){
876  if( dxl_id == joints[jj].get_dxl_id() ){
877  ST_JOINT_PARAM new_param = joints[jj].get_joint_param();
878  if( new_param.temprature_limit != set_param ){
879  uint8_t dxl_error = 0; // Dynamixel error
880  int dxl_comm_result = packetHandler->write1ByteTxRx( portHandler, dxl_id, ADDR_TEMPRATURE_LIMIT, set_param, &dxl_error );
881  if( dxl_comm_result != COMM_SUCCESS ){
882  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
883  ++tx_err;
884  }else if( dxl_error != 0 ){
885  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
886  ++tx_err;
887  }
888  }
889  new_param.temprature_limit = set_param;
890  joints[jj].set_joint_param( new_param );
891  break;
892  }
893  }
894 }
895 void DXLPORT_CONTROL::set_param_vol_limit( uint8_t dxl_id, int max, int min )
896 {
897  uint16_t set_max_param = (uint32_t)max;
898  uint16_t set_min_param = (uint32_t)min;
899 
900  if( !port_stat ){
901  return;
902  }
903  for( int jj=0 ; jj<joint_num; ++jj ){
904  if( dxl_id == joints[jj].get_dxl_id() ){
905  ST_JOINT_PARAM new_param = joints[jj].get_joint_param();
906  if( new_param.max_vol_limit != set_max_param ){
907  uint8_t dxl_error = 0; // Dynamixel error
908  int dxl_comm_result = packetHandler->write2ByteTxRx( portHandler, dxl_id, ADDR_MAX_VOL_LIMIT, set_max_param, &dxl_error );
909  if( dxl_comm_result != COMM_SUCCESS ){
910  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
911  ++tx_err;
912  }else if( dxl_error != 0 ){
913  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
914  ++tx_err;
915  }
916  }
917  if( new_param.min_vol_limit != set_min_param ){
918  uint8_t dxl_error = 0; // Dynamixel error
919  int dxl_comm_result = packetHandler->write2ByteTxRx( portHandler, dxl_id, ADDR_MIN_VOL_LIMIT, set_min_param, &dxl_error );
920  if( dxl_comm_result != COMM_SUCCESS ){
921  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
922  ++tx_err;
923  }else if( dxl_error != 0 ){
924  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
925  ++tx_err;
926  }
927  }
928  new_param.max_vol_limit = set_max_param;
929  new_param.min_vol_limit = set_min_param;
930  joints[jj].set_joint_param( new_param );
931  break;
932  }
933  }
934 }
935 void DXLPORT_CONTROL::set_param_current_limit( uint8_t dxl_id, int val )
936 {
937  uint16_t set_param = (uint16_t)val;
938 
939  if( !port_stat ){
940  return;
941  }
942  for( int jj=0 ; jj<joint_num; ++jj ){
943  if( dxl_id == joints[jj].get_dxl_id() ){
944  ST_JOINT_PARAM new_param = joints[jj].get_joint_param();
945  if( new_param.current_limit != set_param ){
946  uint8_t dxl_error = 0; // Dynamixel error
947  int dxl_comm_result = packetHandler->write2ByteTxRx( portHandler, dxl_id, ADDR_CURRENT_LIMIT, set_param, &dxl_error );
948  if( dxl_comm_result != COMM_SUCCESS ){
949  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
950  ++tx_err;
951  }else if( dxl_error != 0 ){
952  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
953  ++tx_err;
954  }
955  }
956  new_param.current_limit = set_param;
957  joints[jj].set_joint_param( new_param );
958  break;
959  }
960  }
961 }
962 void DXLPORT_CONTROL::set_param_vel_gain( uint8_t dxl_id, int p, int i )
963 {
964  uint16_t set_p_param = (uint16_t)p;
965  uint16_t set_i_param = (uint16_t)i;
966 
967  if( !port_stat ){
968  return;
969  }
970  for( int jj=0 ; jj<joint_num; ++jj ){
971  if( dxl_id == joints[jj].get_dxl_id() ){
972  ST_JOINT_PARAM new_param = joints[jj].get_joint_param();
973  if( (new_param.velocity_p_gain != set_p_param) ){
974  uint8_t dxl_error = 0; // Dynamixel error
975  int dxl_comm_result = packetHandler->write2ByteTxRx( portHandler, dxl_id, ADDR_VELOCITY_PGAIN, set_p_param, &dxl_error );
976  if( dxl_comm_result != COMM_SUCCESS ){
977  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
978  ++tx_err;
979  }else if( dxl_error != 0 ){
980  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
981  ++tx_err;
982  }
983  }
984  if( (new_param.velocity_i_gain != set_i_param) ){
985  uint8_t dxl_error = 0; // Dynamixel error
986  int dxl_comm_result = packetHandler->write2ByteTxRx( portHandler, dxl_id, ADDR_VELOCITY_IGAIN, set_i_param, &dxl_error );
987  if( dxl_comm_result != COMM_SUCCESS ){
988  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
989  ++tx_err;
990  }else if( dxl_error != 0 ){
991  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
992  ++tx_err;
993  }
994  }
995  new_param.velocity_p_gain = set_p_param;
996  new_param.velocity_i_gain = set_i_param;
997  joints[jj].set_joint_param( new_param );
998  break;
999  }
1000  }
1001 }
1002 
1003 void DXLPORT_CONTROL::set_param_pos_gain_all( int p, int i, int d )
1004 {
1005  for( int jj=0 ; jj<joint_num ; ++jj ){
1006  set_param_pos_gain( joints[jj].get_dxl_id(), p, i, d);
1007  }
1008 }
1009 
1010 void DXLPORT_CONTROL::set_param_pos_gain( uint8_t dxl_id, int p, int i, int d )
1011 {
1012  uint16_t set_p_param = (uint16_t)p;
1013  uint16_t set_i_param = (uint16_t)i;
1014  uint16_t set_d_param = (uint16_t)d;
1015 
1016  if( !port_stat ){
1017  return;
1018  }
1019  for( int jj=0 ; jj<joint_num; ++jj ){
1020  if( dxl_id == joints[jj].get_dxl_id() ){
1021  ST_JOINT_PARAM new_param = joints[jj].get_joint_param();
1022  if( new_param.position_p_gain != set_p_param ){
1023  uint8_t dxl_error = 0; // Dynamixel error
1024  int dxl_comm_result = packetHandler->write2ByteTxRx( portHandler, dxl_id, ADDR_POSITION_PGAIN, set_p_param, &dxl_error );
1025  if( dxl_comm_result != COMM_SUCCESS ){
1026  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
1027  ++tx_err;
1028  }else if( dxl_error != 0 ){
1029  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
1030  ++tx_err;
1031  }
1032  }
1033  if( new_param.position_i_gain != set_i_param ){
1034  uint8_t dxl_error = 0; // Dynamixel error
1035  int dxl_comm_result = packetHandler->write2ByteTxRx( portHandler, dxl_id, ADDR_POSITION_IGAIN, set_i_param, &dxl_error );
1036  if( dxl_comm_result != COMM_SUCCESS ){
1037  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
1038  ++tx_err;
1039  }else if( dxl_error != 0 ){
1040  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
1041  ++tx_err;
1042  }
1043  }
1044  if( new_param.position_d_gain != set_d_param ){
1045  uint8_t dxl_error = 0; // Dynamixel error
1046  int dxl_comm_result = packetHandler->write2ByteTxRx( portHandler, dxl_id, ADDR_POSITION_DGAIN, set_d_param, &dxl_error );
1047  if( dxl_comm_result != COMM_SUCCESS ){
1048  error_queue.push( (std::string(__func__) + " ") + packetHandler->getTxRxResult( dxl_comm_result ) );
1049  ++tx_err;
1050  }else if( dxl_error != 0 ){
1051  error_queue.push( (std::string(__func__) + " ") + packetHandler->getRxPacketError( dxl_error ) );
1052  ++tx_err;
1053  }
1054  }
1055  new_param.position_p_gain = set_p_param;
1056  new_param.position_i_gain = set_i_param;
1057  new_param.position_d_gain = set_d_param;
1058  joints[jj].set_joint_param( new_param );
1059  break;
1060  }
1061  }
1062 }
1063 
1064 std::string::size_type DXLPORT_CONTROL::get_error( std::string& errorlog )
1065 {
1066  std::string::size_type result = error_queue.size();
1067  if( result > 0 ){
1068  errorlog = error_queue.front();
1069  error_queue.pop();
1070  }
1071  return result;
1072 }
void set_watchdog(uint8_t dxl_id, uint8_t value)
void set_watchdog_all(uint8_t value)
d
#define DXLPOS2RAD(pos)
void set_param_home_offset(uint8_t dxl_id, int val)
void set_param_pos_gain_all(int p, int i, int d)
void readTemp(ros::Time, ros::Duration)
virtual int read1ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint8_t *data, uint8_t *error=0)=0
bool isAvailable(uint8_t id, uint16_t address, uint16_t data_length)
#define ADDR_POSITION_DGAIN
static PortHandler * getPortHandler(const char *port_name)
uint16_t current_limit
Definition: joint_control.h:99
#define DXL_VELOCITY2RAD_S(v)
#define ADDR_GOAL_CURRENT
DXLPORT_CONTROL(ros::NodeHandle handle, CONTROL_SETTING &setting)
std::string::size_type get_error(std::string &errorlog)
#define ADDR_MOVING_THRESHOLD
#define ADDR_PRESENT_MOVEMENT
void set_goal_current(uint8_t dxl_id, uint16_t current)
virtual bool openPort()=0
#define TORQUE_DISABLE
#define LEN_PRESENT_MOVEMENT
#define REG_LENGTH_DWORD
Definition: joint_control.h:31
bool set_torque(uint8_t dxl_id, bool torque)
int32_t homing_offset
Definition: joint_control.h:95
#define LEN_PRESENT_POSITION
uint8_t temprature_limit
Definition: joint_control.h:96
bool addParam(uint8_t id, uint16_t start_address, uint16_t data_length)
void set_param_drive_mode(uint8_t dxl_id, int val)
uint32_t getjointNum(void)
bool changeParam(uint8_t id, uint16_t start_address, uint16_t data_length, uint8_t *data)
#define ADDR_CURRENT_LIMIT
#define DXL_DEFAULT_PGAIN
#define ADDR_BUS_WATCHDOG
std::queue< std::string > error_queue
static const ST_DYNAMIXEL_REG_TABLE RegTable[]
Definition: joint_control.h:60
void set_param_vol_limit(uint8_t dxl_id, int max, int min)
#define DXL_MIN_LIMIT
uint8_t torque_enable
virtual int read2ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t *data, uint8_t *error=0)=0
void startup_motion(void)
std::vector< ST_SERVO_PARAM > getServoParam(void)
#define LEN_GOAL_POSITION
#define EFFORT2DXL_CURRENT(e, coef)
uint16_t moving_threshold
Definition: joint_control.h:94
#define LEN_PRESENT_CURRENT
#define DXL_MAX_LIMIT
void write(ros::Time, ros::Duration)
#define DXL_CURRENT2EFFORT(c, coef)
#define OPERATING_MODE_CURRENT
#define ADDR_POSITION_PGAIN
int COMM_SUCCESS
#define ADDR_DRIVE_MODE
bool is_change_positions(void)
virtual void closePort()=0
#define PROTOCOL_VERSION
Definition: joint_control.h:13
uint16_t position_p_gain
virtual const char * getRxPacketError(uint8_t error)=0
#define DXL_CURRENT_UNIT
std::string getPortName(void)
#define DXL_TORQUE_ON_STEP_MAX
#define ADDR_PRESENT_POSITION
#define ADDR_VELOCITY_PGAIN
void set_goal_current_all(uint16_t current)
#define ADDR_TORQUE_ENABLE
hardware_interface::JointStateInterface joint_stat_if
#define DXL_TORQUR_ON_STEP
void set_gain_all(uint16_t gain)
virtual int write1ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error=0)=0
#define ADDR_VELOCITY_IGAIN
#define RAD2DXLPOS(rad)
#define ADDR_RETURN_DELAY
uint32_t getBaudrate(void)
void set_gain(uint8_t dxl_id, uint16_t gain)
static PacketHandler * getPacketHandler(float protocol_version=2.0)
void set_param_current_limit(uint8_t dxl_id, int val)
void set_torque_all(bool torque)
#define ADDR_PRESENT_VEL
#define REG_LENGTH_WORD
Definition: joint_control.h:30
uint16_t position_i_gain
void registerHandle(const JointStateHandle &handle)
void init_joint_params(ST_JOINT_PARAM &param, int table_id, int value)
uint8_t max_vol_limit
Definition: joint_control.h:97
ros::Time tempTime
bool sleep()
void readCurrent(ros::Time, ros::Duration)
uint16_t velocity_p_gain
void set_param_delay_time(uint8_t dxl_id, int val)
uint8_t min_vol_limit
Definition: joint_control.h:98
void effort_limitter(void)
dynamixel::GroupBulkRead * readTempGroup
uint32_t getData(uint8_t id, uint16_t address, uint16_t data_length)
JointStateHandle getHandle(const std::string &name)
#define ADDR_TEMPRATURE_LIMIT
bool check_servo_param(uint8_t dxl_id, uint32_t test_addr, uint8_t equal, uint8_t &read_val)
uint8_t return_delay_time
Definition: joint_control.h:91
dynamixel::GroupBulkWrite * writeGoalGroup
void set_param_moving_threshold(uint8_t dxl_id, int val)
uint16_t velocity_i_gain
virtual int write4ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint32_t data, uint8_t *error=0)=0
#define LEN_PRESENT_VEL
bool read(ros::Time, ros::Duration)
#define ADDR_MAX_VOL_LIMIT
void readVel(ros::Time, ros::Duration)
#define LEN_PRESENT_TEMP
#define DXL_TEMP_READ_DURATION
hardware_interface::EffortJointInterface joint_eff_if
#define ADDR_MIN_VOL_LIMIT
virtual int write2ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t data, uint8_t *error=0)=0
dynamixel::GroupBulkRead * readMovementGroup
uint16_t position_d_gain
bool getJointLimits(urdf::JointConstSharedPtr urdf_joint, JointLimits &limits)
void readPos(ros::Time, ros::Duration)
static Time now()
#define REG_LENGTH_BYTE
Definition: joint_control.h:29
void set_param_vel_gain(uint8_t dxl_id, int p, int i)
uint8_t drive_mode
Definition: joint_control.h:92
hardware_interface::PositionJointInterface joint_pos_if
#define TORQUE_ENABLE
virtual int read4ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint32_t *data, uint8_t *error=0)=0
#define LEN_GOAL_CURRENT
uint8_t operation_mode
Definition: joint_control.h:93
#define EFFORT_LIMITING_CNT
#define EFFORT_LIMIT_COEF
virtual bool setBaudRate(const int baudrate)=0
ros::Time getTime() const
std::string self_check(void)
#define ADDR_PRESENT_CURRENT
virtual const char * getTxRxResult(int result)=0
dynamixel::PacketHandler * packetHandler
#define ADDR_GOAL_POSITION
#define ADDR_PRESENT_TEMP
std::vector< JOINT_CONTROL > joints
void set_param_ope_mode(uint8_t dxl_id, int val)
void set_param_temp_limit(uint8_t dxl_id, int val)
ros::Duration getDuration(ros::Time t) const
#define ADDR_OPE_MODE
void set_param_pos_gain(uint8_t dxl_id, int p, int i, int d)
#define ADDR_POSITION_IGAIN
dynamixel::PortHandler * portHandler
joint_limits_interface::PositionJointSoftLimitsInterface joint_limits_if


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