sousenw 3 周之前
父節點
當前提交
9229f304e0

+ 6 - 6
src/wheelchair_state_machine/include/wheelchair_state_machine/recharge_status.hpp

@@ -4,18 +4,18 @@
 // 回充状态上报枚举 (对应图片上半部分)
 enum RechargeReportStatus
 {
-    RECHARGE_EVENT_SEARCHING_STATION = 1,   // 搜索充电站
+    RECHARGE_EVENT_OBSTACLE_DETECTED = 1,   // 前往充电站中
     RECHARGE_EVENT_STATION_NOT_FOUND = 2,   // 未找到充电站
-    RECHARGE_EVENT_STATION_FOUND = 3,       // 找到充电站并前往
-    RECHARGE_EVENT_OBSTACLE_DETECTED = 4,   // 检测到障碍物
-    RECHARGE_EVENT_START_CHARGING = 5,      // 开始充电
-    RECHARGE_EVENT_STOP_CHARGING = 6        // 停止充电
+    RECHARGE_FEEDBACK_SUCCESS_DOCKED = 3      // 成功对接
+    // RECHARGE_EVENT_OBSTACLE_DETECTED = 4,   // 检测到障碍物
+    // RECHARGE_EVENT_START_CHARGING = 5,      // 开始充电
+    // RECHARGE_EVENT_STOP_CHARGING = 6        // 停止充电
 };
 
 // 回充结果反馈枚举 (对应图片下半部分)
 enum RechargeFeedbackResult
 {
-    RECHARGE_FEEDBACK_SUCCESS_DOCKED = 100,     // 成功-正常对接
+    // RECHARGE_FEEDBACK_SUCCESS_DOCKED = 100,     // 成功-正常对接
     RECHARGE_FEEDBACK_FAILED_TIMEOUT = 201,     // 停止-找不到基站超时
     RECHARGE_FEEDBACK_FAILED_OBSTACLE = 202,    // 停止-遇到障碍物
     RECHARGE_FEEDBACK_FAILED_USER_CANCEL = 203, // 停止-人工操作取消

+ 2 - 5
src/wheelchair_state_machine/src/lidascan_ctrl.cpp

@@ -67,7 +67,7 @@ void LidarScanController::initialize()
         rclcpp::QoS(10).transient_local()); // 修改为 transient_local
     pub_charging_voltage_ = node_->create_publisher<std_msgs::msg::String>(
         "/charging/voltage_detected", 10);
-    pub1_=node_->create_publisher<std_msgs::msg::Int32>("/vlago/recharge/status1",10);
+    pub1_=node_->create_publisher<std_msgs::msg::Int32>("/vlago/recharge/state",10);
     pub2_=node_->create_publisher<std_msgs::msg::Int32>("/vlago/recharge/feedback",10);
     // 初始化控制消息
     ctrl_twist_.linear.x = 0.0;
@@ -648,7 +648,7 @@ void LidarScanController::controlRechargeMotion(const RechargeResult &result)
         ctrl_twist_time_ = node_->now();
         auto msg =std_msgs::msg::Int32();
         msg.data=RECHARGE_FEEDBACK_SUCCESS_DOCKED;
-        pub2_->publish(msg);
+        pub1_->publish(msg);
         stopNavigation();
 
         // 模拟检测到充电电压
@@ -1300,9 +1300,6 @@ void LidarScanController::setChargingVoltage(bool value)
     {
         ss << ",message=充电电压已检测到,开始充电流程";
         RCLCPP_INFO(node_->get_logger(), "检测到充电电压");
-        auto msg = std_msgs::msg::Int32();
-        msg.data=RECHARGE_EVENT_START_CHARGING;
-        pub1_->publish(msg);
     }
     else
     {

+ 1 - 1
src/wheelchair_state_machine/src/rotation_manager.cpp

@@ -15,7 +15,7 @@ RotationManager::RotationManager(rclcpp::Node *node)
     cmd_vel_publisher_ = node_->create_publisher<geometry_msgs::msg::Twist>(
         "/cmd_vel_raw", 10);
     rotation_timeout_pub1_ = node_->create_publisher<std_msgs::msg::Int32>(
-        "/vlago/recharge/status1", 10);
+        "/vlago/recharge/state", 10);
     rotation_timeout_pub2_=node_->create_publisher<std_msgs::msg::Int32>("/vlago/recharge/feedback",10);
     rotation_timeout_pub_ = node_->create_publisher<std_msgs::msg::String>(
         "/wheelchair/rotation_timeout", 10);

+ 2 - 6
src/wheelchair_state_machine/src/workflow.cpp

@@ -25,7 +25,7 @@ WorkflowManager::WorkflowManager(rclcpp::Node *node)
     // 创建回充超时报告发布者
     recharge_timeout_publisher_ = node_->create_publisher<std_msgs::msg::String>(
         "/wheelchair/recharge_timeout", 10);
-    pub1_ = node_->create_publisher<std_msgs::msg::Int32>("/vlago/recharge/status1", 10);
+    pub1_ = node_->create_publisher<std_msgs::msg::Int32>("/vlago/recharge/state", 10);
 
     RCLCPP_INFO(node_->get_logger(), "工作流管理器已初始化");
 }
@@ -756,7 +756,7 @@ void WorkflowManager::transitionToWalking()
             RCLCPP_INFO(node_->get_logger(), "轮椅开始行走");
             publishState("WHEELCHAIR_WALKING");
             auto msg = std_msgs::msg::Int32();
-            msg.data = RECHARGE_EVENT_STATION_FOUND;
+            msg.data = RECHARGE_EVENT_OBSTACLE_DETECTED;
             pub1_->publish(msg);
         }
     }
@@ -776,10 +776,6 @@ void WorkflowManager::transitionToSearching()
             setState(WheelchairState::SEARCHING);
             search_start_time_ = node_->now();
             RCLCPP_INFO(node_->get_logger(), "开始搜索充电站");
-            auto msg = std_msgs::msg::Int32();
-            msg.data = RECHARGE_EVENT_SEARCHING_STATION;
-
-            pub1_->publish(msg);
             publishState("SEARCH_CHARGING_STATION_START");
             startSearchTimeoutTimer();
             startRotationTimer();