添加BOOT键、飞控复位控制、串口校验位设置

This commit is contained in:
OPTOC
2025-10-14 10:17:40 +08:00
parent 0336a20472
commit e7989c7444
6 changed files with 87 additions and 2 deletions

View File

@@ -34,6 +34,7 @@ int Protocol_write(const void *data, uint32_t size, uint32_t wait_ms)
void Protocol_init(port_type_m port_type, void* port)
{
protocol.port.data_port = port;
protocol.port_type = port_type;
switch (port_type)
{
case PORT_LINUX_UART:
@@ -105,6 +106,7 @@ int Protocol_buf_search(void* data, uint32_t size)
mavlink_message_t message;
if(mavlink_message(&protocol.mavlink_device, &message,c)){
mavlik_packet_processing(&protocol.mavlink_device, &message);
memcpy(&protocol.message,&message,sizeof(mavlink_message_t));
return PROTOCOL_MAVLINK;
}
// MSP 解析
@@ -157,4 +159,46 @@ protocol_status_t get_protocol_status(void)
protocol.analysis_sussess_count = 0;
return protocol.protocol_status;
}
int fc_reboot(void)
{
switch(protocol.pro_type)
{
case PROTOCOL_IDLE:
printf("The protocol cannot be restarted as it has not been recognized\n");
break;
case PROTOCOL_MSP:
{
}
break;
case PROTOCOL_MAVLINK:
{
mavlink_message_t msg;
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
mavlink_msg_command_long_pack(
255, 0, &msg,
/* target_system */ protocol.message.sysid,
/* target_component */ protocol.message.compid,
/* command */ MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,
/* confirmation */ 0,
/* param1 */ 1, // 1 = reboot
/* param2 */ 1,
/* param3 */ 0,
/* param4 */ 0,
/* param5 */ 0,
/* param6 */ 0,
/* param7 */ 0
);
// 打包成字节流发送
uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);
int size = Protocol_write(buf, len, 0);
printf("reboot sys:%d com:%d size:%d\n", protocol.message.sysid, protocol.message.compid,size);
}
break;
}
return 1;
}