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