From b53898c6b5e73551cceb3b4a122c71a3d6595030 Mon Sep 17 00:00:00 2001 From: OPTOC <9159397+optoc@user.noreply.gitee.com> Date: Tue, 28 Oct 2025 14:55:50 +0800 Subject: [PATCH] =?UTF-8?q?=E6=9B=B4=E6=94=B9=E6=8C=89=E9=94=AE=EF=BC=8C?= =?UTF-8?q?=E5=B7=B2=E7=BB=8F=E6=B7=BB=E5=8A=A0msp=E9=87=8D=E5=90=AF?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- app/drivers/sertrf/key.c | 24 +++++++++++++++++++++--- app/drivers/sertrf/key.h | 8 +++++++- app/drivers/sertrf/protocol/MSP.c | 10 +++++++++- app/drivers/sertrf/protocol/MSP.h | 6 +++++- app/drivers/sertrf/protocol/p_protocol.c | 2 +- app/drivers/sertrf/sertrf.c | 9 +++++---- 6 files changed, 48 insertions(+), 11 deletions(-) diff --git a/app/drivers/sertrf/key.c b/app/drivers/sertrf/key.c index 0914029..9d89c7e 100644 --- a/app/drivers/sertrf/key.c +++ b/app/drivers/sertrf/key.c @@ -3,8 +3,8 @@ button_t btn; cfg_board_pin_io_t key_switch = { - .pin = 9, - .en_lev = 0,}; + .pin = 18, + .en_lev = 1,}; cfg_board_pin_io_t boot_switch = { .pin = 18, .en_lev = 0,}; @@ -174,7 +174,7 @@ void button_work_init() { pin_cfg_input(&key_switch); // pin_cfg_output(&boot_switch); - gpio_to_high_z(&boot_switch); + // gpio_to_high_z(&boot_switch); button_init(&btn, read_button_pin, my_button_handler); @@ -208,4 +208,22 @@ void key_test(void) os_thread_sleep(5000); boot_set_high_z(); +} + +void boot_set_2(uint8_t value) +{ + pin_cfg_output(&boot_switch); + pin_set_valid(&boot_switch, value); + os_work_suspend(&work_handler_button); +} + +void boot_set_high_z_2(void) +{ + pin_cfg_input(&key_switch); + os_work_resume(&work_handler_button,10); +} + +bool key_get_status(void) +{ + return pin_get_valid(&key_switch); } \ No newline at end of file diff --git a/app/drivers/sertrf/key.h b/app/drivers/sertrf/key.h index 3a54391..710a23f 100644 --- a/app/drivers/sertrf/key.h +++ b/app/drivers/sertrf/key.h @@ -60,4 +60,10 @@ void boot_set(uint8_t value); */ void boot_set_high_z(void); -void key_test(void); \ No newline at end of file +void key_test(void); + +void boot_set_2(uint8_t value); + +void boot_set_high_z_2(void); + +bool key_get_status(void); diff --git a/app/drivers/sertrf/protocol/MSP.c b/app/drivers/sertrf/protocol/MSP.c index dd803dd..d5fca22 100644 --- a/app/drivers/sertrf/protocol/MSP.c +++ b/app/drivers/sertrf/protocol/MSP.c @@ -448,7 +448,15 @@ void fc_put_ack(void) // printf("ACK\n"); } - +// MSP重启命令 +void msp_send_reboot(msp_port_t *msp) +{ + msp_send2(msp, MSP_REBOOT, NULL, 0); +} +void msp_request_type(msp_port_t *msp) +{ + msp_send2(msp, MSP_FC_VARIANT, NULL, 0); +} // MSP数据读取,并根据读取的数据进行处理 void msp_recv_loop(msp_port_t *msp) { diff --git a/app/drivers/sertrf/protocol/MSP.h b/app/drivers/sertrf/protocol/MSP.h index 81b0090..2fef451 100644 --- a/app/drivers/sertrf/protocol/MSP.h +++ b/app/drivers/sertrf/protocol/MSP.h @@ -17,6 +17,7 @@ #define MSP_SONAR_ALTITUDE 58 #define MSP_ARMING_CONFIG 61 #define MSP_RX_MAP 64 // get channel map (also returns number of channels total) +#define MSP_REBOOT 68 // 重启命令 #define MSP_LOOP_TIME 73 // FC cycle time i.e looptime parameter #define MSP_STATUS 101 #define MSP_RAW_IMU 102 @@ -366,7 +367,10 @@ void msp_handle_get_gcs(msp_gcs_t pkt); // 回复请求包处理 void fc_put_ack(void); - +// 发送MSP重启命令 +void msp_send_reboot(msp_port_t *msp); +// 请求飞控类型 +void msp_request_type(msp_port_t *msp); // 接口层 int MSP_wirite(const void *data, uint32_t size, uint32_t wait_ms); int MSP_read(void *data, uint32_t size, uint32_t wait_ms); diff --git a/app/drivers/sertrf/protocol/p_protocol.c b/app/drivers/sertrf/protocol/p_protocol.c index 8957a6a..8a9996f 100644 --- a/app/drivers/sertrf/protocol/p_protocol.c +++ b/app/drivers/sertrf/protocol/p_protocol.c @@ -172,7 +172,7 @@ int fc_reboot(void) break; case PROTOCOL_MSP: { - + msp_send_reboot(&protocol.msp); } break; case PROTOCOL_MAVLINK: diff --git a/app/drivers/sertrf/sertrf.c b/app/drivers/sertrf/sertrf.c index d0702f3..523c304 100644 --- a/app/drivers/sertrf/sertrf.c +++ b/app/drivers/sertrf/sertrf.c @@ -522,9 +522,9 @@ void resend_user_parse(void *resend_device) // 修改灯珠颜色 protocol_set_message_status(MESSAGE_FC_ISP); // 重启飞控,并使其进入isp烧录模式 需要在能够识别飞控的情况下才需要重启 - if(sertrf.fc_protocol_status != PROTOCOL_STATUS_TYPE_IDLE && sertrf.fc_protocol_status != PROTOCOL_STATUS_NO_DATA) - fc_reboot(); - boot_set(0); + // if(sertrf.fc_protocol_status != PROTOCOL_STATUS_TYPE_IDLE && sertrf.fc_protocol_status != PROTOCOL_STATUS_NO_DATA) + fc_reboot(); + boot_set_2(0); os_thread_sleep(1000); //串口切换为偶校验模式,并清除缓存 uart_set_parity_switch(sertrf.device.embedded_device, 0x02); @@ -556,7 +556,7 @@ void resend_user_parse(void *resend_device) printf("stmisp: sync ok\n"); os_thread_sleep(100); - boot_set_high_z(); + boot_set_high_z_2(); // 全盘擦除 if(!cmd_extended_erase_mass(&sertrf.stmisp_device)) printf("stmisp: erase mass error\n"); @@ -604,6 +604,7 @@ void resend_user_parse(void *resend_device) uart_set_parity_switch(sertrf.device.embedded_device, 0x00); SYS_LOG_INF("RESEND_CMD_FC_ISP_END2"); resend_send_cmd(resend_device, RESEND_CMD_ACK, 0); + esp_restart(); break; default: