0228_2
This commit is contained in:
parent
11a7ee57aa
commit
86d2d7d514
@ -24,6 +24,7 @@ struct RadioData
|
|||||||
int16_t throttle; // 油门数据
|
int16_t throttle; // 油门数据
|
||||||
uint8_t gear; // 挡位数据
|
uint8_t gear; // 挡位数据
|
||||||
uint8_t sweep; // 清扫开关数据
|
uint8_t sweep; // 清扫开关数据
|
||||||
|
uint8_t enabled; // 使能
|
||||||
bool data_valid; // 数据有效性标志
|
bool data_valid; // 数据有效性标志
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -34,7 +35,7 @@ extern std::mutex radio_data_mutex; // 保护radio_data的互斥锁
|
|||||||
// 函数声明
|
// 函数声明
|
||||||
int can_Init(void);
|
int can_Init(void);
|
||||||
void can_Recv_CAN1(void);
|
void can_Recv_CAN1(void);
|
||||||
RadioData get_radio_data(void); //
|
RadioData get_radio_data(void); //
|
||||||
void can_Stop_Recv(void); //
|
void can_Stop_Recv(void); //
|
||||||
|
|
||||||
#endif // !_CANDEV_H
|
#endif // !_CANDEV_H
|
||||||
@ -68,11 +68,11 @@ class CanRadioCtrlNode : public rclcpp::Node
|
|||||||
|
|
||||||
// 检查数据有效性
|
// 检查数据有效性
|
||||||
bool has_received = radio_data.data_valid;
|
bool has_received = radio_data.data_valid;
|
||||||
bool data_safe = radio_data.data_valid;
|
bool enabled = (radio_data.enabled == 0);
|
||||||
|
|
||||||
auto msg = sweeperMsg::McCtrl();
|
auto msg = sweeperMsg::McCtrl();
|
||||||
|
|
||||||
if (has_received && data_safe)
|
if (has_received && enabled)
|
||||||
{
|
{
|
||||||
// 解析挡位
|
// 解析挡位
|
||||||
switch (radio_data.gear) // 通道E
|
switch (radio_data.gear) // 通道E
|
||||||
@ -172,7 +172,7 @@ class CanRadioCtrlNode : public rclcpp::Node
|
|||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
LOG_WARN("CAN radio control data lost or failsafe!");
|
LOG_WARN("CAN radio control unabled!");
|
||||||
}
|
}
|
||||||
print_counter = 0;
|
print_counter = 0;
|
||||||
}
|
}
|
||||||
|
|||||||
@ -8,7 +8,7 @@
|
|||||||
#include <thread> // 异步接收线程
|
#include <thread> // 异步接收线程
|
||||||
|
|
||||||
// 全局变量定义
|
// 全局变量定义
|
||||||
RadioData radio_data = {0, 0, 0, 0, false};
|
RadioData radio_data = {0, 0, 0, 0, true, false};
|
||||||
std::mutex radio_data_mutex; // 保护radio_data的互斥锁
|
std::mutex radio_data_mutex; // 保护radio_data的互斥锁
|
||||||
|
|
||||||
// CAN 文件描述符
|
// CAN 文件描述符
|
||||||
@ -125,6 +125,7 @@ void can_recv_loop()
|
|||||||
uint8_t ch7 = frame.data[6];
|
uint8_t ch7 = frame.data[6];
|
||||||
uint8_t ch8 = frame.data[7];
|
uint8_t ch8 = frame.data[7];
|
||||||
radio_data.gear = ch1;
|
radio_data.gear = ch1;
|
||||||
|
radio_data.enabled = ch3;
|
||||||
radio_data.sweep = ch4;
|
radio_data.sweep = ch4;
|
||||||
// printf("ch1 : %d ,ch2 : %d ,ch3 : %d ,ch4 : %d\n", ch1, ch2, ch3, 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);
|
// printf("ch5 : %d ,ch6 : %d ,ch7 : %d ,ch8 : %d\n", ch5, ch6, ch7, ch8);
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user