@@ -964,14 +964,16 @@ DxlError Dynamixel::ProcessReadCommunication(
964964 if (is_sync) {
965965 dxl_comm_result = group_sync_read->txPacket ();
966966 if (dxl_comm_result != COMM_SUCCESS) {
967- fprintf (stderr, " SyncRead Tx Fail [Dxl Size : %d] [Error code : %d]\n " ,
967+ fprintf (
968+ stderr, " SyncRead Tx Fail [Dxl Size : %d] [Error code : %d]\n " ,
968969 read_data_list_.size (), dxl_comm_result);
969970 return DxlError::SYNC_READ_FAIL;
970971 }
971972 } else {
972973 dxl_comm_result = group_bulk_read->txPacket ();
973974 if (dxl_comm_result != COMM_SUCCESS) {
974- fprintf (stderr, " BulkRead Tx Fail [Dxl Size : %d] [Error code : %d]\n " ,
975+ fprintf (
976+ stderr, " BulkRead Tx Fail [Dxl Size : %d] [Error code : %d]\n " ,
975977 read_data_list_.size (), dxl_comm_result);
976978 return DxlError::BULK_READ_FAIL;
977979 }
@@ -986,14 +988,16 @@ DxlError Dynamixel::ProcessReadCommunication(
986988 if (is_sync) {
987989 dxl_comm_result = group_sync_read->rxPacket ();
988990 if (dxl_comm_result != COMM_SUCCESS) {
989- fprintf (stderr, " SyncRead Rx Fail [Dxl Size : %d] [Error code : %d]\n " ,
991+ fprintf (
992+ stderr, " SyncRead Rx Fail [Dxl Size : %d] [Error code : %d]\n " ,
990993 read_data_list_.size (), dxl_comm_result);
991994 return DxlError::SYNC_READ_FAIL;
992995 }
993996 } else {
994997 dxl_comm_result = group_bulk_read->rxPacket ();
995998 if (dxl_comm_result != COMM_SUCCESS) {
996- fprintf (stderr, " BulkRead Rx Fail [Dxl Size : %d] [Error code : %d]\n " ,
999+ fprintf (
1000+ stderr, " BulkRead Rx Fail [Dxl Size : %d] [Error code : %d]\n " ,
9971001 read_data_list_.size (), dxl_comm_result);
9981002 return DxlError::BULK_READ_FAIL;
9991003 }
@@ -1019,13 +1023,16 @@ DxlError Dynamixel::ProcessReadData(
10191023 uint32_t dxl_getdata = get_data_func (id, current_addr, size);
10201024
10211025 if (item_names[item_index] == " Present Position" ) {
1022- *data_ptrs[item_index] = dxl_info_.ConvertValueToRadian (id,
1026+ *data_ptrs[item_index] = dxl_info_.ConvertValueToRadian (
1027+ id,
10231028 static_cast <int32_t >(dxl_getdata));
10241029 } else if (item_names[item_index] == " Present Velocity" ) {
1025- *data_ptrs[item_index] = dxl_info_.ConvertValueRPMToVelocityRPS (id,
1030+ *data_ptrs[item_index] = dxl_info_.ConvertValueRPMToVelocityRPS (
1031+ id,
10261032 static_cast <int32_t >(dxl_getdata));
10271033 } else if (item_names[item_index] == " Present Current" ) {
1028- *data_ptrs[item_index] = dxl_info_.ConvertCurrentToEffort (id,
1034+ *data_ptrs[item_index] = dxl_info_.ConvertCurrentToEffort (
1035+ id,
10291036 static_cast <int16_t >(dxl_getdata));
10301037 } else {
10311038 *data_ptrs[item_index] = static_cast <double >(dxl_getdata);
0 commit comments