瀏覽代碼

wheelchair_state_machine

sousenw 2 月之前
父節點
當前提交
71a1212f30
共有 27 個文件被更改,包括 482 次插入403 次删除
  1. 0 53
      src/wheelchair_state_machine/include/wheelchair_state_machine/wheelchair_state_machine.hpp
  2. 0 143
      src/wheelchair_state_machine/src/event_input.cpp
  3. 0 20
      src/wheelchair_state_machine/src/main.cpp
  4. 0 186
      src/wheelchair_state_machine/src/wheelchair_state_machine.cpp
  5. 0 0
      src3/interface/CMakeLists.txt
  6. 0 0
      src3/interface/msg/Empty.msg
  7. 0 0
      src3/interface/package.xml
  8. 0 0
      src3/interface/srv/SceneControls.srv
  9. 0 1
      src3/wheelchair_state_machine/CMakeLists.txt
  10. 0 0
      src3/wheelchair_state_machine/LICENSE
  11. 0 0
      src3/wheelchair_state_machine/include/wheelchair_state_machine/battery_manager.hpp
  12. 36 0
      src3/wheelchair_state_machine/include/wheelchair_state_machine/event_input.hpp
  13. 0 0
      src3/wheelchair_state_machine/include/wheelchair_state_machine/ipad_manager.hpp
  14. 0 0
      src3/wheelchair_state_machine/include/wheelchair_state_machine/lidascan_ctrl.hpp
  15. 0 0
      src3/wheelchair_state_machine/include/wheelchair_state_machine/recharge_tool.hpp
  16. 0 0
      src3/wheelchair_state_machine/include/wheelchair_state_machine/report.hpp
  17. 0 0
      src3/wheelchair_state_machine/include/wheelchair_state_machine/wheelchair_types.hpp
  18. 0 0
      src3/wheelchair_state_machine/include/wheelchair_state_machine/workflow.hpp
  19. 0 0
      src3/wheelchair_state_machine/package.xml
  20. 0 0
      src3/wheelchair_state_machine/src/battery_manager.cpp
  21. 412 0
      src3/wheelchair_state_machine/src/event_input.cpp
  22. 0 0
      src3/wheelchair_state_machine/src/ipad_manager.cpp
  23. 0 0
      src3/wheelchair_state_machine/src/lidascan_ctrl.cpp
  24. 34 0
      src3/wheelchair_state_machine/src/main.cpp
  25. 0 0
      src3/wheelchair_state_machine/src/recharge_tool.cpp
  26. 0 0
      src3/wheelchair_state_machine/src/report.cpp
  27. 0 0
      src3/wheelchair_state_machine/src/workflow.cpp

+ 0 - 53
src/wheelchair_state_machine/include/wheelchair_state_machine/wheelchair_state_machine.hpp

@@ -1,53 +0,0 @@
-// wheelchair_state_machine.hpp
-#ifndef WHEELCHAIR_STATE_MACHINE_HPP
-#define WHEELCHAIR_STATE_MACHINE_HPP
-
-#include <rclcpp/rclcpp.hpp>
-#include <string>
-#include <memory>
-#include "wheelchair_types.hpp"
-#include "battery_manager.hpp"
-#include "lidascan_ctrl.hpp"
-#include "ipad_manager.hpp"
-#include "workflow.hpp"
-#include "event_input.hpp"
-#include "report.hpp"
-#include <std_msgs/msg/bool.hpp>
-
-class WheelchairStateMachine : public rclcpp::Node
-{
-public:
-    WheelchairStateMachine();
-    
-    // 状态查询接口
-    std::string getCurrentState() const;
-    bool isRechargeActive() const;
-    
-    // 系统状态显示
-    void displaySystemStatus();
-    
-private:
-    // 模块化组件
-    BatteryManager battery_manager_;
-    LidarScanController lidar_controller_;
-    IpadManager ipad_manager_;
-    WorkflowManager workflow_manager_;
-    EventInputHandler event_handler_;
-    ReportManager report_manager_;
-    
-    // ROS订阅者
-    rclcpp::Subscription<std_msgs::msg::Bool>::SharedPtr cmd_enable_sub_;
-    
-    // 状态标志
-    bool interface_active_;
-    
-    // 初始化
-    void initializeModules();
-    void setupModuleCallbacks();
-    
-    // 导航控制
-    void startNavigationControl();
-    void stopNavigationControl();
-};
-
-#endif // WHEELCHAIR_STATE_MACHINE_HPP

+ 0 - 143
src/wheelchair_state_machine/src/event_input.cpp

@@ -1,143 +0,0 @@
-// event_input.cpp
-#include "wheelchair_state_machine/event_input.hpp"
-#include <rclcpp/logging.hpp>
-
-using namespace std::chrono_literals;
-
-EventInputHandler::EventInputHandler(rclcpp::Node* node)
-    : node_(node)
-{
-    RCLCPP_INFO(node_->get_logger(), "事件输入处理器已初始化");
-}
-
-void EventInputHandler::registerEvent(const std::string& event_name, EventCallback callback)
-{
-    event_callbacks_[event_name] = callback;
-    RCLCPP_INFO(node_->get_logger(), "已注册事件: %s", event_name.c_str());
-}
-
-void EventInputHandler::triggerEvent(const std::string& event_name)
-{
-    triggerEvent(event_name, "");
-}
-
-void EventInputHandler::triggerEvent(const std::string& event_name, const std::string& data)
-{
-    logEvent(event_name, data);
-    
-    if (event_callbacks_.find(event_name) != event_callbacks_.end())
-    {
-        event_callbacks_[event_name](data);
-    }
-    else
-    {
-        RCLCPP_WARN(node_->get_logger(), "未注册的事件: %s", event_name.c_str());
-    }
-}
-
-void EventInputHandler::triggerIpadStart()
-{
-    triggerEvent("ipad_phone_interface_start", "iPad启动回充");
-}
-
-void EventInputHandler::triggerIpadCancel()
-{
-    triggerEvent("ipad_phone_interface_cancel", "iPad取消回充");
-}
-
-void EventInputHandler::triggerBluetoothDisconnected()
-{
-    triggerEvent("bluetooth_disconnected", "蓝牙断开连接");
-}
-
-void EventInputHandler::triggerBluetoothConnected()
-{
-    triggerEvent("bluetooth_connected", "蓝牙已连接");
-}
-
-void EventInputHandler::triggerBaseStationPowerOff()
-{
-    triggerEvent("base_station_power_off", "基站断电");
-}
-
-void EventInputHandler::triggerLowBattery(BatteryState state, float percentage)
-{
-    std::string data = "低电量警告 - 状态: ";
-    data += std::to_string(static_cast<int>(state));
-    data += ", 电量: " + std::to_string(percentage) + "%";
-    triggerEvent("low_battery_warning", data);
-}
-
-void EventInputHandler::triggerLockVehicle()
-{
-    triggerEvent("lock_vehicle", "锁车操作");
-}
-
-void EventInputHandler::triggerUnlockVehicle()
-{
-    triggerEvent("unlock_vehicle", "解锁操作");
-}
-
-void EventInputHandler::triggerJoystickPullBack()
-{
-    triggerEvent("joystick_pull_back", "摇杆后拉");
-}
-
-void EventInputHandler::triggerJoystickStop()
-{
-    triggerEvent("joystick_stop", "摇杆停止");
-}
-
-void EventInputHandler::triggerPushStart()
-{
-    triggerEvent("push_start", "推行启动");
-}
-
-void EventInputHandler::triggerPushStop()
-{
-    triggerEvent("push_stop", "推行停止");
-}
-
-void EventInputHandler::triggerBatteryStartCharging()
-{
-    triggerEvent("battery_start_charging", "开始充电");
-}
-
-void EventInputHandler::triggerBatteryStopCharging()
-{
-    triggerEvent("battery_stop_charging", "停止充电");
-}
-
-void EventInputHandler::triggerBatteryFull()
-{
-    triggerEvent("battery_full", "电池充满");
-}
-
-void EventInputHandler::triggerErrorCode(int error_code)
-{
-    std::string data = "错误码: " + std::to_string(error_code);
-    triggerEvent("error_code_handling", data);
-}
-
-void EventInputHandler::triggerBaseStationLost()
-{
-    triggerEvent("base_station_lost", "基站检测丢失");
-}
-
-void EventInputHandler::triggerSearchTimeout()
-{
-    triggerEvent("search_30s_timeout", "搜索30秒超时");
-}
-
-void EventInputHandler::logEvent(const std::string& event_name, const std::string& details)
-{
-    if (details.empty())
-    {
-        RCLCPP_INFO(node_->get_logger(), "触发事件: %s", event_name.c_str());
-    }
-    else
-    {
-        RCLCPP_INFO(node_->get_logger(), "触发事件: %s - %s", 
-                   event_name.c_str(), details.c_str());
-    }
-}

+ 0 - 20
src/wheelchair_state_machine/src/main.cpp

@@ -1,20 +0,0 @@
-// main.cpp
-#include "wheelchair_state_machine/wheelchair_state_machine.hpp"
-#include <rclcpp/rclcpp.hpp>
-#include <memory>
-
-int main(int argc, char **argv)
-{
-    rclcpp::init(argc, argv);
-    
-    auto state_machine = std::make_shared<WheelchairStateMachine>();
-    
-    // 显示系统状态
-    state_machine->displaySystemStatus();
-    
-    // 保持节点运行
-    rclcpp::spin(state_machine);
-    rclcpp::shutdown();
-    
-    return 0;
-}

+ 0 - 186
src/wheelchair_state_machine/src/wheelchair_state_machine.cpp

@@ -1,186 +0,0 @@
-// wheelchair_state_machine.cpp
-#include "wheelchair_state_machine/wheelchair_state_machine.hpp"
-#include <rclcpp/logging.hpp>
-#include <rclcpp/qos.hpp>
-
-using namespace std::chrono_literals;
-using std::placeholders::_1;
-
-WheelchairStateMachine::WheelchairStateMachine()
-    : Node("wheelchair_state_machine")
-    , battery_manager_(this, 20.0f, 10.0f)
-    , lidar_controller_(this)
-    , ipad_manager_(this)
-    , workflow_manager_(this)
-    , event_handler_(this)
-    , report_manager_(this)
-    , interface_active_(false)
-{
-    initializeModules();
-    setupModuleCallbacks();
-    
-    RCLCPP_INFO(this->get_logger(), "智能轮椅状态机已启动");
-}
-
-void WheelchairStateMachine::initializeModules()
-{
-    // 初始化所有模块
-    battery_manager_.initialize();
-    lidar_controller_.initialize();
-    
-    RCLCPP_INFO(this->get_logger(), "所有模块初始化完成");
-}
-
-void WheelchairStateMachine::setupModuleCallbacks()
-{
-    // 1. 设置电池管理器回调
-    battery_manager_.setBatteryStateCallback(
-        [this](BatteryState state, float percentage) {
-            // 报告电池状态
-            report_manager_.reportBatteryStatus(state, percentage);
-            
-            // 触发电池状态事件
-            if (state == BatteryState::CHARGING)
-            {
-                event_handler_.triggerEvent("battery_start_charging");
-            }
-            else if (state == BatteryState::FULL)
-            {
-                event_handler_.triggerEvent("battery_full");
-            }
-        });
-    
-    battery_manager_.setLowBatteryCallback(
-        [this](BatteryState state, float percentage) {
-            // 触发低电量事件
-            event_handler_.triggerLowBattery(state, percentage);
-        });
-    
-    // 2. 设置iPad管理器回调 - 只处理开始和结束
-    ipad_manager_.setRechargeStartCallback(
-        [this]() {
-            RCLCPP_INFO(this->get_logger(), "iPad启动回充");
-            event_handler_.triggerEvent("ipad_phone_interface_start");
-        });
-    
-    ipad_manager_.setRechargeCancelCallback(
-        [this]() {
-            RCLCPP_INFO(this->get_logger(), "iPad取消回充");
-            event_handler_.triggerEvent("ipad_phone_interface_cancel");
-        });
-    
-    // 3. 设置工作流管理器回调
-    workflow_manager_.setStateUpdateCallback(
-        [this](const std::string& state_str, const std::string& message) {
-            // 报告状态更新
-            report_manager_.reportInfo(state_str + ": " + message);
-            
-            // 根据状态变化控制导航
-            WheelchairState current_state = workflow_manager_.getCurrentWheelchairState();
-            if (current_state == WheelchairState::SEARCHING)
-            {
-                startNavigationControl();
-            }
-            else if (current_state == WheelchairState::CHARGING)
-            {
-                lidar_controller_.stopMotion();
-                lidar_controller_.setChargingVoltage(true);
-            }
-            else if (current_state == WheelchairState::READY)
-            {
-                stopNavigationControl();
-            }
-        });
-    
-    // 4. 设置事件处理器回调 - 所有事件都转发给工作流管理器
-    event_handler_.registerEvent("ipad_phone_interface_start",
-        [this](const std::string& data) {
-            RCLCPP_INFO(this->get_logger(), "处理iPad启动事件");
-            workflow_manager_.handleEvent("ipad_phone_interface_start");
-        });
-    
-    event_handler_.registerEvent("ipad_phone_interface_cancel",
-        [this](const std::string& data) {
-            RCLCPP_INFO(this->get_logger(), "处理iPad取消事件");
-            workflow_manager_.handleEvent("ipad_phone_interface_cancel");
-        });
-    
-    event_handler_.registerEvent("low_battery_warning",
-        [this](const std::string& data) {
-            RCLCPP_INFO(this->get_logger(), "处理低电量事件");
-            workflow_manager_.handleEvent("low_battery_warning");
-        });
-    
-    event_handler_.registerEvent("battery_start_charging",
-        [this](const std::string& data) {
-            RCLCPP_INFO(this->get_logger(), "处理开始充电事件");
-            workflow_manager_.handleEvent("battery_start_charging");
-        });
-    
-    event_handler_.registerEvent("battery_stop_charging",
-        [this](const std::string& data) {
-            RCLCPP_INFO(this->get_logger(), "处理停止充电事件");
-            workflow_manager_.handleEvent("battery_stop_charging");
-        });
-    
-    event_handler_.registerEvent("battery_full",
-        [this](const std::string& data) {
-            RCLCPP_INFO(this->get_logger(), "处理电池充满事件");
-            workflow_manager_.handleEvent("battery_full");
-        });
-    
-    // 5. 创建命令使能订阅者
-    cmd_enable_sub_ = this->create_subscription<std_msgs::msg::Bool>(
-        "/recharge/cmd_enable", 10,
-        [this](const std_msgs::msg::Bool::SharedPtr msg) {
-            this->ipad_manager_.onCmdEnable(msg);
-        });
-    
-    RCLCPP_INFO(this->get_logger(), "模块回调设置完成");
-}
-
-void WheelchairStateMachine::startNavigationControl()
-{
-    if (!interface_active_)
-    {
-        lidar_controller_.startNavigation();
-        interface_active_ = true;
-        RCLCPP_INFO(this->get_logger(), "启动导航控制");
-    }
-}
-
-void WheelchairStateMachine::stopNavigationControl()
-{
-    if (interface_active_)
-    {
-        lidar_controller_.stopNavigation();
-        lidar_controller_.stopMotion();
-        interface_active_ = false;
-        RCLCPP_INFO(this->get_logger(), "停止导航控制");
-    }
-}
-
-std::string WheelchairStateMachine::getCurrentState() const
-{
-    return workflow_manager_.getCurrentState();
-}
-
-bool WheelchairStateMachine::isRechargeActive() const
-{
-    return interface_active_;
-}
-
-void WheelchairStateMachine::displaySystemStatus()
-{
-    std::string control_mode = interface_active_ ? "iPad控制" : "本地控制";
-    
-    report_manager_.reportSystemStatus(
-        workflow_manager_.getCurrentWheelchairState(),
-        battery_manager_.getBatteryState(),
-        battery_manager_.getBatteryPercentage(),
-        lidar_controller_.getChargingState(),
-        lidar_controller_.getChargingVoltage(),
-        isRechargeActive(),
-        control_mode
-    );
-}

+ 0 - 0
src/interface/CMakeLists.txt → src3/interface/CMakeLists.txt


+ 0 - 0
src/interface/msg/Empty.msg → src3/interface/msg/Empty.msg


+ 0 - 0
src/interface/package.xml → src3/interface/package.xml


+ 0 - 0
src/interface/srv/SceneControls.srv → src3/interface/srv/SceneControls.srv


+ 0 - 1
src/wheelchair_state_machine/CMakeLists.txt → src3/wheelchair_state_machine/CMakeLists.txt

@@ -33,7 +33,6 @@ add_executable(wheelchair_state_machine
   src/recharge_tool.cpp
   src/ipad_manager.cpp
   src/battery_manager.cpp
-  src/wheelchair_state_machine.cpp
 )
 
 # 使用 ament_target_dependencies 自动处理ROS2依赖

+ 0 - 0
src/wheelchair_state_machine/LICENSE → src3/wheelchair_state_machine/LICENSE


+ 0 - 0
src/wheelchair_state_machine/include/wheelchair_state_machine/battery_manager.hpp → src3/wheelchair_state_machine/include/wheelchair_state_machine/battery_manager.hpp


+ 36 - 0
src/wheelchair_state_machine/include/wheelchair_state_machine/event_input.hpp → src3/wheelchair_state_machine/include/wheelchair_state_machine/event_input.hpp

@@ -8,6 +8,12 @@
 #include <map>
 #include <memory>
 #include "wheelchair_types.hpp"
+#include "battery_manager.hpp"
+#include "lidascan_ctrl.hpp"
+#include "ipad_manager.hpp"
+#include "workflow.hpp"
+#include "report.hpp"
+#include <std_msgs/msg/bool.hpp>
 
 class EventInputHandler
 {
@@ -16,6 +22,9 @@ public:
     
     EventInputHandler(rclcpp::Node* node);
     
+    // 初始化接口
+    void initializeModules();
+    
     // 事件注册接口
     void registerEvent(const std::string& event_name, EventCallback callback);
     
@@ -43,10 +52,37 @@ public:
     void triggerBaseStationLost();
     void triggerSearchTimeout();
     
+    // 系统状态查询
+    std::string getCurrentState() const;
+    bool isRechargeActive() const;
+    
+    // 系统状态显示
+    void displaySystemStatus();
+    
 private:
     rclcpp::Node* node_;
+    
+    // 模块化组件
+    std::unique_ptr<BatteryManager> battery_manager_;
+    std::unique_ptr<LidarScanController> lidar_controller_;
+    std::unique_ptr<IpadManager> ipad_manager_;
+    std::unique_ptr<WorkflowManager> workflow_manager_;
+    std::unique_ptr<ReportManager> report_manager_;
+    
+    // ROS订阅者
+    rclcpp::Subscription<std_msgs::msg::Bool>::SharedPtr cmd_enable_sub_;
+    
+    // 事件回调映射
     std::map<std::string, EventCallback> event_callbacks_;
     
+    // 状态标志
+    bool interface_active_ = false;
+    
+    // 私有方法
+    void setupModuleCallbacks();
+    void setupSubscriptions();
+    void startNavigationControl();
+    void stopNavigationControl();
     void logEvent(const std::string& event_name, const std::string& details = "");
 };
 

+ 0 - 0
src/wheelchair_state_machine/include/wheelchair_state_machine/ipad_manager.hpp → src3/wheelchair_state_machine/include/wheelchair_state_machine/ipad_manager.hpp


+ 0 - 0
src/wheelchair_state_machine/include/wheelchair_state_machine/lidascan_ctrl.hpp → src3/wheelchair_state_machine/include/wheelchair_state_machine/lidascan_ctrl.hpp


+ 0 - 0
src/wheelchair_state_machine/include/wheelchair_state_machine/recharge_tool.hpp → src3/wheelchair_state_machine/include/wheelchair_state_machine/recharge_tool.hpp


+ 0 - 0
src/wheelchair_state_machine/include/wheelchair_state_machine/report.hpp → src3/wheelchair_state_machine/include/wheelchair_state_machine/report.hpp


+ 0 - 0
src/wheelchair_state_machine/include/wheelchair_state_machine/wheelchair_types.hpp → src3/wheelchair_state_machine/include/wheelchair_state_machine/wheelchair_types.hpp


+ 0 - 0
src/wheelchair_state_machine/include/wheelchair_state_machine/workflow.hpp → src3/wheelchair_state_machine/include/wheelchair_state_machine/workflow.hpp


+ 0 - 0
src/wheelchair_state_machine/package.xml → src3/wheelchair_state_machine/package.xml


+ 0 - 0
src/wheelchair_state_machine/src/battery_manager.cpp → src3/wheelchair_state_machine/src/battery_manager.cpp


+ 412 - 0
src3/wheelchair_state_machine/src/event_input.cpp

@@ -0,0 +1,412 @@
+#include "wheelchair_state_machine/event_input.hpp"
+#include <rclcpp/logging.hpp>
+#include <std_msgs/msg/bool.hpp>
+
+using namespace std::chrono_literals;
+
+EventInputHandler::EventInputHandler(rclcpp::Node* node)
+    : node_(node)
+    , battery_manager_(nullptr)
+    , lidar_controller_(nullptr)
+    , ipad_manager_(nullptr)
+    , workflow_manager_(nullptr)
+    , report_manager_(nullptr)
+{
+    RCLCPP_INFO(node_->get_logger(), "事件输入处理器已初始化");
+}
+
+void EventInputHandler::initializeModules()
+{
+    // 初始化电池管理器
+    battery_manager_ = std::make_unique<BatteryManager>(node_, 20.0f, 10.0f);
+    battery_manager_->initialize();
+    
+    // 初始化激光控制器
+    lidar_controller_ = std::make_unique<LidarScanController>(node_);
+    lidar_controller_->initialize();
+    
+    // 初始化iPad管理器
+    ipad_manager_ = std::make_unique<IpadManager>(node_);
+    
+    // 初始化工作流管理器
+    workflow_manager_ = std::make_unique<WorkflowManager>(node_);
+    
+    // 初始化报告管理器
+    report_manager_ = std::make_unique<ReportManager>(node_);
+    
+    setupModuleCallbacks();
+    setupSubscriptions();
+    
+    RCLCPP_INFO(node_->get_logger(), "所有模块初始化完成");
+}
+
+void EventInputHandler::setupModuleCallbacks()
+{
+    // 1. 设置电池管理器回调
+    battery_manager_->setBatteryStateCallback(
+        [this](BatteryState state, float percentage) {
+            // 报告电池状态
+            report_manager_->reportBatteryStatus(state, percentage);
+            
+            // 触发电池状态事件
+            if (state == BatteryState::CHARGING)
+            {
+                triggerEvent("battery_start_charging");
+            }
+            else if (state == BatteryState::FULL)
+            {
+                triggerEvent("battery_full");
+            }
+        });
+    
+    battery_manager_->setLowBatteryCallback(
+        [this](BatteryState state, float percentage) {
+            // 触发低电量事件
+            triggerLowBattery(state, percentage);
+        });
+    
+    // 2. 设置iPad管理器回调 - 只处理开始和结束
+    ipad_manager_->setRechargeStartCallback(
+        [this]() {
+            RCLCPP_INFO(node_->get_logger(), "iPad启动回充");
+            triggerEvent("ipad_phone_interface_start");
+        });
+    
+    ipad_manager_->setRechargeCancelCallback(
+        [this]() {
+            RCLCPP_INFO(node_->get_logger(), "iPad取消回充");
+            triggerEvent("ipad_phone_interface_cancel");
+        });
+    
+    // 3. 设置工作流管理器回调
+    workflow_manager_->setStateUpdateCallback(
+        [this](const std::string& state_str, const std::string& message) {
+            // 报告状态更新
+            report_manager_->reportInfo(state_str + ": " + message);
+            
+            // 根据状态变化控制导航
+            WheelchairState current_state = workflow_manager_->getCurrentWheelchairState();
+            if (current_state == WheelchairState::SEARCHING)
+            {
+                startNavigationControl();
+            }
+            else if (current_state == WheelchairState::CHARGING)
+            {
+                lidar_controller_->stopMotion();
+                lidar_controller_->setChargingVoltage(true);
+            }
+            else if (current_state == WheelchairState::READY)
+            {
+                stopNavigationControl();
+            }
+        });
+    
+    // 4. 设置事件处理器回调 - 所有事件都转发给工作流管理器
+    registerEvent("ipad_phone_interface_start",
+        [this](const std::string& data) {
+            RCLCPP_INFO(node_->get_logger(), "处理iPad启动事件");
+            workflow_manager_->handleEvent("ipad_phone_interface_start");
+        });
+    
+    registerEvent("ipad_phone_interface_cancel",
+        [this](const std::string& data) {
+            RCLCPP_INFO(node_->get_logger(), "处理iPad取消事件");
+            workflow_manager_->handleEvent("ipad_phone_interface_cancel");
+        });
+    
+    registerEvent("low_battery_warning",
+        [this](const std::string& data) {
+            RCLCPP_INFO(node_->get_logger(), "处理低电量事件");
+            workflow_manager_->handleEvent("low_battery_warning");
+        });
+    
+    registerEvent("battery_start_charging",
+        [this](const std::string& data) {
+            RCLCPP_INFO(node_->get_logger(), "处理开始充电事件");
+            workflow_manager_->handleEvent("battery_start_charging");
+        });
+    
+    registerEvent("battery_stop_charging",
+        [this](const std::string& data) {
+            RCLCPP_INFO(node_->get_logger(), "处理停止充电事件");
+            workflow_manager_->handleEvent("battery_stop_charging");
+        });
+    
+    registerEvent("battery_full",
+        [this](const std::string& data) {
+            RCLCPP_INFO(node_->get_logger(), "处理电池充满事件");
+            workflow_manager_->handleEvent("battery_full");
+        });
+    
+    registerEvent("bluetooth_disconnected",
+        [this](const std::string& data) {
+            RCLCPP_INFO(node_->get_logger(), "处理蓝牙断开事件");
+            workflow_manager_->handleEvent("bluetooth_disconnected");
+        });
+    
+    registerEvent("bluetooth_connected",
+        [this](const std::string& data) {
+            RCLCPP_INFO(node_->get_logger(), "处理蓝牙连接事件");
+            workflow_manager_->handleEvent("bluetooth_connected");
+        });
+    
+    registerEvent("base_station_power_off",
+        [this](const std::string& data) {
+            RCLCPP_INFO(node_->get_logger(), "处理基站断电事件");
+            workflow_manager_->handleEvent("base_station_power_off");
+        });
+    
+    registerEvent("lock_vehicle",
+        [this](const std::string& data) {
+            RCLCPP_INFO(node_->get_logger(), "处理锁车事件");
+            workflow_manager_->handleEvent("lock_vehicle");
+        });
+    
+    registerEvent("unlock_vehicle",
+        [this](const std::string& data) {
+            RCLCPP_INFO(node_->get_logger(), "处理解锁事件");
+            workflow_manager_->handleEvent("unlock_vehicle");
+        });
+    
+    registerEvent("joystick_pull_back",
+        [this](const std::string& data) {
+            RCLCPP_INFO(node_->get_logger(), "处理摇杆后拉事件");
+            workflow_manager_->handleEvent("joystick_pull_back");
+        });
+    
+    registerEvent("joystick_stop",
+        [this](const std::string& data) {
+            RCLCPP_INFO(node_->get_logger(), "处理摇杆停止事件");
+            workflow_manager_->handleEvent("joystick_stop");
+        });
+    
+    registerEvent("push_start",
+        [this](const std::string& data) {
+            RCLCPP_INFO(node_->get_logger(), "处理推行启动事件");
+            workflow_manager_->handleEvent("push_start");
+        });
+    
+    registerEvent("push_stop",
+        [this](const std::string& data) {
+            RCLCPP_INFO(node_->get_logger(), "处理推行停止事件");
+            workflow_manager_->handleEvent("push_stop");
+        });
+    
+    registerEvent("error_code_handling",
+        [this](const std::string& data) {
+            RCLCPP_INFO(node_->get_logger(), "处理错误码事件");
+            workflow_manager_->handleEvent("error_code_handling");
+        });
+    
+    registerEvent("base_station_lost",
+        [this](const std::string& data) {
+            RCLCPP_INFO(node_->get_logger(), "处理基站丢失事件");
+            workflow_manager_->handleEvent("base_station_lost");
+        });
+    
+    registerEvent("search_30s_timeout",
+        [this](const std::string& data) {
+            RCLCPP_INFO(node_->get_logger(), "处理搜索超时事件");
+            workflow_manager_->handleEvent("search_30s_timeout");
+        });
+    
+    RCLCPP_INFO(node_->get_logger(), "模块回调设置完成");
+}
+
+void EventInputHandler::setupSubscriptions()
+{
+    // 创建命令使能订阅者
+    cmd_enable_sub_ = node_->create_subscription<std_msgs::msg::Bool>(
+        "/recharge/cmd_enable", 10,
+        [this](const std_msgs::msg::Bool::SharedPtr msg) {
+            this->ipad_manager_->onCmdEnable(msg);
+        });
+    
+    RCLCPP_INFO(node_->get_logger(), "订阅器设置完成");
+}
+
+void EventInputHandler::startNavigationControl()
+{
+    if (!interface_active_)
+    {
+        lidar_controller_->startNavigation();
+        interface_active_ = true;
+        RCLCPP_INFO(node_->get_logger(), "启动导航控制");
+    }
+}
+
+void EventInputHandler::stopNavigationControl()
+{
+    if (interface_active_)
+    {
+        lidar_controller_->stopNavigation();
+        lidar_controller_->stopMotion();
+        interface_active_ = false;
+        RCLCPP_INFO(node_->get_logger(), "停止导航控制");
+    }
+}
+
+void EventInputHandler::registerEvent(const std::string& event_name, EventCallback callback)
+{
+    event_callbacks_[event_name] = callback;
+    RCLCPP_INFO(node_->get_logger(), "已注册事件: %s", event_name.c_str());
+}
+
+void EventInputHandler::triggerEvent(const std::string& event_name)
+{
+    triggerEvent(event_name, "");
+}
+
+void EventInputHandler::triggerEvent(const std::string& event_name, const std::string& data)
+{
+    logEvent(event_name, data);
+    
+    if (event_callbacks_.find(event_name) != event_callbacks_.end())
+    {
+        event_callbacks_[event_name](data);
+    }
+    else
+    {
+        RCLCPP_WARN(node_->get_logger(), "未注册的事件: %s", event_name.c_str());
+    }
+}
+
+void EventInputHandler::triggerIpadStart()
+{
+    triggerEvent("ipad_phone_interface_start", "iPad启动回充");
+}
+
+void EventInputHandler::triggerIpadCancel()
+{
+    triggerEvent("ipad_phone_interface_cancel", "iPad取消回充");
+}
+
+void EventInputHandler::triggerBluetoothDisconnected()
+{
+    triggerEvent("bluetooth_disconnected", "蓝牙断开连接");
+}
+
+void EventInputHandler::triggerBluetoothConnected()
+{
+    triggerEvent("bluetooth_connected", "蓝牙已连接");
+}
+
+void EventInputHandler::triggerBaseStationPowerOff()
+{
+    triggerEvent("base_station_power_off", "基站断电");
+}
+
+void EventInputHandler::triggerLowBattery(BatteryState state, float percentage)
+{
+    std::string data = "低电量警告 - 状态: ";
+    data += std::to_string(static_cast<int>(state));
+    data += ", 电量: " + std::to_string(percentage) + "%";
+    triggerEvent("low_battery_warning", data);
+}
+
+void EventInputHandler::triggerLockVehicle()
+{
+    triggerEvent("lock_vehicle", "锁车操作");
+}
+
+void EventInputHandler::triggerUnlockVehicle()
+{
+    triggerEvent("unlock_vehicle", "解锁操作");
+}
+
+void EventInputHandler::triggerJoystickPullBack()
+{
+    triggerEvent("joystick_pull_back", "摇杆后拉");
+}
+
+void EventInputHandler::triggerJoystickStop()
+{
+    triggerEvent("joystick_stop", "摇杆停止");
+}
+
+void EventInputHandler::triggerPushStart()
+{
+    triggerEvent("push_start", "推行启动");
+}
+
+void EventInputHandler::triggerPushStop()
+{
+    triggerEvent("push_stop", "推行停止");
+}
+
+void EventInputHandler::triggerBatteryStartCharging()
+{
+    triggerEvent("battery_start_charging", "开始充电");
+}
+
+void EventInputHandler::triggerBatteryStopCharging()
+{
+    triggerEvent("battery_stop_charging", "停止充电");
+}
+
+void EventInputHandler::triggerBatteryFull()
+{
+    triggerEvent("battery_full", "电池充满");
+}
+
+void EventInputHandler::triggerErrorCode(int error_code)
+{
+    std::string data = "错误码: " + std::to_string(error_code);
+    triggerEvent("error_code_handling", data);
+}
+
+void EventInputHandler::triggerBaseStationLost()
+{
+    triggerEvent("base_station_lost", "基站检测丢失");
+}
+
+void EventInputHandler::triggerSearchTimeout()
+{
+    triggerEvent("search_30s_timeout", "搜索30秒超时");
+}
+
+void EventInputHandler::logEvent(const std::string& event_name, const std::string& details)
+{
+    if (details.empty())
+    {
+        RCLCPP_INFO(node_->get_logger(), "触发事件: %s", event_name.c_str());
+    }
+    else
+    {
+        RCLCPP_INFO(node_->get_logger(), "触发事件: %s - %s", 
+                   event_name.c_str(), details.c_str());
+    }
+}
+
+std::string EventInputHandler::getCurrentState() const
+{
+    if (workflow_manager_)
+        return workflow_manager_->getCurrentState();
+    return "未初始化";
+}
+
+bool EventInputHandler::isRechargeActive() const
+{
+    return interface_active_;
+}
+
+void EventInputHandler::displaySystemStatus()
+{
+    if (!workflow_manager_ || !battery_manager_ || !lidar_controller_ || !report_manager_)
+    {
+        RCLCPP_ERROR(node_->get_logger(), "系统未初始化");
+        return;
+    }
+    
+    std::string control_mode = interface_active_ ? "iPad控制" : "本地控制";
+    
+    report_manager_->reportSystemStatus(
+        workflow_manager_->getCurrentWheelchairState(),
+        battery_manager_->getBatteryState(),
+        battery_manager_->getBatteryPercentage(),
+        lidar_controller_->getChargingState(),
+        lidar_controller_->getChargingVoltage(),
+        isRechargeActive(),
+        control_mode
+    );
+}

+ 0 - 0
src/wheelchair_state_machine/src/ipad_manager.cpp → src3/wheelchair_state_machine/src/ipad_manager.cpp


+ 0 - 0
src/wheelchair_state_machine/src/lidascan_ctrl.cpp → src3/wheelchair_state_machine/src/lidascan_ctrl.cpp


+ 34 - 0
src3/wheelchair_state_machine/src/main.cpp

@@ -0,0 +1,34 @@
+// main.cpp
+#include "wheelchair_state_machine/event_input.hpp"
+#include <rclcpp/rclcpp.hpp>
+#include <memory>
+
+class WheelchairStateMachineNode : public rclcpp::Node
+{
+public:
+    WheelchairStateMachineNode()
+        : Node("wheelchair_state_machine")
+    {
+        event_handler_ = std::make_unique<EventInputHandler>(this);
+        event_handler_->initializeModules();
+        
+        // 显示系统状态
+        event_handler_->displaySystemStatus();
+        
+        RCLCPP_INFO(this->get_logger(), "智能轮椅状态机已启动");
+    }
+    
+private:
+    std::unique_ptr<EventInputHandler> event_handler_;
+};
+
+int main(int argc, char **argv)
+{
+    rclcpp::init(argc, argv);
+    
+    auto node = std::make_shared<WheelchairStateMachineNode>();
+    
+    rclcpp::spin(node);
+    rclcpp::shutdown();
+    return 0;
+}

+ 0 - 0
src/wheelchair_state_machine/src/recharge_tool.cpp → src3/wheelchair_state_machine/src/recharge_tool.cpp


+ 0 - 0
src/wheelchair_state_machine/src/report.cpp → src3/wheelchair_state_machine/src/report.cpp


+ 0 - 0
src/wheelchair_state_machine/src/workflow.cpp → src3/wheelchair_state_machine/src/workflow.cpp