From 853d0155fe5f24b94ca5e28f39cb5f4c88dc0820 Mon Sep 17 00:00:00 2001 From: lyq Date: Tue, 27 Jan 2026 10:22:50 +0800 Subject: [PATCH] =?UTF-8?q?=E5=88=A0=E9=99=A4DetectLine=E7=9B=B8=E5=85=B3?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- src/autonomy/fu/src/fu_node.cpp | 10 ---------- 1 file changed, 10 deletions(-) diff --git a/src/autonomy/fu/src/fu_node.cpp b/src/autonomy/fu/src/fu_node.cpp index 81f3000..ead41fb 100644 --- a/src/autonomy/fu/src/fu_node.cpp +++ b/src/autonomy/fu/src/fu_node.cpp @@ -13,7 +13,6 @@ #include "logger/logger.h" #include "rclcpp/rclcpp.hpp" #include "sweeper_interfaces/msg/can_frame.hpp" -#include "sweeper_interfaces/msg/detect_line.hpp" #include "sweeper_interfaces/msg/fu.hpp" #include "sweeper_interfaces/msg/mc_ctrl.hpp" #include "sweeper_interfaces/msg/pl.hpp" @@ -71,8 +70,6 @@ class fu_node : public rclcpp::Node msg_subscribe_pl = this->create_subscription( "pl_message", 10, std::bind(&fu_node::msg_callback_pl, this, std::placeholders::_1)); - msg_subscribe_DetectLine = this->create_subscription( - "airy_message", 10, std::bind(&fu_node::msg_callback_DetectLine, this, std::placeholders::_1)); // 发布控制指令 pub_mc = this->create_publisher("auto_mc_ctrl", 10); @@ -291,7 +288,6 @@ class fu_node : public rclcpp::Node // 声明订阅者和发布者 rclcpp::Subscription::SharedPtr subscription_grid; rclcpp::Subscription::SharedPtr msg_subscribe_pl; - rclcpp::Subscription::SharedPtr msg_subscribe_DetectLine; rclcpp::Subscription::SharedPtr subscription_; rclcpp::Publisher::SharedPtr pub_mc; @@ -754,12 +750,6 @@ class fu_node : public rclcpp::Node LOG_INFO("目标点位置: x -- %.2f , y -- %.2f", x, y); } - void msg_callback_DetectLine(const sweeper_interfaces::msg::DetectLine::SharedPtr msg) - { - nl_adjust = 0 - msg->adjust + remain_adjust; - detected_line = msg->detected_line; - } - void timer_callback() { if (speed == 0)