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)
20 int position_mode_joint_num = 0;
21 int current_mode_joint_num = 0;
22 int current_position_mode_joint_num = 0;
38 JOINT_CONTROL work( list[jj].name, list[jj].
id, list[jj].center, list[jj].home, list[jj].eff_cnst, list[jj].mode );
53 uint8_t dxl_id =
joints[jj].get_dxl_id();
57 error_queue.push(
"Bulk current write setting failed.");
78 error_queue.push(
"Bulk group read setting failed.");
96 uint8_t dxl_id =
joints[jj].get_dxl_id();
100 error_queue.push(
"Initialize communication failed.");
118 ++current_mode_joint_num;
121 ++position_mode_joint_num;
125 joints[jj].set_limits( limits );
131 reg_limits_handle( reg_joint_handle, limits, soft_limits );
135 if( position_mode_joint_num > 0 ){
138 if( current_mode_joint_num > 0 ){
183 uint8_t dxl_id =
joints[jj].get_dxl_id();
185 if( !dxl_getdata_result ){
187 ROS_INFO(
"readId error [%d]",dxl_id);
191 if( get_id == dxl_id ){
206 int32_t present_pos = 0;
207 uint8_t dxl_id =
joints[jj].get_dxl_id();
209 if( !dxl_getdata_result ){
214 joints[jj].set_dxl_pos( present_pos );
215 present_pos = (present_pos -
joints[jj].get_center());
228 int16_t present_current = 0;
229 uint8_t dxl_id =
joints[jj].get_dxl_id();
231 if( !dxl_getdata_result ){
236 joints[jj].set_dxl_curr( present_current );
250 uint8_t dxl_id =
joints[jj].get_dxl_id();
252 if( !dxl_getdata_result ){
257 joints[jj].set_dxl_temp( present_temp );
258 joints[jj].set_temprature( present_temp );
271 uint8_t dxl_id =
joints[jj].get_dxl_id();
273 if( !dxl_getdata_result ){
292 get_cmd =
joints[jj].get_command();
293 joints[jj].updt_d_command( get_cmd );
294 joints[jj].set_position( get_cmd );
300 #ifdef MASTER_WAIST_SLAVE_NECK
301 double slave_pos_data;
303 if(
joints[jj].get_dxl_id() == 18 ){
304 slave_pos_data =
joints[jj].get_command();
306 if(
joints[jj].get_dxl_id() == 19 ){
307 joints[jj].set_command( -slave_pos_data );
310 get_cmd =
joints[jj].get_command();
314 joints[jj].updt_d_command( 0.0 );
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);
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);
332 joints[jj].updt_d_command( get_cmd );
333 work_pos +=
joints[jj].get_center();
341 uint32_t dxl_pos = (uint32_t)round( work_pos );
342 uint8_t* goal_data =
joints[jj].get_dxl_goal_addr();
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);
364 if( fabs(
joints[jj].get_d_command() ) > 0.0 ){
387 uint8_t dxl_error = 0;
395 }
else if( dxl_error != 0 ){
416 uint8_t dxl_error = 0;
424 }
else if( dxl_error != 0 ){
439 uint8_t dxl_error = 0;
446 }
else if( dxl_error != 0 ){
456 for( uint8_t jj=0 ; jj<
joint_num; ++jj ){
458 joints[jj].set_torque( torque );
469 uint8_t dxl_error = 0;
476 }
else if( dxl_error != 0 ){
484 for( uint8_t jj=0 ; jj<
joint_num; ++jj ){
496 std::vector<ST_HOME_MOTION_DATA> home_motion_data;
514 joints[jj].set_command( 0.0 );
518 home_motion_data.push_back( motion_work );
528 for(
int step=0 ; step<step_max ; ++step ){
544 joints[jj].set_command(
joints[jj].get_command() + home_motion_data[jj].step_rad );
555 joints[jj].set_command( home_motion_data[jj].home_rad );
561 joints[jj].updt_d_command( 0.0 );
568 uint8_t dxl_error = 0;
578 }
else if( dxl_error != 0 ){
582 if( read_data == equal ){
585 read_val = read_data;
590 uint8_t dxl_error = 0;
600 }
else if( dxl_error != 0 ){
604 if( read_data == equal ){
607 read_val = read_data;
612 uint8_t dxl_error = 0;
622 }
else if( dxl_error != 0 ){
626 if( read_data == equal ){
629 read_val = read_data;
637 param.return_delay_time = (uint8_t)value;
640 param.drive_mode = (uint8_t)value;
643 param.operation_mode = (uint8_t)value;
646 param.homing_offset = (int32_t)value;
649 param.moving_threshold = (uint16_t)value;
652 param.temprature_limit = (uint8_t)value;
655 param.max_vol_limit = (uint8_t)value;
658 param.min_vol_limit = (uint8_t)value;
661 param.current_limit = (uint16_t)value;
664 param.torque_enable = (uint8_t)value;
667 param.velocity_i_gain = (uint16_t)value;
670 param.velocity_p_gain = (uint16_t)value;
673 param.position_d_gain = (uint16_t)value;
676 param.position_i_gain = (uint16_t)value;
679 param.position_p_gain = (uint16_t)value;
696 std::string res_str =
"[DYNAMIXEL PARAMETER SELF CHECK]\n";
699 res_str =
"SKIP SELF CHECK...";
703 bool check_result =
true;
705 uint8_t chk_8data, read_8data;
706 uint16_t chk_16data, read_16data;
707 uint32_t chk_32data, read_32data;
713 chk_8data = (uint8_t)
RegTable[ii].init_value;
714 if(
RegTable[ii].name ==
"OPERATION_MODE" ){
715 chk_8data =
joints[ii].get_ope_mode();
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;
725 joints[jj].set_joint_param( work );
729 chk_16data = (uint16_t)
RegTable[ii].init_value;
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;
738 joints[jj].set_joint_param( work );
742 chk_32data = (uint32_t)
RegTable[ii].init_value;
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;
751 joints[jj].set_joint_param( work );
757 res_str +=
" CHECK OK\n";
759 res_str +=
" CHECK NG!\n";
768 uint8_t set_param = (uint8_t)val;
774 if( dxl_id ==
joints[jj].get_dxl_id() ){
777 uint8_t dxl_error = 0;
784 }
else if( dxl_error != 0 ){
790 joints[jj].set_joint_param( new_param );
797 uint8_t set_param = (uint8_t)val;
803 if( dxl_id ==
joints[jj].get_dxl_id() ){
806 uint8_t dxl_error = 0;
813 }
else if( dxl_error != 0 ){
819 joints[jj].set_joint_param( new_param );
826 uint8_t set_param = (uint8_t)val;
832 if( dxl_id ==
joints[jj].get_dxl_id() ){
835 uint8_t dxl_error = 0;
842 }
else if( dxl_error != 0 ){
848 joints[jj].set_joint_param( new_param );
855 uint32_t set_param = (uint32_t)val;
861 if( dxl_id ==
joints[jj].get_dxl_id() ){
864 uint8_t dxl_error = 0;
871 }
else if( dxl_error != 0 ){
877 joints[jj].set_joint_param( new_param );
884 uint32_t set_param = (uint32_t)val;
890 if( dxl_id ==
joints[jj].get_dxl_id() ){
893 uint8_t dxl_error = 0;
900 }
else if( dxl_error != 0 ){
906 joints[jj].set_joint_param( new_param );
913 uint8_t set_param = (uint8_t)val;
919 if( dxl_id ==
joints[jj].get_dxl_id() ){
922 uint8_t dxl_error = 0;
929 }
else if( dxl_error != 0 ){
935 joints[jj].set_joint_param( new_param );
942 uint16_t set_max_param = (uint32_t)max;
943 uint16_t set_min_param = (uint32_t)
min;
949 if( dxl_id ==
joints[jj].get_dxl_id() ){
952 uint8_t dxl_error = 0;
959 }
else if( dxl_error != 0 ){
965 uint8_t dxl_error = 0;
972 }
else if( dxl_error != 0 ){
979 joints[jj].set_joint_param( new_param );
986 uint16_t set_param = (uint16_t)val;
992 if( dxl_id ==
joints[jj].get_dxl_id() ){
995 uint8_t dxl_error = 0;
1002 }
else if( dxl_error != 0 ){
1008 joints[jj].set_joint_param( new_param );
1015 uint16_t set_p_param = (uint16_t)p;
1016 uint16_t set_i_param = (uint16_t)i;
1022 if( dxl_id ==
joints[jj].get_dxl_id() ){
1025 uint8_t dxl_error = 0;
1032 }
else if( dxl_error != 0 ){
1038 uint8_t dxl_error = 0;
1045 }
else if( dxl_error != 0 ){
1052 joints[jj].set_joint_param( new_param );
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;
1078 if( dxl_id ==
joints[jj].get_dxl_id() ){
1081 uint8_t dxl_error = 0;
1088 }
else if( dxl_error != 0 ){
1094 uint8_t dxl_error = 0;
1101 }
else if( dxl_error != 0 ){
1107 uint8_t dxl_error = 0;
1114 }
else if( dxl_error != 0 ){
1122 joints[jj].set_joint_param( new_param );
1130 std::string::size_type result =
error_queue.size();
1140 uint8_t dxl_error = 0;
1141 uint16_t setup_data[] = { 224, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 146 };
1148 }
else if( dxl_error != 0 ){
1153 for(
int idx=0 ; idx<
sizeof(setup_data)/2 ; ++idx ){
1159 }
else if( dxl_error != 0 ){