| 123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137 |
- // workflow.hpp
- #ifndef WORKFLOW_HPP
- #define WORKFLOW_HPP
- #include <rclcpp/rclcpp.hpp>
- #include <string>
- #include <map>
- #include <memory>
- #include <functional>
- #include "wheelchair_types.hpp"
- #include "error_code.hpp"
- #include <std_msgs/msg/string.hpp>
- #include <std_msgs/msg/u_int32.hpp>
- #include <rclcpp/timer.hpp>
- class WorkflowManager
- {
- public:
- using StateUpdateCallback = std::function<void(const std::string &, const std::string &)>;
- WorkflowManager(rclcpp::Node *node);
- // ==================== 状态机核心接口 ====================
- // 事件处理接口
- bool handleEvent(const std::string &event);
- // 状态查询接口
- std::string getCurrentState() const;
- WheelchairState getCurrentWheelchairState() const { return current_state_; }
- // 状态设置接口
- void setState(WheelchairState new_state);
- // ==================== 状态转移控制 ====================
- // 标准状态转移
- void transitionToWalking();
- void transitionToSearching();
- void transitionToCharging();
- void transitionToReady();
- // 紧急状态转移
- void emergencyTransitionToReady(const std::string &reason = "未知原因");
- // ==================== 回调设置接口 ====================
- void setStateUpdateCallback(StateUpdateCallback callback);
- void setRechargeStatusCallback(StateUpdateCallback callback);
- void setRechargeErrorCallback(std::function<void(const ErrorInfo &)> callback);
- // ==================== 定时器管理 ====================
- void startSearchTimeoutTimer();
- void stopSearchTimeoutTimer();
- // ==================== 事件处理接口 ====================
- // 外部事件处理
- void handleLowBatteryEvent(BatteryState state, float percentage);
- void handleChargingStartEvent();
- void handleChargingStopEvent();
- void handleChargingFullEvent();
- void handleBaseStationLostEvent();
- void handleSearchTimeoutEvent();
- void handleRechargeFailure(const std::string &reason);
- // 内部事件触发
- void triggerEvent(const std::string &event_name);
- private:
- rclcpp::Node *node_;
- // 状态机状态
- WheelchairState current_state_;
- std::map<std::string, std::map<WheelchairState, bool>> transition_table_;
- // ROS发布者
- rclcpp::Publisher<std_msgs::msg::String>::SharedPtr state_publisher_;
- rclcpp::Publisher<std_msgs::msg::String>::SharedPtr recharge_timeout_publisher_;
- // 定时器
- rclcpp::TimerBase::SharedPtr search_timeout_timer_;
- // 回调函数
- StateUpdateCallback state_update_callback_;
- StateUpdateCallback recharge_status_callback_;
- std::function<void(const ErrorInfo &)> recharge_error_callback_;
- // ==================== 私有方法 ====================
- // 初始化方法
- void initializeTransitionTable();
- // 事件权限检查
- bool checkEventPermission(const std::string &event);
- // 事件执行
- void executeEvent(const std::string &event);
- void processStateTransition(const std::string &event);
- // 状态发布
- void publishState(const std::string &state_str, const std::string &message = "");
- std::string stateToString(WheelchairState state) const;
- // 回充状态管理
- void publishRechargeStatus(const std::string &status, const std::string &message);
- void publishRechargeErrorCode(uint32_t error_code);
- // ==================== 具体事件处理函数 ====================
- // 外部事件处理
- void processIpadStartEvent();
- void processIpadCancelEvent();
- void processBluetoothDisconnected();
- void processBluetoothConnected();
- void processBaseStationPowerOff();
- void processLockVehicle();
- void processUnlockVehicle();
- void processJoystickPullBack();
- void processJoystickStop();
- void processPushStart();
- void processPushStop();
- // 错误码处理(保留接口)
- void processErrorCode();
- // ==================== 异常处理函数 ====================
- void handleException(const std::string &context, const std::exception &e);
- // ==================== 定时器回调 ====================
- void searchTimeoutCallback();
- };
- #endif // WORKFLOW_HPP
|