添加BOOT键、飞控复位控制、串口校验位设置
This commit is contained in:
@@ -494,3 +494,18 @@ void sb_uart_port_unbind(sb_data_port_t *port)
|
||||
port->data = NULL;
|
||||
}
|
||||
}
|
||||
|
||||
void uart_set_parity_switch(sb_data_port_t *port, uint8_t parity)
|
||||
{
|
||||
__uart_data_t *uart_data = port->data;
|
||||
|
||||
uart_wait_tx_done(uart_data->uart_num, pdMS_TO_TICKS(100)); // 等待已发完
|
||||
uart_flush_input(uart_data->uart_num); // 清空接收FIFO,避免半帧造成校验错
|
||||
|
||||
//清除缓存数据
|
||||
os_pipe_clr(&uart_data->rx_pipe);
|
||||
int size = _uart_port_get_rx_length(port);
|
||||
printf("size: %d\n", size);
|
||||
|
||||
uart_set_parity(uart_data->uart_num, parity); // 切换为偶校验
|
||||
}
|
||||
@@ -26,3 +26,6 @@ sb_data_port_t *sb_uart_port_bind(int uartNum,
|
||||
os_work_t *rx_resume_work);
|
||||
|
||||
void sb_uart_port_unbind(sb_data_port_t *port);
|
||||
|
||||
//切换校验方式
|
||||
void uart_set_parity_switch(sb_data_port_t *port, uint8_t parity);
|
||||
|
||||
@@ -5,6 +5,9 @@ button_t btn;
|
||||
cfg_board_pin_io_t key_switch = {
|
||||
.pin = 9,
|
||||
.en_lev = 0,};
|
||||
cfg_board_pin_io_t boot_switch = {
|
||||
.pin = ~0,
|
||||
.en_lev = 0,};
|
||||
// 新增事件类型
|
||||
// EVT_DOUBLE_CLICK: 双击
|
||||
// EVT_SINGLE_LONG_PRESS: 单击后长按
|
||||
@@ -34,6 +37,7 @@ static void my_button_handler(button_event_t evt) {
|
||||
break;
|
||||
case EVT_LONG_PRESS: //长按
|
||||
SYS_LOG_INF("[Event] LONG_PRESS");
|
||||
Examples_run();
|
||||
rgb_Indicator_light_off(0);
|
||||
break;
|
||||
case EVT_SINGLE_LONG_PRESS: //单击后长按
|
||||
@@ -163,9 +167,18 @@ void _work_button(void *arg) {
|
||||
}
|
||||
|
||||
void button_work_init() {
|
||||
|
||||
pin_cfg_input(&key_switch);
|
||||
pin_cfg_output(&boot_switch);
|
||||
|
||||
button_init(&btn, read_button_pin, my_button_handler);
|
||||
|
||||
static os_work_t work_handler_button;
|
||||
os_work_create(&work_handler_button, "work-button", _work_button, NULL, OS_PRIORITY_NORMAL);
|
||||
os_work_submit(default_os_work_q_hdl, &work_handler_button, 10);
|
||||
}
|
||||
|
||||
void boot_set(uint8_t value)
|
||||
{
|
||||
pin_set_valid(&boot_switch, value);
|
||||
}
|
||||
|
||||
@@ -11,6 +11,8 @@
|
||||
#include "os/os.h"
|
||||
#include "device.h"
|
||||
#include "../led_strip/led_strip.h"
|
||||
#include "protocol/stmisp.h"
|
||||
|
||||
// 按键事件类型
|
||||
typedef enum {
|
||||
EVT_NONE = 0, // 无事件
|
||||
@@ -46,3 +48,4 @@ typedef struct {
|
||||
extern bool key_single_click,key_press_down,key_press_up;
|
||||
void _work_button(void *arg);
|
||||
void button_work_init();
|
||||
void boot_set(uint8_t value);
|
||||
@@ -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 解析
|
||||
@@ -158,3 +160,45 @@ protocol_status_t get_protocol_status(void)
|
||||
|
||||
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;
|
||||
}
|
||||
@@ -49,6 +49,8 @@ typedef struct
|
||||
uint16_t analysis_sussess_count; //数据解析成功次数
|
||||
|
||||
message_status_m message_status;
|
||||
|
||||
mavlink_message_t message;
|
||||
}protocol_t;
|
||||
|
||||
/**
|
||||
@@ -96,4 +98,9 @@ void protocol_set_message_status(message_status_m status);
|
||||
*/
|
||||
protocol_status_t get_protocol_status(void);
|
||||
|
||||
/**
|
||||
* @brief 飞控重启命令
|
||||
*
|
||||
*/
|
||||
int fc_reboot(void);
|
||||
#endif
|
||||
Reference in New Issue
Block a user