| 
50 | 50 | namespace dynamixel_hardware_interface  | 
51 | 51 | {  | 
52 | 52 | 
 
  | 
 | 53 | +// Hardware Error Status bit definitions  | 
 | 54 | +struct HardwareErrorStatusBitInfo  | 
 | 55 | +{  | 
 | 56 | +  int bit;  | 
 | 57 | +  const char * label;  | 
 | 58 | +  const char * description;  | 
 | 59 | +};  | 
 | 60 | + | 
 | 61 | +static constexpr HardwareErrorStatusBitInfo HardwareErrorStatusTable[] = {  | 
 | 62 | +  {0, "Input Voltage Error", "Detects that input voltage exceeds the configured operating voltage"},  | 
 | 63 | +  {1, "Motor Hall Sensor Error", "Detects that Motor hall sensor value exceeds normal range"},  | 
 | 64 | +  {2, "Overheating Error",  | 
 | 65 | +    "Detects that internal temperature exceeds the configured operating temperature"},  | 
 | 66 | +  {3, "Motor Encoder Error", "Detects malfunction of the motor encoder"},  | 
 | 67 | +  {4,  | 
 | 68 | +    "Electrical Shock Error",  | 
 | 69 | +    "Detects electric shock on the circuit or insufficient power to operate the motor"},  | 
 | 70 | +  {5, "Overload Error", "Detects that persistent load exceeds maximum output"},  | 
 | 71 | +  {6, "Not used", "Always 0"},  | 
 | 72 | +  {7, "Not used", "Always 0"}  | 
 | 73 | +};  | 
 | 74 | + | 
 | 75 | +inline const HardwareErrorStatusBitInfo * get_hardware_error_status_bit_info(int bit)  | 
 | 76 | +{  | 
 | 77 | +  for (const auto & entry : HardwareErrorStatusTable) {  | 
 | 78 | +    if (entry.bit == bit) {return &entry;}  | 
 | 79 | +  }  | 
 | 80 | +  return nullptr;  | 
 | 81 | +}  | 
 | 82 | + | 
 | 83 | +// Error Code (153) definitions  | 
 | 84 | +struct ErrorCodeInfo  | 
 | 85 | +{  | 
 | 86 | +  int value;  | 
 | 87 | +  const char * label;  | 
 | 88 | +  const char * description;  | 
 | 89 | +};  | 
 | 90 | + | 
 | 91 | +static constexpr ErrorCodeInfo ErrorCodeTable[] = {  | 
 | 92 | +  {0x00, "No Error", "No error"},  | 
 | 93 | +  {0x01, "Over Voltage Error", "Device supply voltage exceeds the Max Voltage Limit(60)"},  | 
 | 94 | +  {0x02, "Low Voltage Error", "Device supply voltage exceeds the Min Voltage Limit(62)"},  | 
 | 95 | +  {0x03,  | 
 | 96 | +    "Inverter Overheating Error",  | 
 | 97 | +    "The inverter temperature has exceeded the Inverter Temperature Limit(56)"},  | 
 | 98 | +  {0x04,  | 
 | 99 | +    "Motor Overheating Error",  | 
 | 100 | +    "The motor temperature has exceeded the Motor Temperature Limit(57)"},  | 
 | 101 | +  {0x05, "Overload Error", "Operating current exceeding rated current for an extended duration"},  | 
 | 102 | +  {0x07, "Inverter Error", "An issue has occurred with the inverter"},  | 
 | 103 | +  {0x09, "Battery Warning", "Low Multi-turn battery voltage. Replacement recommended"},  | 
 | 104 | +  {0x0A, "Battery Error", "Multi-turn battery voltage is too low, causing issues"},  | 
 | 105 | +  {0x0B, "Magnet Error", "Multi-turn position lost. Multi-turn reset required"},  | 
 | 106 | +  {0x0C, "Multi-turn Error", "An issue has occurred with the Multi-turn IC"},  | 
 | 107 | +  {0x0D, "Encoder Error", "An issue has occurred with the Encoder IC"},  | 
 | 108 | +  {0x0E, "Hall Sensor Error", "An issue has occurred with the Hall Sensor"},  | 
 | 109 | +  {0x0F, "Calibration Error", "Cannot find calibration Data"},  | 
 | 110 | +  {0x11, "Following Error", "Position control error exceeds the Following Error Threshold(44)"},  | 
 | 111 | +  {0x12, "Bus Watchdog Error", "An issue has occurred with the Bus Watchdog"},  | 
 | 112 | +  {0x13, "Over Speed Error", "Rotates at a speed of 120% or more than the Velocity Limit(72)"},  | 
 | 113 | +  {0x14,  | 
 | 114 | +    "Position Limit Reached Error",  | 
 | 115 | +    "In position control mode, the current position has moved beyond the Max/Min Position Limit"  | 
 | 116 | +    " + Position Limit Threshold(38) range."}  | 
 | 117 | +};  | 
 | 118 | + | 
 | 119 | +inline const ErrorCodeInfo * get_error_code_info(int value)  | 
 | 120 | +{  | 
 | 121 | +  for (const auto & entry : ErrorCodeTable) {  | 
 | 122 | +    if (entry.value == value) {return &entry;}  | 
 | 123 | +  }  | 
 | 124 | +  return nullptr;  | 
 | 125 | +}  | 
 | 126 | + | 
53 | 127 | /**  | 
54 | 128 |  * @brief Constants for hardware state interface names.  | 
55 | 129 |  */  | 
@@ -175,14 +249,16 @@ class DynamixelHardware : public  | 
175 | 249 | private:  | 
176 | 250 |   ///// ros  | 
177 | 251 |   rclcpp::Logger logger_;  | 
 | 252 | +  rclcpp::Clock clock_;  | 
178 | 253 | 
 
  | 
179 | 254 |   ///// dxl error  | 
180 | 255 |   DxlStatus dxl_status_;  | 
181 | 256 |   DxlError dxl_comm_err_;  | 
182 | 257 |   std::map<uint8_t /*id*/, uint8_t /*err*/> dxl_hw_err_;  | 
 | 258 | +  std::map<uint8_t /*id*/, uint8_t /*error code*/> dxl_error_code_;  | 
183 | 259 |   DxlTorqueStatus dxl_torque_status_;  | 
184 | 260 |   std::map<uint8_t /*id*/, bool /*enable*/> dxl_torque_state_;  | 
185 |  | -  std::map<uint8_t /*id*/, bool /*enable*/> dxl_torque_enable_;  | 
 | 261 | +  std::vector<uint8_t> torque_enabled_ids_;  | 
186 | 262 |   double err_timeout_ms_;  | 
187 | 263 |   rclcpp::Duration read_error_duration_{0, 0};  | 
188 | 264 |   rclcpp::Duration write_error_duration_{0, 0};  | 
@@ -298,8 +374,9 @@ class DynamixelHardware : public  | 
298 | 374 |   ///// function  | 
299 | 375 |   /**  | 
300 | 376 |    * @brief Sets up the joint-to-transmission and transmission-to-joint matrices.  | 
 | 377 | +   * @return True if matrices were set up successfully, false otherwise.  | 
301 | 378 |    */  | 
302 |  | -  void SetMatrix();  | 
 | 379 | +  bool SetMatrix();  | 
303 | 380 | 
 
  | 
304 | 381 |   /**  | 
305 | 382 |    * @brief Calculates the joint states from transmission states.  | 
@@ -346,12 +423,30 @@ class DynamixelHardware : public  | 
346 | 423 |     const std::shared_ptr<std_srvs::srv::SetBool::Request> request,  | 
347 | 424 |     std::shared_ptr<std_srvs::srv::SetBool::Response> response);  | 
348 | 425 | 
 
  | 
 | 426 | +  rclcpp::Service<dynamixel_interfaces::srv::GetDataFromDxl>::SharedPtr get_dxl_error_summary_srv_;  | 
 | 427 | +  void get_dxl_error_summary_srv_callback(  | 
 | 428 | +    const std::shared_ptr<dynamixel_interfaces::srv::GetDataFromDxl::Request> request,  | 
 | 429 | +    std::shared_ptr<dynamixel_interfaces::srv::GetDataFromDxl::Response> response);  | 
 | 430 | + | 
349 | 431 |   void initRevoluteToPrismaticParam();  | 
350 | 432 | 
 
  | 
351 | 433 |   double revoluteToPrismatic(double revolute_value);  | 
352 | 434 | 
 
  | 
353 | 435 |   double prismaticToRevolute(double prismatic_value);  | 
354 | 436 | 
 
  | 
 | 437 | +  /**  | 
 | 438 | +   * @brief Get a formatted error summary for a specific Dynamixel ID  | 
 | 439 | +   * @param id The Dynamixel ID  | 
 | 440 | +   * @return A string containing the error summary  | 
 | 441 | +   */  | 
 | 442 | +  std::string getErrorSummary(uint8_t id) const;  | 
 | 443 | + | 
 | 444 | +  /**  | 
 | 445 | +   * @brief Get error summaries for all Dynamixel IDs  | 
 | 446 | +   * @return A string containing error summaries for all Dynamixels  | 
 | 447 | +   */  | 
 | 448 | +  std::string getAllErrorSummaries() const;  | 
 | 449 | + | 
355 | 450 |   void MapInterfaces(  | 
356 | 451 |     size_t outer_size,  | 
357 | 452 |     size_t inner_size,  | 
 | 
0 commit comments