@@ -635,6 +635,8 @@ std::string Dynamixel::DxlErrorToString(DxlError error_num)
635635 return " DLX_HARDWARE_ERROR" ;
636636 case DXL_REBOOT_FAIL:
637637 return " DXL_REBOOT_FAIL" ;
638+ default :
639+ return " UNKNOWN_ERROR" ;
638640 }
639641}
640642
@@ -965,15 +967,15 @@ DxlError Dynamixel::ProcessReadCommunication(
965967 dxl_comm_result = group_sync_read->txPacket ();
966968 if (dxl_comm_result != COMM_SUCCESS) {
967969 fprintf (
968- stderr, " SyncRead Tx Fail [Dxl Size : %d ] [Error code : %d]\n " ,
970+ stderr, " SyncRead Tx Fail [Dxl Size : %ld ] [Error code : %d]\n " ,
969971 read_data_list_.size (), dxl_comm_result);
970972 return DxlError::SYNC_READ_FAIL;
971973 }
972974 } else {
973975 dxl_comm_result = group_bulk_read->txPacket ();
974976 if (dxl_comm_result != COMM_SUCCESS) {
975977 fprintf (
976- stderr, " BulkRead Tx Fail [Dxl Size : %d ] [Error code : %d]\n " ,
978+ stderr, " BulkRead Tx Fail [Dxl Size : %ld ] [Error code : %d]\n " ,
977979 read_data_list_.size (), dxl_comm_result);
978980 return DxlError::BULK_READ_FAIL;
979981 }
@@ -989,15 +991,15 @@ DxlError Dynamixel::ProcessReadCommunication(
989991 dxl_comm_result = group_sync_read->rxPacket ();
990992 if (dxl_comm_result != COMM_SUCCESS) {
991993 fprintf (
992- stderr, " SyncRead Rx Fail [Dxl Size : %d ] [Error code : %d]\n " ,
994+ stderr, " SyncRead Rx Fail [Dxl Size : %ld ] [Error code : %d]\n " ,
993995 read_data_list_.size (), dxl_comm_result);
994996 return DxlError::SYNC_READ_FAIL;
995997 }
996998 } else {
997999 dxl_comm_result = group_bulk_read->rxPacket ();
9981000 if (dxl_comm_result != COMM_SUCCESS) {
9991001 fprintf (
1000- stderr, " BulkRead Rx Fail [Dxl Size : %d ] [Error code : %d]\n " ,
1002+ stderr, " BulkRead Rx Fail [Dxl Size : %ld ] [Error code : %d]\n " ,
10011003 read_data_list_.size (), dxl_comm_result);
10021004 return DxlError::BULK_READ_FAIL;
10031005 }
@@ -1027,9 +1029,8 @@ DxlError Dynamixel::ProcessReadData(
10271029 id,
10281030 static_cast <int32_t >(dxl_getdata));
10291031 } else if (item_names[item_index] == " Present Velocity" ) {
1030- *data_ptrs[item_index] = dxl_info_.ConvertValueRPMToVelocityRPS (
1031- id,
1032- static_cast <int32_t >(dxl_getdata));
1032+ *data_ptrs[item_index] =
1033+ dxl_info_.ConvertValueRPMToVelocityRPS (static_cast <int32_t >(dxl_getdata));
10331034 } else if (item_names[item_index] == " Present Current" ) {
10341035 *data_ptrs[item_index] = dxl_info_.ConvertCurrentToEffort (
10351036 id,
@@ -1173,7 +1174,7 @@ DxlError Dynamixel::SetDxlValueToSyncWrite()
11731174 param_write_value[added_byte + 0 ] = DXL_LOBYTE (goal_current);
11741175 param_write_value[added_byte + 1 ] = DXL_HIBYTE (goal_current);
11751176 } else if (indirect_info_write_[ID].item_name .at (item_index) == " Goal Velocity" ) {
1176- int16_t goal_velocity = dxl_info_.ConvertVelocityRPSToValueRPM (ID, data);
1177+ int16_t goal_velocity = dxl_info_.ConvertVelocityRPSToValueRPM (data);
11771178 param_write_value[added_byte + 0 ] = DXL_LOBYTE (DXL_LOWORD (goal_velocity));
11781179 param_write_value[added_byte + 1 ] = DXL_HIBYTE (DXL_LOWORD (goal_velocity));
11791180 param_write_value[added_byte + 2 ] = DXL_LOBYTE (DXL_HIWORD (goal_velocity));
@@ -1288,7 +1289,7 @@ DxlError Dynamixel::SetDxlValueToBulkWrite()
12881289 param_write_value[added_byte + 0 ] = DXL_LOBYTE (goal_current);
12891290 param_write_value[added_byte + 1 ] = DXL_HIBYTE (goal_current);
12901291 } else if (indirect_info_write_[ID].item_name .at (item_index) == " Goal Velocity" ) {
1291- int32_t goal_velocity = dxl_info_.ConvertVelocityRPSToValueRPM (ID, data);
1292+ int32_t goal_velocity = dxl_info_.ConvertVelocityRPSToValueRPM (data);
12921293 param_write_value[added_byte + 0 ] = DXL_LOBYTE (DXL_LOWORD (goal_velocity));
12931294 param_write_value[added_byte + 1 ] = DXL_HIBYTE (DXL_LOWORD (goal_velocity));
12941295 param_write_value[added_byte + 2 ] = DXL_LOBYTE (DXL_HIWORD (goal_velocity));
0 commit comments