-
Notifications
You must be signed in to change notification settings - Fork 11
Bump 1.4.15 #86
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Bump 1.4.15 #86
Changes from all commits
124ab3f
6a86ec9
8dfe465
0bb65ca
cc00798
49a8b09
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -199,13 +199,76 @@ DxlError Dynamixel::InitDxlComm( | |
if (dxl_comm_result != COMM_SUCCESS) { | ||
fprintf(stderr, " - COMM_ERROR : %s\n", packet_handler_->getTxRxResult(dxl_comm_result)); | ||
return DxlError::CANNOT_FIND_CONTROL_ITEM; | ||
} else if (dxl_error != 0) { | ||
} | ||
|
||
// First, read the model file to get the control table structure | ||
try { | ||
dxl_info_.ReadDxlModelFile(it_id, dxl_model_number); | ||
} catch (const std::exception & e) { | ||
fprintf(stderr, "[InitDxlComm][ID:%03d] Error reading model file: %s\n", it_id, e.what()); | ||
return DxlError::CANNOT_FIND_CONTROL_ITEM; | ||
} | ||
|
||
if (dxl_error != 0) { | ||
fprintf(stderr, " - RX_PACKET_ERROR : %s\n", packet_handler_->getRxPacketError(dxl_error)); | ||
uint32_t err = 0; | ||
if (ReadItem(it_id, "Hardware Error Status", err) == DxlError::OK) { | ||
fprintf(stderr, "[ID:%03d] Read Hardware Error Status : %x\n", it_id, err); | ||
|
||
// Check if Hardware Error Status control item exists | ||
uint16_t hw_error_addr, error_code_addr; | ||
uint8_t hw_error_size, error_code_size; | ||
bool hw_error_exists = dxl_info_.GetDxlControlItem( | ||
it_id, "Hardware Error Status", hw_error_addr, hw_error_size); | ||
bool error_code_exists = dxl_info_.GetDxlControlItem( | ||
it_id, "Error Code", error_code_addr, error_code_size); | ||
|
||
if (hw_error_exists) { | ||
uint32_t hw_error_status = 0; | ||
ReadItem(it_id, "Hardware Error Status", hw_error_status); | ||
|
||
std::string error_string = ""; | ||
uint8_t hw_error_byte = static_cast<uint8_t>(hw_error_status); | ||
|
||
for (int bit = 0; bit < 8; ++bit) { | ||
if (hw_error_byte & (1 << bit)) { | ||
const HardwareErrorStatusBitInfo * bit_info = get_hardware_error_status_bit_info(bit); | ||
if (bit_info) { | ||
error_string += bit_info->label; | ||
error_string += " (" + std::string(bit_info->description) + ")/ "; | ||
} else { | ||
error_string += "Unknown Error Bit " + std::to_string(bit) + "/ "; | ||
} | ||
} | ||
} | ||
|
||
if (!error_string.empty()) { | ||
fprintf( | ||
stderr, "[ID:%03d] Hardware Error Details: 0x%x (%d): %s\n", | ||
it_id, hw_error_byte, hw_error_byte, error_string.c_str()); | ||
} | ||
} else if (error_code_exists) { | ||
uint32_t error_code = 0; | ||
ReadItem(it_id, "Error Code", error_code); | ||
|
||
uint8_t error_code_byte = static_cast<uint8_t>(error_code); | ||
if (error_code_byte != 0x00) { | ||
const ErrorCodeInfo * error_info = get_error_code_info(error_code_byte); | ||
if (error_info) { | ||
fprintf( | ||
stderr, "[ID:%03d] Error Code Details: 0x%x (%s): %s\n", | ||
it_id, error_code_byte, error_info->label, error_info->description); | ||
} else { | ||
fprintf( | ||
stderr, "[ID:%03d] Error Code Details: 0x%x (Unknown Error Code)\n", | ||
it_id, error_code_byte); | ||
} | ||
} | ||
} else { | ||
fprintf( | ||
stderr, | ||
"[ID:%03d] Neither Hardware Error Status nor Error Code control items available.\n", | ||
it_id | ||
); | ||
} | ||
fprintf(stderr, "[ID:%03d] Hardware Error detected, rebooting...\n", it_id); | ||
|
||
Reboot(it_id); | ||
return DxlError::DXL_HARDWARE_ERROR; | ||
} else { | ||
|
@@ -215,14 +278,6 @@ DxlError Dynamixel::InitDxlComm( | |
model_name.c_str()); | ||
} | ||
|
||
// First, read the model file to get the control table structure | ||
try { | ||
dxl_info_.ReadDxlModelFile(it_id, dxl_model_number); | ||
} catch (const std::exception & e) { | ||
fprintf(stderr, "[InitDxlComm][ID:%03d] Error reading model file: %s\n", it_id, e.what()); | ||
return DxlError::CANNOT_FIND_CONTROL_ITEM; | ||
} | ||
|
||
// Read firmware version and reload model file with firmware-specific version if available | ||
uint8_t firmware_version = 0; | ||
DxlError fw_result = ReadFirmwareVersion(it_id, firmware_version); | ||
|
@@ -725,6 +780,16 @@ DxlError Dynamixel::ReadItem(uint8_t id, std::string item_name, uint32_t & data) | |
return DxlError::ITEM_READ_FAIL; | ||
} | ||
} else if (dxl_error != 0) { | ||
bool is_alert = dxl_error & 0x80; | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Using the magic number |
||
if (is_alert) { | ||
fprintf( | ||
stderr, | ||
"[ReadItem][ID:%03d][comm_id:%03d] RX_PACKET_ERROR : %s\n", | ||
id, | ||
comm_id, | ||
packet_handler_->getRxPacketError(dxl_error)); | ||
return DxlError::OK; | ||
} | ||
fprintf( | ||
stderr, | ||
"[ReadItem][ID:%03d][comm_id:%03d] RX_PACKET_ERROR : %s (retry %d/%d)\n", | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
The
else
block here appears to be unreachable. Theget_hardware_error_status_bit_info
function is called withbit
values from 0 to 7, and theHardwareErrorStatusTable
indynamixel.hpp
defines entries for all of these bits. As a result,bit_info
will never benullptr
. You can simplify the code by removing theif-else
construct.