@@ -205,8 +205,10 @@ DxlError Dynamixel::InitDxlComm(
205205 // Check if Hardware Error Status control item exists
206206 uint16_t hw_error_addr, error_code_addr;
207207 uint8_t hw_error_size, error_code_size;
208- bool hw_error_exists = dxl_info_.GetDxlControlItem (it_id, " Hardware Error Status" , hw_error_addr, hw_error_size);
209- bool error_code_exists = dxl_info_.GetDxlControlItem (it_id, " Error Code" , error_code_addr, error_code_size);
208+ bool hw_error_exists = dxl_info_.GetDxlControlItem (
209+ it_id, " Hardware Error Status" , hw_error_addr, hw_error_size);
210+ bool error_code_exists = dxl_info_.GetDxlControlItem (
211+ it_id, " Error Code" , error_code_addr, error_code_size);
210212
211213 if (hw_error_exists) {
212214 uint32_t hw_error_status = 0 ;
@@ -255,7 +257,11 @@ DxlError Dynamixel::InitDxlComm(
255257 }
256258 }
257259 } else {
258- fprintf (stderr, " [ID:%03d] Neither Hardware Error Status nor Error Code control items available.\n " , it_id);
260+ fprintf (
261+ stderr,
262+ " [ID:%03d] Neither Hardware Error Status nor Error Code control items available.\n " ,
263+ it_id
264+ );
259265 }
260266
261267 fprintf (stderr, " [ID:%03d] Hardware Error detected, rebooting...\n " , it_id);
0 commit comments