VID 透传改成200ms持续发布
This commit is contained in:
parent
a5bd401f9c
commit
15b9046d8b
@ -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;
|
||||
}
|
||||
|
||||
@ -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");
|
||||
}
|
||||
|
||||
@ -90,9 +90,8 @@ void bmsTimerTask(CANDriver& canctl)
|
||||
// 注册 VID 发送定时器任务
|
||||
void setupVidTimer(rclcpp::Node::SharedPtr node, std::function<void()> 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");
|
||||
}
|
||||
|
||||
Loading…
Reference in New Issue
Block a user