From 86d2d7d514d08be89e9b04d301ef45318d8b3789 Mon Sep 17 00:00:00 2001 From: lyq Date: Sat, 28 Feb 2026 17:19:29 +0800 Subject: [PATCH] 0228_2 --- src/control/can_radio_ctrl/include/can_radio_ctrl/candev.h | 5 +++-- src/control/can_radio_ctrl/src/can_radio_ctrl.cpp | 6 +++--- src/control/can_radio_ctrl/src/candev.cpp | 3 ++- 3 files changed, 8 insertions(+), 6 deletions(-) diff --git a/src/control/can_radio_ctrl/include/can_radio_ctrl/candev.h b/src/control/can_radio_ctrl/include/can_radio_ctrl/candev.h index 0660050..be4b588 100644 --- a/src/control/can_radio_ctrl/include/can_radio_ctrl/candev.h +++ b/src/control/can_radio_ctrl/include/can_radio_ctrl/candev.h @@ -24,6 +24,7 @@ struct RadioData int16_t throttle; // 油门数据 uint8_t gear; // 挡位数据 uint8_t sweep; // 清扫开关数据 + uint8_t enabled; // 使能 bool data_valid; // 数据有效性标志 }; @@ -34,7 +35,7 @@ extern std::mutex radio_data_mutex; // 保护radio_data的互斥锁 // 函数声明 int can_Init(void); void can_Recv_CAN1(void); -RadioData get_radio_data(void); // -void can_Stop_Recv(void); // +RadioData get_radio_data(void); // +void can_Stop_Recv(void); // #endif // !_CANDEV_H \ No newline at end of file diff --git a/src/control/can_radio_ctrl/src/can_radio_ctrl.cpp b/src/control/can_radio_ctrl/src/can_radio_ctrl.cpp index 7200645..8a826dc 100644 --- a/src/control/can_radio_ctrl/src/can_radio_ctrl.cpp +++ b/src/control/can_radio_ctrl/src/can_radio_ctrl.cpp @@ -68,11 +68,11 @@ class CanRadioCtrlNode : public rclcpp::Node // 检查数据有效性 bool has_received = radio_data.data_valid; - bool data_safe = radio_data.data_valid; + bool enabled = (radio_data.enabled == 0); auto msg = sweeperMsg::McCtrl(); - if (has_received && data_safe) + if (has_received && enabled) { // 解析挡位 switch (radio_data.gear) // 通道E @@ -172,7 +172,7 @@ class CanRadioCtrlNode : public rclcpp::Node } else { - LOG_WARN("CAN radio control data lost or failsafe!"); + LOG_WARN("CAN radio control unabled!"); } print_counter = 0; } diff --git a/src/control/can_radio_ctrl/src/candev.cpp b/src/control/can_radio_ctrl/src/candev.cpp index ccaf132..f6cceca 100644 --- a/src/control/can_radio_ctrl/src/candev.cpp +++ b/src/control/can_radio_ctrl/src/candev.cpp @@ -8,7 +8,7 @@ #include // 异步接收线程 // 全局变量定义 -RadioData radio_data = {0, 0, 0, 0, false}; +RadioData radio_data = {0, 0, 0, 0, true, false}; std::mutex radio_data_mutex; // 保护radio_data的互斥锁 // CAN 文件描述符 @@ -125,6 +125,7 @@ void can_recv_loop() uint8_t ch7 = frame.data[6]; uint8_t ch8 = frame.data[7]; radio_data.gear = ch1; + radio_data.enabled = ch3; radio_data.sweep = ch4; // printf("ch1 : %d ,ch2 : %d ,ch3 : %d ,ch4 : %d\n", ch1, ch2, ch3, ch4); // printf("ch5 : %d ,ch6 : %d ,ch7 : %d ,ch8 : %d\n", ch5, ch6, ch7, ch8);