Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
35 changes: 31 additions & 4 deletions src/Dynamixel2Arduino.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -610,14 +610,14 @@ bool Dynamixel2Arduino::setLedState(uint8_t id, bool state)
case PRO_M54P_040_S250_R:
case PRO_M54P_060_S250_R:
if (state == false) {
writeControlTableItem(ControlTableItem::LED_GREEN, id, state);
writeControlTableItem(ControlTableItem::LED_BLUE, id, state);
writeControlTableItem(ControlTableItem::DXL_LED_GREEN, id, state);
writeControlTableItem(ControlTableItem::DXL_LED_BLUE, id, state);
}
ret = writeControlTableItem(ControlTableItem::LED_RED, id, state);
ret = writeControlTableItem(ControlTableItem::DXL_LED_RED, id, state);
break;

default:
ret = writeControlTableItem(ControlTableItem::LED, id, state);
ret = writeControlTableItem(ControlTableItem::DXL_LED, id, state);
break;
}

Expand Down Expand Up @@ -915,6 +915,33 @@ bool Dynamixel2Arduino::getTorqueEnableStat(uint8_t id)
return ret;
}

uint8_t Dynamixel2Arduino::getHardwareError(uint8_t id)
{
uint16_t model_num = getModelNumberFromTable(id);
uint8_t ret = 0;

if(model_num == UNREGISTERED_MODEL){
if(setModelNumber(id, getModelNumber(id)) == true){
model_num = getModelNumberFromTable(id);
}
}
Comment on lines +923 to +927

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

high

What happens if setModelNumber always returns false? This could lead to an infinite loop. Consider adding a counter or a boolean flag to prevent this.

Suggested change
if(model_num == UNREGISTERED_MODEL){
if(setModelNumber(id, getModelNumber(id)) == true){
model_num = getModelNumberFromTable(id);
}
}
if(model_num == UNREGISTERED_MODEL){
static uint8_t retry_count = 0;
if(setModelNumber(id, getModelNumber(id)) == true){
model_num = getModelNumberFromTable(id);
retry_count = 0; // reset the counter if successful
} else {
retry_count++;
if (retry_count > 3) {
setLastLibErrCode(D2A_LIB_ERROR_UNKNOWN_MODEL_NUMBER);
return 0; // or some other appropriate error value
}
}
}


if(model_num == AX12A || model_num == AX12W || model_num == AX18A || model_num == DX113 || model_num == DX116 || model_num == DX117 || model_num == RX10 || model_num == RX24F || model_num == RX28 || model_num == RX64 || model_num == EX106 || model_num == MX12W || model_num == MX28 || model_num == MX64 || model_num == MX106 || model_num == XL320)
{
setLastLibErrCode(DXL_LIB_ERROR_NOT_SUPPORTED);
}
else if(model_num == YM070_210_M001_RH || model_num == YM070_210_B001_RH || model_num == YM070_210_R051_RH || model_num == YM070_210_R099_RH || model_num == YM070_210_A051_RH || model_num == YM070_210_A099_RH || model_num == YM080_230_M001_RH || model_num == YM080_230_B001_RH || model_num == YM080_230_R051_RH || model_num == YM080_230_R099_RH || model_num == YM080_230_A051_RH || model_num == YM080_230_A099_RH)
{
ret = (uint8_t)readControlTableItem(ControlTableItem::ERROR_CODE, id);
}
else
{
ret = (uint8_t)readControlTableItem(ControlTableItem::HARDWARE_ERROR_STATUS, id);
}

return ret;
}

int32_t Dynamixel2Arduino::readControlTableItem(uint8_t item_idx, uint8_t id, uint32_t timeout)
{
int32_t ret = 0;
Expand Down
50 changes: 47 additions & 3 deletions src/Dynamixel2Arduino.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,37 @@ enum D2ALibErrorCode
D2A_LIB_ERROR_UNKNOWN_MODEL_NUMBER
};

enum HardwareErrorCode
{
INPUT_VOLTAGE_ERROR = 0x01,
OVERHEATING_ERROR = 0x04,
MOTOR_ENCODER_ERROR = 0x08,
ELECTRICAL_SHOCK_ERROR = 0x10,
OVERLOAD_ERROR = 0x20
};

enum DYErrorCode
{
DY_NO_ERROR = 0,
DY_OVER_VOLTAGE_ERROR,
DY_LOW_VOLTAGE_ERROR,
DY_INVERTER_OVERHEATING_ERROR,
DY_MOTOR_OVERHEATING_ERROR,
DY_OVERLOAD_ERROR,
DY_INVERTER_ERROR,
DY_BATTERY_WARNING,
DY_BATTERY_ERROR,
DY_MAGNET_ERROR,
DY_MULTI_TURN_ERROR,
DY_ENCODER_ERROR,
DY_HALL_SENSOR_ERROR,
DY_CALIBRATION_ERROR,
DY_FOLLOWING_ERROR,
DY_BUS_WATCHDOG_ERROR,
DY_OVER_SPEED_ERROR,
DY_POSITION_LIMIT_REACHED_ERROR
};

class Dynamixel2Arduino : public DYNAMIXEL::Master
{
public:
Expand Down Expand Up @@ -385,7 +416,22 @@ class Dynamixel2Arduino : public DYNAMIXEL::Master
* @return It returns the Torque Enable data read from DXL control table item.
* If the Torque is On, true(1) is returned. Otherwise false(0) is returned.
*/
bool getTorqueEnableStat(uint8_t id);
bool getTorqueEnableStat(uint8_t id);

/**
* @brief It is API for getting hardware error status of DYNAMIXEL.
* @code
* const int DXL_DIR_PIN = 2;
* Dynamixel2Arduino dxl(Serial1, DXL_DIR_PIN);
* if ((dxl.getHardwareError(1) & INPUT_VOLTAGE_ERROR) == INPUT_VOLTAGE_ERROR) {
* Serial.println("Input Voltage Error");
* }
* @endcode
* @param id DYNAMIXEL Actuator's ID.
* @return It returns 0 on no error, value any other than 0 on hardware error.
* If the read fails, 0 is returned. Whether or not this is an actual value can be confirmed with @getLastLibErrCode().
*/
uint8_t getHardwareError(uint8_t id);

/**
* @brief It is API for getting data of a DYNAMIXEL control table item.
Expand Down Expand Up @@ -441,8 +487,6 @@ class Dynamixel2Arduino : public DYNAMIXEL::Master
bool setPositionPIDGain(uint8_t id, uint16_t p_gain, uint16_t i_gain, uint16_t d_gain);
bool setVelocityPIGain(uint8_t id, uint16_t p_gain, uint16_t i_gain);
bool setFeedForwardGain(uint8_t id, uint16_t fisrt_gain, uint16_t second_gain);

uint8_t getHardwareError(uint8_t id);

// https://github.com/ROBOTIS-GIT/Dynamixel2Arduino/issues/73
uint8_t getOperatingMode(uint8_t id);
Expand Down
22 changes: 11 additions & 11 deletions src/actuator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ const ModelControlTableInfo_t control_table_1_0[] PROGMEM = {
{ControlTableItem::SHUTDOWN, 18, 1},

{ControlTableItem::TORQUE_ENABLE, 24, 1},
{ControlTableItem::LED, 25, 1},
{ControlTableItem::DXL_LED, 25, 1},
{ControlTableItem::CW_COMPLIANCE_MARGIN, 26, 1},
{ControlTableItem::CCW_COMPLIANCE_MARGIN, 27, 1},
{ControlTableItem::CW_COMPLIANCE_SLOPE, 28, 1},
Expand Down Expand Up @@ -85,7 +85,7 @@ const ModelControlTableInfo_t control_table_1_1[] PROGMEM = {
{ControlTableItem::RESOLUTION_DIVIDER, 22, 1},

{ControlTableItem::TORQUE_ENABLE, 24, 1},
{ControlTableItem::LED, 25, 1},
{ControlTableItem::DXL_LED, 25, 1},
{ControlTableItem::D_GAIN, 26, 1},
{ControlTableItem::I_GAIN, 27, 1},
{ControlTableItem::P_GAIN, 28, 1},
Expand Down Expand Up @@ -144,7 +144,7 @@ const ModelControlTableInfo_t xl320_control_table[] PROGMEM = {
{ControlTableItem::SHUTDOWN, 18, 1},

{ControlTableItem::TORQUE_ENABLE, 24, 1},
{ControlTableItem::LED, 25, 1},
{ControlTableItem::DXL_LED, 25, 1},
{ControlTableItem::D_GAIN, 27, 1},
{ControlTableItem::I_GAIN, 28, 1},
{ControlTableItem::P_GAIN, 29, 1},
Expand Down Expand Up @@ -197,7 +197,7 @@ const ModelControlTableInfo_t control_table_2_0[] PROGMEM = {
{ControlTableItem::SHUTDOWN, 63, 1},

{ControlTableItem::TORQUE_ENABLE, 64, 1},
{ControlTableItem::LED, 65, 1},
{ControlTableItem::DXL_LED, 65, 1},
{ControlTableItem::STATUS_RETURN_LEVEL, 68, 1},
{ControlTableItem::REGISTERED_INSTRUCTION, 69, 1},
{ControlTableItem::HARDWARE_ERROR_STATUS, 70, 1},
Expand Down Expand Up @@ -319,9 +319,9 @@ const ModelControlTableInfo_t pro_r_control_table[] PROGMEM = {
{ControlTableItem::SHUTDOWN, 48, 1},

{ControlTableItem::TORQUE_ENABLE, 562, 1},
{ControlTableItem::LED_RED, 563, 1},
{ControlTableItem::LED_GREEN, 564, 1},
{ControlTableItem::LED_BLUE, 565, 1},
{ControlTableItem::DXL_LED_RED, 563, 1},
{ControlTableItem::DXL_LED_GREEN, 564, 1},
{ControlTableItem::DXL_LED_BLUE, 565, 1},
{ControlTableItem::VELOCITY_I_GAIN, 586, 2},
{ControlTableItem::VELOCITY_P_GAIN, 588, 2},
{ControlTableItem::POSITION_P_GAIN, 594, 2},
Expand Down Expand Up @@ -377,9 +377,9 @@ const ModelControlTableInfo_t pro_ra_pro_plus_control_table[] PROGMEM = {
{ControlTableItem::SHUTDOWN, 63, 1},

{ControlTableItem::TORQUE_ENABLE, 512, 1},
{ControlTableItem::LED_RED, 513, 1},
{ControlTableItem::LED_GREEN, 514, 1},
{ControlTableItem::LED_BLUE, 515, 1},
{ControlTableItem::DXL_LED_RED, 513, 1},
{ControlTableItem::DXL_LED_GREEN, 514, 1},
{ControlTableItem::DXL_LED_BLUE, 515, 1},
{ControlTableItem::STATUS_RETURN_LEVEL, 516, 1},
{ControlTableItem::REGISTERED_INSTRUCTION, 517, 1},
{ControlTableItem::HARDWARE_ERROR_STATUS, 518, 1},
Expand Down Expand Up @@ -475,7 +475,7 @@ const ModelControlTableInfo_t y_control_table[] PROGMEM = {
{ControlTableItem::PROFILE_ACCELERATION_TIME, 248, 4},
{ControlTableItem::PROFIIE_TIME, 252, 4},
{ControlTableItem::TORQUE_ENABLE, 512, 1},
{ControlTableItem::LED, 513, 1},
{ControlTableItem::DXL_LED, 513, 1},
{ControlTableItem::PWM_OFFSET, 516, 2},
{ControlTableItem::CURRENT_OFFSET, 518, 2},
{ControlTableItem::VELOCITY_OFFSET, 520, 4},
Expand Down
8 changes: 4 additions & 4 deletions src/actuator.h
Original file line number Diff line number Diff line change
Expand Up @@ -331,10 +331,10 @@ namespace ControlTableItem{
SHUTDOWN,

TORQUE_ENABLE,
LED,
LED_RED,
LED_GREEN,
LED_BLUE,
DXL_LED,
DXL_LED_RED,
DXL_LED_GREEN,
DXL_LED_BLUE,
REGISTERED_INSTRUCTION,
HARDWARE_ERROR_STATUS,
VELOCITY_P_GAIN,
Expand Down