workflow.hpp 4.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137
  1. // workflow.hpp
  2. #ifndef WORKFLOW_HPP
  3. #define WORKFLOW_HPP
  4. #include <rclcpp/rclcpp.hpp>
  5. #include <string>
  6. #include <map>
  7. #include <memory>
  8. #include <functional>
  9. #include "wheelchair_types.hpp"
  10. #include "error_code.hpp"
  11. #include <std_msgs/msg/string.hpp>
  12. #include <std_msgs/msg/u_int32.hpp>
  13. #include <rclcpp/timer.hpp>
  14. class WorkflowManager
  15. {
  16. public:
  17. using StateUpdateCallback = std::function<void(const std::string &, const std::string &)>;
  18. WorkflowManager(rclcpp::Node *node);
  19. // ==================== 状态机核心接口 ====================
  20. // 事件处理接口
  21. bool handleEvent(const std::string &event);
  22. // 状态查询接口
  23. std::string getCurrentState() const;
  24. WheelchairState getCurrentWheelchairState() const { return current_state_; }
  25. // 状态设置接口
  26. void setState(WheelchairState new_state);
  27. // ==================== 状态转移控制 ====================
  28. // 标准状态转移
  29. void transitionToWalking();
  30. void transitionToSearching();
  31. void transitionToCharging();
  32. void transitionToReady();
  33. // 紧急状态转移
  34. void emergencyTransitionToReady(const std::string &reason = "未知原因");
  35. // ==================== 回调设置接口 ====================
  36. void setStateUpdateCallback(StateUpdateCallback callback);
  37. void setRechargeStatusCallback(StateUpdateCallback callback);
  38. void setRechargeErrorCallback(std::function<void(const ErrorInfo &)> callback);
  39. // ==================== 定时器管理 ====================
  40. void startSearchTimeoutTimer();
  41. void stopSearchTimeoutTimer();
  42. // ==================== 事件处理接口 ====================
  43. // 外部事件处理
  44. void handleLowBatteryEvent(BatteryState state, float percentage);
  45. void handleChargingStartEvent();
  46. void handleChargingStopEvent();
  47. void handleChargingFullEvent();
  48. void handleBaseStationLostEvent();
  49. void handleSearchTimeoutEvent();
  50. void handleRechargeFailure(const std::string &reason);
  51. // 内部事件触发
  52. void triggerEvent(const std::string &event_name);
  53. private:
  54. rclcpp::Node *node_;
  55. // 状态机状态
  56. WheelchairState current_state_;
  57. std::map<std::string, std::map<WheelchairState, bool>> transition_table_;
  58. // ROS发布者
  59. rclcpp::Publisher<std_msgs::msg::String>::SharedPtr state_publisher_;
  60. rclcpp::Publisher<std_msgs::msg::String>::SharedPtr recharge_timeout_publisher_;
  61. // 定时器
  62. rclcpp::TimerBase::SharedPtr search_timeout_timer_;
  63. // 回调函数
  64. StateUpdateCallback state_update_callback_;
  65. StateUpdateCallback recharge_status_callback_;
  66. std::function<void(const ErrorInfo &)> recharge_error_callback_;
  67. // ==================== 私有方法 ====================
  68. // 初始化方法
  69. void initializeTransitionTable();
  70. // 事件权限检查
  71. bool checkEventPermission(const std::string &event);
  72. // 事件执行
  73. void executeEvent(const std::string &event);
  74. void processStateTransition(const std::string &event);
  75. // 状态发布
  76. void publishState(const std::string &state_str, const std::string &message = "");
  77. std::string stateToString(WheelchairState state) const;
  78. // 回充状态管理
  79. void publishRechargeStatus(const std::string &status, const std::string &message);
  80. void publishRechargeErrorCode(uint32_t error_code);
  81. // ==================== 具体事件处理函数 ====================
  82. // 外部事件处理
  83. void processIpadStartEvent();
  84. void processIpadCancelEvent();
  85. void processBluetoothDisconnected();
  86. void processBluetoothConnected();
  87. void processBaseStationPowerOff();
  88. void processLockVehicle();
  89. void processUnlockVehicle();
  90. void processJoystickPullBack();
  91. void processJoystickStop();
  92. void processPushStart();
  93. void processPushStop();
  94. // 错误码处理(保留接口)
  95. void processErrorCode();
  96. // ==================== 异常处理函数 ====================
  97. void handleException(const std::string &context, const std::exception &e);
  98. // ==================== 定时器回调 ====================
  99. void searchTimeoutCallback();
  100. };
  101. #endif // WORKFLOW_HPP