From 15b9046d8b309e11c7bff73af3a32184609f5e1c Mon Sep 17 00:00:00 2001 From: lyq Date: Thu, 19 Mar 2026 15:20:13 +0800 Subject: [PATCH] =?UTF-8?q?VID=20=E9=80=8F=E4=BC=A0=E6=94=B9=E6=88=90200ms?= =?UTF-8?q?=E6=8C=81=E7=BB=AD=E5=8F=91=E5=B8=83?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- src/base/mc/include/mc/vid_transmit.hpp | 8 ++++---- src/base/mc/src/mc.cpp | 10 ++-------- src/base/mc/src/timer_tasks.cpp | 5 ++--- 3 files changed, 8 insertions(+), 15 deletions(-) diff --git a/src/base/mc/include/mc/vid_transmit.hpp b/src/base/mc/include/mc/vid_transmit.hpp index c539ff8..b742909 100644 --- a/src/base/mc/include/mc/vid_transmit.hpp +++ b/src/base/mc/include/mc/vid_transmit.hpp @@ -100,13 +100,13 @@ inline bool send_vid_to_can(CANDriver& can_driver, const std::string& vid) if (!can_driver.sendFrame(frame)) { - LOG_ERROR("Failed to send VID frame to CAN bus"); + LOG_ERROR_THROTTLE(5000, "Failed to send VID frame to CAN bus"); return false; } - LOG_INFO("VID sent to CAN bus: %s (CAN ID: 0x%03X, Data: %02X %02X %02X %02X %02X %02X %02X %02X)", vid.c_str(), - frame.id, frame.data[0], frame.data[1], frame.data[2], frame.data[3], frame.data[4], frame.data[5], - frame.data[6], frame.data[7]); + LOG_INFO_THROTTLE(5000, "VID sent to CAN bus: %s (CAN ID: 0x%03X, Data: %02X %02X %02X %02X %02X %02X %02X %02X)", + vid.c_str(), frame.id, frame.data[0], frame.data[1], frame.data[2], frame.data[3], frame.data[4], + frame.data[5], frame.data[6], frame.data[7]); return true; } diff --git a/src/base/mc/src/mc.cpp b/src/base/mc/src/mc.cpp index bf99110..45dcd47 100644 --- a/src/base/mc/src/mc.cpp +++ b/src/base/mc/src/mc.cpp @@ -16,7 +16,6 @@ namespace sweeperMsg = sweeper_interfaces::msg; CANDriver canctl; std::string current_vid; -bool vid_sent = false; void vehicleIdentityCallback(const sweeperMsg::VehicleIdentity::SharedPtr msg) { @@ -24,19 +23,14 @@ void vehicleIdentityCallback(const sweeperMsg::VehicleIdentity::SharedPtr msg) { LOG_INFO("Received new VID: %s", msg->vid.c_str()); current_vid = msg->vid; - vid_sent = false; // 新 VID 需要重新发送 } } void send_vid_task() { - if (!vid_sent && !current_vid.empty()) + if (!current_vid.empty()) { - if (vid_transmit::send_vid_to_can(canctl, current_vid)) - { - vid_sent = true; // 成功发送后标记 - } - else + if (!vid_transmit::send_vid_to_can(canctl, current_vid)) { LOG_WARN("Failed to send VID, will retry"); } diff --git a/src/base/mc/src/timer_tasks.cpp b/src/base/mc/src/timer_tasks.cpp index 320221c..8357a4c 100644 --- a/src/base/mc/src/timer_tasks.cpp +++ b/src/base/mc/src/timer_tasks.cpp @@ -90,9 +90,8 @@ void bmsTimerTask(CANDriver& canctl) // 注册 VID 发送定时器任务 void setupVidTimer(rclcpp::Node::SharedPtr node, std::function callback) { - // 每秒检查一次 VID 是否需要发送 - static auto timer_vid = - node->create_wall_timer(std::chrono::milliseconds(1000), callback); + // 200ms 持续发布 VID + static auto timer_vid = node->create_wall_timer(std::chrono::milliseconds(200), callback); LOG_INFO("[TIMER] VID transmit timer setup completed"); }