report.hpp 3.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116
  1. // report.hpp
  2. #ifndef REPORT_MANAGER_HPP
  3. #define REPORT_MANAGER_HPP
  4. #include <rclcpp/rclcpp.hpp>
  5. #include <string>
  6. #include <functional>
  7. #include <memory>
  8. #include <map>
  9. #include <vector>
  10. #include <mutex>
  11. #include "wheelchair_types.hpp"
  12. #include "error_code.hpp"
  13. #include <std_msgs/msg/string.hpp>
  14. #include <std_msgs/msg/u_int32.hpp>
  15. class ReportManager
  16. {
  17. public:
  18. using StatusReportCallback = std::function<void(const std::string &)>;
  19. using ErrorCallback = std::function<void(const ErrorInfo &)>;
  20. ReportManager(rclcpp::Node *node);
  21. // 错误管理初始化
  22. void initializeErrorManager();
  23. // 报告生成接口
  24. std::string generateSystemStatusReport(
  25. WheelchairState wheelchair_state,
  26. BatteryState battery_state,
  27. float battery_percentage,
  28. ChargingState charging_state,
  29. bool charging_voltage_detected,
  30. bool recharge_active,
  31. const std::string &control_mode);
  32. // 状态报告发布
  33. void publishStatusReport(const std::string &report);
  34. // 特定状态报告
  35. void reportSystemStatus(
  36. WheelchairState wheelchair_state,
  37. BatteryState battery_state,
  38. float battery_percentage,
  39. ChargingState charging_state,
  40. bool charging_voltage_detected,
  41. bool recharge_active,
  42. const std::string &control_mode);
  43. void reportBatteryStatus(BatteryState state, float percentage);
  44. void reportChargingStatus(ChargingState state);
  45. void reportNavigationStatus(const std::string &status);
  46. void reportError(const std::string &error_message);
  47. void reportWarning(const std::string &warning_message);
  48. void reportInfo(const std::string &info_message);
  49. // 错误处理接口
  50. void processErrorCode(uint32_t error_code);
  51. void processErrorCode(const ErrorInfo &error_info);
  52. void notifyErrorRecovered(uint32_t error_code);
  53. // 错误查询接口
  54. bool hasCriticalErrors() const;
  55. bool hasError(uint32_t error_code) const;
  56. std::vector<ErrorInfo> getActiveErrors() const;
  57. std::vector<ErrorInfo> getCriticalErrors() const;
  58. // 回调设置
  59. void setStatusReportCallback(StatusReportCallback callback);
  60. void setErrorCallback(ErrorCallback callback);
  61. void setCriticalErrorCallback(ErrorCallback callback);
  62. void setRecoveryCallback(ErrorCallback callback);
  63. private:
  64. rclcpp::Node *node_;
  65. rclcpp::Publisher<std_msgs::msg::String>::SharedPtr report_publisher_;
  66. // 错误订阅者
  67. rclcpp::Subscription<std_msgs::msg::UInt32>::SharedPtr error_sub_;
  68. StatusReportCallback status_report_callback_;
  69. // 错误管理相关
  70. std::map<uint32_t, ErrorInfo> active_errors_;
  71. mutable std::mutex error_mutex_;
  72. ErrorCallback error_callback_;
  73. ErrorCallback critical_error_callback_;
  74. ErrorCallback recovery_callback_;
  75. // 错误码映射
  76. static std::map<uint32_t, std::string> error_descriptions_;
  77. static std::map<ErrorModule, std::string> module_names_;
  78. static std::map<ErrorSubModule, std::string> sub_module_names_;
  79. // 辅助函数
  80. std::string wheelchairStateToString(WheelchairState state) const;
  81. std::string batteryStateToString(BatteryState state) const;
  82. std::string chargingStateToString(ChargingState state) const;
  83. // 错误处理函数
  84. void errorCodeCallback(const std_msgs::msg::UInt32::SharedPtr msg);
  85. ErrorInfo parseErrorCode(uint32_t error_code);
  86. void handleNewError(const ErrorInfo &error_info);
  87. void handleErrorRecovery(const ErrorInfo &error_info);
  88. static std::string getErrorDescription(uint32_t error_code);
  89. static std::string getModuleName(ErrorModule module);
  90. static std::string getSubModuleName(ErrorSubModule sub_module);
  91. static void initializeErrorMaps();
  92. void logReport(const std::string &category, const std::string &message);
  93. };
  94. #endif // REPORT_MANAGER_HPP