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


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