8 #define     EFFORT_LIMIT_COEF   (0.95) 
   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) 
   21     int position_mode_joint_num = 0;
 
   22     int current_mode_joint_num = 0;
 
   37         JOINT_CONTROL work( list[jj].name, list[jj].
id, list[jj].center, list[jj].home, list[jj].eff_cnst, list[jj].mode );
 
   49         uint8_t dxl_id = 
joints[jj].get_dxl_id();
 
   53                 error_queue.push(
"Bulk current write setting failed.");
 
   68             error_queue.push(
"Bulk group read setting failed.");
 
   85                 error_queue.push(
"Initialize communication failed.");
 
  100             ++current_mode_joint_num;
 
  103             ++position_mode_joint_num;
 
  107             joints[jj].set_limits( limits );
 
  113                             reg_limits_handle( reg_joint_handle, limits, soft_limits );
 
  117     if( position_mode_joint_num > 0 ){
 
  120     if( current_mode_joint_num > 0 ){
 
  165         int32_t present_pos = 0;
 
  166         uint8_t dxl_id = 
joints[jj].get_dxl_id();
 
  168         if( !dxl_getdata_result ){
 
  173             joints[jj].set_dxl_pos( present_pos );
 
  174             present_pos = (present_pos - 
joints[jj].get_center());
 
  183         int16_t present_current = 0;
 
  184         uint8_t dxl_id = 
joints[jj].get_dxl_id();
 
  186         if( !dxl_getdata_result ){
 
  191             joints[jj].set_dxl_curr( present_current );
 
  206             uint8_t dxl_id = 
joints[jj].get_dxl_id();
 
  208             if( !dxl_getdata_result ){
 
  213                 joints[jj].set_dxl_temp( present_temp );
 
  214                 joints[jj].set_temprature( present_temp );
 
  224         uint8_t dxl_id = 
joints[jj].get_dxl_id();
 
  226         if( !dxl_getdata_result ){
 
  242             get_cmd = 
joints[jj].get_command();
 
  243             joints[jj].updt_d_command( get_cmd );
 
  244             joints[jj].set_position( get_cmd );
 
  249         get_cmd = 
joints[jj].get_command();
 
  253             joints[jj].updt_d_command( 0.0 );
 
  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);
 
  264             joints[jj].updt_d_command( get_cmd );
 
  265             work_pos += 
joints[jj].get_center();          
 
  273             uint32_t dxl_pos = (uint32_t)round( work_pos );
 
  274             uint8_t* goal_data = 
joints[jj].get_dxl_goal_addr();
 
  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);
 
  296         if( fabs( 
joints[jj].get_d_command() ) > 0.0 ){
 
  318     uint8_t dxl_error = 0;                          
 
  324     }
else if( dxl_error != 0 ){
 
  345     uint8_t dxl_error = 0;                          
 
  351     }
else if( dxl_error != 0 ){
 
  366     uint8_t dxl_error = 0; 
 
  371     }
else if( dxl_error != 0 ){
 
  381     for( uint8_t jj=0 ; jj<
joint_num; ++jj ){
 
  383             joints[jj].set_torque( torque );
 
  394     uint8_t dxl_error = 0; 
 
  399     }
else if( dxl_error != 0 ){
 
  407     for( uint8_t jj=0 ; jj<
joint_num; ++jj ){
 
  419     std::vector<ST_HOME_MOTION_DATA> home_motion_data;
 
  434             joints[jj].set_command( 0.0 );
 
  438         home_motion_data.push_back( motion_work );
 
  446     for( 
int step=0 ; step<step_max ; ++step ){
 
  463             joints[jj].set_command( 
joints[jj].get_command() + home_motion_data[jj].step_rad );
 
  472         joints[jj].set_command( home_motion_data[jj].home_rad );
 
  476         joints[jj].updt_d_command( 0.0 );
 
  483     uint8_t dxl_error = 0;                          
 
  491     }
else if( dxl_error != 0 ){
 
  495     if( read_data == equal ){
 
  498     read_val = read_data;
 
  503     uint8_t dxl_error = 0;                          
 
  511     }
else if( dxl_error != 0 ){
 
  515     if( read_data == equal ){
 
  518     read_val = read_data;
 
  523     uint8_t dxl_error = 0;                          
 
  531     }
else if( dxl_error != 0 ){
 
  535     if( read_data == equal ){
 
  538     read_val = read_data;
 
  546         param.return_delay_time = (uint8_t)value;
 
  549         param.drive_mode = (uint8_t)value;
 
  552         param.operation_mode = (uint8_t)value;
 
  555         param.homing_offset = (int32_t)value;
 
  558         param.moving_threshold = (uint16_t)value;
 
  561         param.temprature_limit = (uint8_t)value;
 
  564         param.max_vol_limit = (uint8_t)value;
 
  567         param.min_vol_limit = (uint8_t)value;
 
  570         param.current_limit = (uint16_t)value;
 
  573         param.torque_enable = (uint8_t)value;
 
  576         param.velocity_i_gain = (uint16_t)value;
 
  579         param.velocity_p_gain = (uint16_t)value;
 
  582         param.position_d_gain = (uint16_t)value;
 
  585         param.position_i_gain = (uint16_t)value;
 
  588         param.position_p_gain = (uint16_t)value;
 
  605     std::string res_str = 
"[DYNAMIXEL PARAMETER SELF CHECK]\n";
 
  608         res_str = 
"SKIP SELF CHECK...";
 
  612         bool check_result = 
true;
 
  614         uint8_t chk_8data, read_8data;
 
  615         uint16_t chk_16data, read_16data;
 
  616         uint32_t chk_32data, read_32data;
 
  622             chk_8data = (uint8_t)
RegTable[ii].init_value;
 
  623             if( 
RegTable[ii].name == 
"OPERATION_MODE" ){
 
  624                 chk_8data = 
joints[ii].get_ope_mode();
 
  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;
 
  634                 joints[jj].set_joint_param( work );
 
  638             chk_16data = (uint16_t)
RegTable[ii].init_value;
 
  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;
 
  647                 joints[jj].set_joint_param( work );
 
  651             chk_32data = (uint32_t)
RegTable[ii].init_value;
 
  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;
 
  660                 joints[jj].set_joint_param( work );
 
  666                 res_str += 
" CHECK OK\n";
 
  668                 res_str += 
" CHECK NG!\n";
 
  677     uint8_t dxl_error = 0;                          
 
  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();
 
  692                 if( 
joints[jj].is_effort_limiting() ){
 
  697                     }
else if( dxl_error != 0 ){
 
  701                         set_pgain = get_pgain;
 
  706                 joints[jj].set_eff_limiting( 
true );
 
  710             if( 
joints[jj].is_effort_limiting() ){
 
  715                 }
else if( dxl_error != 0 ){
 
  719                     joints[jj].clear_eff_over();
 
  720                     joints[jj].set_eff_limiting( 
false );
 
  723                     joints[jj].set_eff_limiting( 
true );
 
  735     uint8_t set_param = (uint8_t)val;
 
  741         if( dxl_id == 
joints[jj].get_dxl_id() ){
 
  744                 uint8_t dxl_error = 0; 
 
  749                 }
else if( dxl_error != 0 ){
 
  755             joints[jj].set_joint_param( new_param );
 
  762     uint8_t set_param = (uint8_t)val;
 
  768         if( dxl_id == 
joints[jj].get_dxl_id() ){
 
  771                 uint8_t dxl_error = 0; 
 
  776                 }
else if( dxl_error != 0 ){
 
  782             joints[jj].set_joint_param( new_param );
 
  789     uint8_t set_param = (uint8_t)val;
 
  795         if( dxl_id == 
joints[jj].get_dxl_id() ){
 
  798                 uint8_t dxl_error = 0; 
 
  803                 }
else if( dxl_error != 0 ){
 
  809             joints[jj].set_joint_param( new_param );
 
  816     uint32_t set_param = (uint32_t)val;
 
  822         if( dxl_id == 
joints[jj].get_dxl_id() ){
 
  825                 uint8_t dxl_error = 0; 
 
  830                 }
else if( dxl_error != 0 ){
 
  836             joints[jj].set_joint_param( new_param );
 
  843     uint32_t set_param = (uint32_t)val;
 
  849         if( dxl_id == 
joints[jj].get_dxl_id() ){
 
  852                 uint8_t dxl_error = 0; 
 
  857                 }
else if( dxl_error != 0 ){
 
  863             joints[jj].set_joint_param( new_param );
 
  870     uint8_t set_param = (uint8_t)val;
 
  876         if( dxl_id == 
joints[jj].get_dxl_id() ){
 
  879                 uint8_t dxl_error = 0; 
 
  884                 }
else if( dxl_error != 0 ){
 
  890             joints[jj].set_joint_param( new_param );
 
  897     uint16_t set_max_param = (uint32_t)max;
 
  898     uint16_t set_min_param = (uint32_t)
min;
 
  904         if( dxl_id == 
joints[jj].get_dxl_id() ){
 
  907                 uint8_t dxl_error = 0; 
 
  912                 }
else if( dxl_error != 0 ){
 
  918                 uint8_t dxl_error = 0; 
 
  923                 }
else if( dxl_error != 0 ){
 
  930             joints[jj].set_joint_param( new_param );
 
  937     uint16_t set_param = (uint16_t)val;
 
  943         if( dxl_id == 
joints[jj].get_dxl_id() ){
 
  946                 uint8_t dxl_error = 0; 
 
  951                 }
else if( dxl_error != 0 ){
 
  957             joints[jj].set_joint_param( new_param );
 
  964     uint16_t set_p_param = (uint16_t)p;
 
  965     uint16_t set_i_param = (uint16_t)i;
 
  971         if( dxl_id == 
joints[jj].get_dxl_id() ){
 
  974                 uint8_t dxl_error = 0; 
 
  979                 }
else if( dxl_error != 0 ){
 
  985                 uint8_t dxl_error = 0; 
 
  990                 }
else if( dxl_error != 0 ){
 
  997             joints[jj].set_joint_param( new_param );
 
 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;
 
 1020         if( dxl_id == 
joints[jj].get_dxl_id() ){
 
 1023                 uint8_t dxl_error = 0; 
 
 1028                 }
else if( dxl_error != 0 ){
 
 1034                 uint8_t dxl_error = 0; 
 
 1039                 }
else if( dxl_error != 0 ){
 
 1045                 uint8_t dxl_error = 0; 
 
 1050                 }
else if( dxl_error != 0 ){
 
 1058             joints[jj].set_joint_param( new_param );
 
 1066     std::string::size_type result = 
error_queue.size();