@@ -222,7 +222,7 @@ DxlError Dynamixel::InitDxlComm(
222
222
223
223
if (hw_error_exists) {
224
224
uint32_t hw_error_status = 0 ;
225
- DxlError hw_error_result = ReadItem (it_id, " Hardware Error Status" , hw_error_status);
225
+ ReadItem (it_id, " Hardware Error Status" , hw_error_status);
226
226
227
227
std::string error_string = " " ;
228
228
uint8_t hw_error_byte = static_cast <uint8_t >(hw_error_status);
@@ -240,22 +240,25 @@ DxlError Dynamixel::InitDxlComm(
240
240
}
241
241
242
242
if (!error_string.empty ()) {
243
- fprintf (stderr, " [ID:%03d] Hardware Error Details: 0x%x (%d): %s\n " ,
244
- it_id, hw_error_byte, hw_error_byte, error_string.c_str ());
243
+ fprintf (
244
+ stderr, " [ID:%03d] Hardware Error Details: 0x%x (%d): %s\n " ,
245
+ it_id, hw_error_byte, hw_error_byte, error_string.c_str ());
245
246
}
246
247
} else if (error_code_exists) {
247
248
uint32_t error_code = 0 ;
248
- DxlError error_code_result = ReadItem (it_id, " Error Code" , error_code);
249
+ ReadItem (it_id, " Error Code" , error_code);
249
250
250
251
uint8_t error_code_byte = static_cast <uint8_t >(error_code);
251
252
if (error_code_byte != 0x00 ) {
252
253
const ErrorCodeInfo * error_info = get_error_code_info (error_code_byte);
253
254
if (error_info) {
254
- fprintf (stderr, " [ID:%03d] Error Code Details: 0x%x (%s): %s\n " ,
255
- it_id, error_code_byte, error_info->label , error_info->description );
255
+ fprintf (
256
+ stderr, " [ID:%03d] Error Code Details: 0x%x (%s): %s\n " ,
257
+ it_id, error_code_byte, error_info->label , error_info->description );
256
258
} else {
257
- fprintf (stderr, " [ID:%03d] Error Code Details: 0x%x (Unknown Error Code)\n " ,
258
- it_id, error_code_byte);
259
+ fprintf (
260
+ stderr, " [ID:%03d] Error Code Details: 0x%x (Unknown Error Code)\n " ,
261
+ it_id, error_code_byte);
259
262
}
260
263
}
261
264
} else {
0 commit comments