当解析不出飞控数据时闪红灯

This commit is contained in:
OPTOC
2025-09-04 16:01:12 +08:00
parent 2e5b3416a6
commit bd9ffa3de2
9 changed files with 112 additions and 22 deletions

View File

@@ -466,21 +466,23 @@ void msp_recv_loop(msp_port_t *msp)
}
}
}
void msp_recv_buf(msp_port_t *msp, void *data, uint32_t size)
int msp_recv_buf(msp_port_t *msp, void *data, uint32_t size)
{
uint8_t res = 0;
uint32_t size_lat = size;
uint8_t* data_char = (uint8_t*)data;
while (size_lat --)
{
uint8_t c = data_char[size - size_lat - 1];
uint8_t c = data_char[size - size_lat - 1];
if (msp_parse_received_data(msp, c))
{
if (msp->c_state == MSP_COMMAND_RECEIVED)
{
msp_process_received_command(msp);
// break;
res ++;
}
}
}
return res;
}

View File

@@ -318,8 +318,9 @@ void msp_recv_loop(msp_port_t *msp);
* @param msp 接口
* @param data 接收数据
* @param size 接收数据长度
* @retval 解析成功次数
*/
void msp_recv_buf(msp_port_t *msp,void *data, uint32_t size);
int msp_recv_buf(msp_port_t *msp,void *data, uint32_t size);
/**
* @brief MSP数据包解析
*

View File

@@ -179,10 +179,11 @@ void mavlink_recv_loop(mavlink_device_t* mavlink_device)
}
}
void mavlink_recv_buf(mavlink_device_t* mavlink_device, void *data, uint32_t size)
int mavlink_recv_buf(mavlink_device_t* mavlink_device, void *data, uint32_t size)
{
uint8_t res = 0;
bool success = false;
mavlink_message_t message;
uint32_t size_lat = size;
@@ -196,8 +197,9 @@ void mavlink_recv_buf(mavlink_device_t* mavlink_device, void *data, uint32_t siz
if(success){
// printf("Received message from serial with ID #%d (sys:%d|comp:%d):\n", message.msgid, message.sysid, message.compid);
mavlik_packet_processing(mavlink_device,&message);
// break;
success = false;
res++;
}
}
return res;
}

View File

@@ -101,7 +101,8 @@ void mavlink_recv_loop(mavlink_device_t* mavlink_device);
* @param mavlink_device 接口
* @param data 数据
* @param size 大小
* @retval 解析成功次数
*/
void mavlink_recv_buf(mavlink_device_t* mavlink_device, void *data, uint32_t size);
int mavlink_recv_buf(mavlink_device_t* mavlink_device, void *data, uint32_t size);
#endif

View File

@@ -128,10 +128,27 @@ void Protocol_buf_decode(void* data, uint32_t size)
protocol.pro_type = Protocol_buf_search(data, size);
break;
case PROTOCOL_MSP:
msp_recv_buf(&protocol.msp, data, size);
protocol.analysis_sussess_count += msp_recv_buf(&protocol.msp, data, size);
break;
case PROTOCOL_MAVLINK:
mavlink_recv_buf(&protocol.mavlink_device, data, size);
protocol.analysis_sussess_count += mavlink_recv_buf(&protocol.mavlink_device, data, size);
break;
}
}
protocol_status_t get_protocol_status(void)
{
protocol.protocol_status = PROTOCOL_STATUS_OK;
if(protocol.pro_type == PROTOCOL_IDLE)
{
protocol.protocol_status = PROTOCOL_STATUS_TYPE_IDLE;
} else if(protocol.analysis_sussess_count == 0)
{
protocol.protocol_status = PROTOCOL_STATUS_NO_DATA;
}
protocol.analysis_sussess_count = 0;
return protocol.protocol_status;
}

View File

@@ -23,6 +23,13 @@ typedef enum
PORT_LINUX_UART = 0,
PORT_LINUX_SBDATA,
}port_type_m;
typedef enum
{
PROTOCOL_STATUS_OK = 0,
PROTOCOL_STATUS_NO_DATA, //没有收到数据,或者数据小于一定量
PROTOCOL_STATUS_TYPE_IDLE, //协议类型未知
PROTOCOL_STATUS_ANALYSIS_ERROR, //长时间解析失败
}protocol_status_t;
typedef struct
{
protocol_port_t port;
@@ -32,6 +39,8 @@ typedef struct
mavlink_device_t mavlink_device;
msp_port_t msp;
protocol_status_t protocol_status;
uint16_t analysis_sussess_count; //数据解析成功次数
}protocol_t;
/**
@@ -66,4 +75,10 @@ int Protocol_buf_search(void* data, uint32_t size);
* @param size 数据长度
*/
void Protocol_buf_decode(void* data, uint32_t size);
/**
* @brief 获取协议状态
*
* @retval 协议状态
*/
protocol_status_t get_protocol_status(void);
#endif