Compare commits
12 Commits
d54455dee9
...
ed435b4cc8
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
ed435b4cc8 | ||
|
|
d43b1aca73 | ||
|
|
f798c1e230 | ||
|
|
4308315fa2 | ||
|
|
b53898c6b5 | ||
|
|
5932e44c3e | ||
|
|
2800c2660b | ||
|
|
d192e3e40f | ||
|
|
9b9964439c | ||
|
|
b479ee103a | ||
|
|
4d633454e9 | ||
|
|
cdff6c812a |
@@ -769,7 +769,7 @@ static void _ble_spp_server_init(void)
|
||||
{
|
||||
|
||||
s_init_param.manufacturer_data(s_manufacturer_data);
|
||||
printf("set manufacturer data %d %d\n",s_manufacturer_data[0],s_manufacturer_data[1]);
|
||||
// SYS_LOG_DBG("set manufacturer data %d %d\n",s_manufacturer_data[0],s_manufacturer_data[1]);
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
@@ -60,6 +60,7 @@ typedef struct
|
||||
|
||||
typedef enum
|
||||
{
|
||||
RC_OFF_NONE,
|
||||
WIFI_NETIF_MODE_AP,
|
||||
WIFI_NETIF_MODE_STA,
|
||||
} wifi_netif_mode_t;
|
||||
|
||||
@@ -19,6 +19,7 @@ uint16_t toggle_cycle = 1000;
|
||||
bool toggle_flag[EXAMPLE_LED_NUMBERS] = {true,true};
|
||||
bool toggle_flag_lat[EXAMPLE_LED_NUMBERS] = {true,true};
|
||||
|
||||
rgb_color_t rgb_color_none = {0,0,0,0,0,1,0,RGB_COLOR_NONE};
|
||||
rgb_color_t rgb_color_rad = {0,255,0,0,0,1,0,RGB_COLOR_RAD};
|
||||
rgb_color_t rgb_color_orange = {0,255,80,0,0,1,0,RGB_COLOR_ORANGE};
|
||||
rgb_color_t rgb_color_green = {0,0,255,0,0,1,0,RGB_COLOR_GREEN};
|
||||
@@ -104,6 +105,9 @@ void rgb_color_change(uint8_t index, uint8_t color)
|
||||
{
|
||||
switch(color)
|
||||
{
|
||||
case RGB_COLOR_NONE:
|
||||
memcpy(&expression[index], &rgb_color_none, sizeof(rgb_color_none));
|
||||
break;
|
||||
case RGB_COLOR_RAD:
|
||||
memcpy(&expression[index], &rgb_color_rad, sizeof(rgb_color_rad));
|
||||
break;
|
||||
|
||||
@@ -91,6 +91,7 @@ static void ble_server_connect_handler(ble_server_status_t status)
|
||||
if(res == DEVICE_PC_ERROR){
|
||||
}
|
||||
device_wifi_stop();
|
||||
device_inside->ble_one_connect_flag = 1;
|
||||
SYS_LOG_INF("ble Connected");
|
||||
} else if(status == BLE_SERVER_STATUS_DISCONNECTED){
|
||||
uint8_t res = pc_device_choice_inside(NULL, DATA_PORT_TYPE_BLE_VAL, DISCONNECT);
|
||||
@@ -157,14 +158,14 @@ static void wifi_event_handler(bool is_connect, sb_data_port_t *port)
|
||||
{
|
||||
SYS_LOG_ERR("wifi pc device choice error");
|
||||
}
|
||||
SYS_LOG_INF("wifi connect");
|
||||
SYS_LOG_INF("wifi tcp connect");
|
||||
}else{
|
||||
uint8_t res = pc_device_choice_inside(NULL, DATA_PORT_TYPE_WIFI_UDP, DISCONNECT);
|
||||
uint8_t res = pc_device_choice_inside(NULL, DATA_PORT_TYPE_WIFI_UDP, CONNECT_WIFI_UDP);
|
||||
if(res == DEVICE_PC_ERROR)
|
||||
{
|
||||
SYS_LOG_ERR("wifi pc device choice error");
|
||||
}
|
||||
SYS_LOG_INF("wifi disconnect");
|
||||
SYS_LOG_INF("wifi tcp disconnect");
|
||||
}
|
||||
}
|
||||
static void wifi_ap_connect_handler(wifi_ap_connect_status_t status, uint8_t connect_cnt)
|
||||
@@ -281,27 +282,38 @@ uint8_t wifi_init(init_device_t *port)
|
||||
void wifi_mode_switch(init_device_t *port)
|
||||
{
|
||||
static init_device_t* port_lat = NULL;
|
||||
static bool wifi_mode_flag = false;
|
||||
static uint8_t wifi_mode_flag = 0;
|
||||
|
||||
if(port_lat == NULL && port != NULL)
|
||||
{
|
||||
port_lat = port;
|
||||
port_lat->wifi_mode = WIFI_NETIF_MODE_AP;
|
||||
return;
|
||||
}
|
||||
|
||||
if (wifi_mode_flag)
|
||||
switch(wifi_mode_flag)
|
||||
{
|
||||
wifi_mode_flag = false;
|
||||
wifi_set_mode(WIFI_NETIF_MODE_AP);
|
||||
port_lat->wifi_mode = WIFI_NETIF_MODE_AP;
|
||||
SYS_LOG_INF("wifi mode switch to ap");
|
||||
}
|
||||
else
|
||||
{
|
||||
wifi_mode_flag = true;
|
||||
case 0:
|
||||
wifi_mode_flag = 1;
|
||||
wifi_set_mode(WIFI_NETIF_MODE_STA);
|
||||
port_lat->wifi_mode = WIFI_NETIF_MODE_STA;
|
||||
SYS_LOG_INF("wifi mode switch to sta");
|
||||
break;
|
||||
case 1:
|
||||
wifi_mode_flag = 2;
|
||||
SYS_LOG_INF("wifi mode switch to off");
|
||||
port_lat->wifi_mode = RC_OFF_NONE;
|
||||
rf_stop(device_inside);
|
||||
break;
|
||||
case 2:
|
||||
rf_start(device_inside);
|
||||
wifi_mode_flag = 0;
|
||||
wifi_set_mode(WIFI_NETIF_MODE_AP);
|
||||
port_lat->wifi_mode = WIFI_NETIF_MODE_AP;
|
||||
SYS_LOG_INF("wifi mode switch to ap");
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
wifi_start();
|
||||
}
|
||||
|
||||
@@ -96,6 +96,8 @@ typedef struct
|
||||
// int (*embedded_write)(device_t *port, const void *data, uint32_t size);
|
||||
uint8_t last_color;
|
||||
|
||||
// 每次刚连接ble都会将标志位置一 ,因为连接上app后,app会发送一段字符串,这段字符串我暂时用不到需要抛弃,不然会影响异常飞控固件升级
|
||||
uint8_t ble_one_connect_flag;
|
||||
}device_t;
|
||||
|
||||
/**
|
||||
|
||||
@@ -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,};
|
||||
@@ -36,7 +36,7 @@ static void my_button_handler(button_event_t evt) {
|
||||
// SYS_LOG_INF("[Event] DOUBLE_CLICK");
|
||||
// sertrf_rf_switch(1);
|
||||
// aes_test();
|
||||
key_test();
|
||||
// key_test();
|
||||
break;
|
||||
case EVT_LONG_PRESS: //长按
|
||||
SYS_LOG_INF("[Event] LONG_PRESS");
|
||||
@@ -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);
|
||||
|
||||
@@ -209,3 +209,21 @@ void key_test(void)
|
||||
|
||||
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);
|
||||
}
|
||||
@@ -61,3 +61,9 @@ void boot_set(uint8_t value);
|
||||
void boot_set_high_z(void);
|
||||
|
||||
void key_test(void);
|
||||
|
||||
void boot_set_2(uint8_t value);
|
||||
|
||||
void boot_set_high_z_2(void);
|
||||
|
||||
bool key_get_status(void);
|
||||
|
||||
@@ -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)
|
||||
{
|
||||
|
||||
@@ -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);
|
||||
|
||||
@@ -31,7 +31,7 @@ int Protocol_write(const void *data, uint32_t size, uint32_t wait_ms)
|
||||
return -1;
|
||||
}
|
||||
|
||||
void Protocol_init(port_type_m port_type, void* port)
|
||||
void Protocol_init(port_type_e port_type, void* port)
|
||||
{
|
||||
protocol.port.data_port = port;
|
||||
protocol.port_type = port_type;
|
||||
@@ -137,16 +137,16 @@ void Protocol_buf_decode(void* data, uint32_t size)
|
||||
break;
|
||||
}
|
||||
}
|
||||
void protocol_set_message_status(message_status_m status)
|
||||
void protocol_set_message_status(message_status_e status)
|
||||
{
|
||||
protocol.message_status = status;
|
||||
}
|
||||
protocol_status_t get_protocol_status(void)
|
||||
protocol_status_e get_protocol_status(void)
|
||||
{
|
||||
protocol.protocol_status = PROTOCOL_STATUS_OK;
|
||||
|
||||
// 先OTA升级、未知协议、未收到飞控数据
|
||||
if(protocol.message_status == MESSAGE_OTA)
|
||||
if(protocol.message_status == MESSAGE_OTA || protocol.message_status == MESSAGE_FC_ISP)
|
||||
{
|
||||
protocol.protocol_status = PROTOCOL_STATUS_IN_OTA;
|
||||
}
|
||||
@@ -172,7 +172,7 @@ int fc_reboot(void)
|
||||
break;
|
||||
case PROTOCOL_MSP:
|
||||
{
|
||||
|
||||
msp_send_reboot(&protocol.msp);
|
||||
}
|
||||
break;
|
||||
case PROTOCOL_MAVLINK:
|
||||
|
||||
@@ -22,12 +22,13 @@ typedef enum
|
||||
{
|
||||
PORT_LINUX_UART = 0,
|
||||
PORT_LINUX_SBDATA,
|
||||
}port_type_m;
|
||||
}port_type_e;
|
||||
typedef enum
|
||||
{
|
||||
MESSAGE_IDLE = 0,
|
||||
MESSAGE_OTA,
|
||||
}message_status_m;
|
||||
MESSAGE_FC_ISP,
|
||||
}message_status_e;
|
||||
typedef enum
|
||||
{
|
||||
PROTOCOL_STATUS_OK = 0,
|
||||
@@ -35,20 +36,20 @@ typedef enum
|
||||
PROTOCOL_STATUS_TYPE_IDLE, //协议类型未知
|
||||
PROTOCOL_STATUS_ANALYSIS_ERROR, //长时间解析失败
|
||||
PROTOCOL_STATUS_IN_OTA, //OTA中
|
||||
}protocol_status_t;
|
||||
}protocol_status_e;
|
||||
typedef struct
|
||||
{
|
||||
protocol_port_t port;
|
||||
protocol_type_m pro_type;
|
||||
port_type_m port_type;
|
||||
port_type_e port_type;
|
||||
|
||||
mavlink_device_t mavlink_device;
|
||||
msp_port_t msp;
|
||||
|
||||
protocol_status_t protocol_status;
|
||||
protocol_status_e protocol_status;
|
||||
uint16_t analysis_sussess_count; //数据解析成功次数
|
||||
|
||||
message_status_m message_status;
|
||||
message_status_e message_status;
|
||||
|
||||
mavlink_message_t message;
|
||||
}protocol_t;
|
||||
@@ -59,7 +60,7 @@ typedef struct
|
||||
* @param port_type 使用的设备类型(如串口或其他)
|
||||
* @param port 由对应的驱动提供的绑定接口获得的句柄
|
||||
*/
|
||||
void Protocol_init(port_type_m port_type, void* port);
|
||||
void Protocol_init(port_type_e port_type, void* port);
|
||||
/**
|
||||
* @brief 搜索协议
|
||||
*
|
||||
@@ -90,13 +91,13 @@ void Protocol_buf_decode(void* data, uint32_t size);
|
||||
*
|
||||
* @param status 消息状态
|
||||
*/
|
||||
void protocol_set_message_status(message_status_m status);
|
||||
void protocol_set_message_status(message_status_e status);
|
||||
/**
|
||||
* @brief 获取协议状态
|
||||
*
|
||||
* @retval 协议状态
|
||||
*/
|
||||
protocol_status_t get_protocol_status(void);
|
||||
protocol_status_e get_protocol_status(void);
|
||||
|
||||
/**
|
||||
* @brief 飞控重启命令
|
||||
|
||||
@@ -34,7 +34,7 @@ typedef enum
|
||||
|
||||
RESEND_CMD_DATA_ACK = 0x06,
|
||||
|
||||
RESEND_CMD_MODE_STATUS = 0x07,
|
||||
RESEND_CMD_ERROR_CODE = 0x07,
|
||||
|
||||
RESEND_CMD_OTA_GET_PARAM = 0x010,
|
||||
RESEND_CMD_OTA_START = 0x011,
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
#include "sertrf.h"
|
||||
|
||||
//设置日志打印类型
|
||||
#define CONFIG_SYS_LOG_LEVEL SYS_LOG_LEVEL_INF
|
||||
#define CONFIG_SYS_LOG_LEVEL SYS_LOG_LEVEL_DBG
|
||||
#define SYS_LOG_DOMAIN "Seryrf"
|
||||
|
||||
sertrf_t sertrf;
|
||||
@@ -42,6 +42,9 @@ void sertrf_init(void)
|
||||
//初始化环形buff
|
||||
rb_init(&sertrf.data_handle_buffer, DATA_HANDLE_BUFFER_SIZE, sizeof(uint8_t));
|
||||
|
||||
// 判断飞控是否进入 飞控固件强刷模式
|
||||
sertrf.force_update = key_get_status();
|
||||
|
||||
//线程启动
|
||||
sertrf_start();
|
||||
|
||||
@@ -53,13 +56,13 @@ void sertrf_start(void)
|
||||
"embedded_thread",
|
||||
embedded_thread,
|
||||
NULL,
|
||||
2048,
|
||||
4096,
|
||||
20);
|
||||
os_thread_create(&sertrf.pc_thread,
|
||||
"pc_thread",
|
||||
pc_thread,
|
||||
NULL,
|
||||
2048,
|
||||
4096,
|
||||
20);
|
||||
os_thread_create(&sertrf.app_thread,
|
||||
"app_thread",
|
||||
@@ -102,7 +105,7 @@ void embedded_thread(void* arg)
|
||||
{
|
||||
uint8_t data[embedded_size ];
|
||||
// data[embedded_size] = '\0';
|
||||
if(!sertrf.stmisp_device.flag)
|
||||
if(!sertrf.stmisp_device.flag && !sertrf.force_update)
|
||||
embedded_device_read(&sertrf.device, data, embedded_size,0);
|
||||
|
||||
Protocol_buf_decode(data, embedded_size);
|
||||
@@ -118,6 +121,7 @@ void embedded_thread(void* arg)
|
||||
}
|
||||
void pc_thread(void* arg)
|
||||
{
|
||||
static bool app_pc_discard = true;
|
||||
while(true)
|
||||
{
|
||||
uint32_t pc_size = pc_device_get_rx_length(&sertrf.device);
|
||||
@@ -127,7 +131,13 @@ void pc_thread(void* arg)
|
||||
uint8_t data[pc_size];
|
||||
pc_device_read(&sertrf.device, data, pc_size);
|
||||
// SYS_LOG_INF("data : %s", data);
|
||||
if(!sertrf.stmisp_device.flag)
|
||||
// 由于APP连接上后,会发送一串我用不到的数据,需要丢弃掉,不然会影响我异常飞控固件升级
|
||||
if(sertrf.device.ble_one_connect_flag == 1)
|
||||
{
|
||||
sertrf.device.ble_one_connect_flag = 0;
|
||||
continue;
|
||||
}
|
||||
if(!sertrf.stmisp_device.flag && !sertrf.force_update)
|
||||
embedded_device_write(&sertrf.device, data, pc_size);
|
||||
}
|
||||
// printf_chill_time(10,1000);
|
||||
@@ -157,13 +167,13 @@ void app_thread(void* arg)
|
||||
sertrf.resend_device.handle_flag = 0;//标志位清零
|
||||
break;
|
||||
case RESEND_CMD_OTA_GET_PARAM:
|
||||
printf("RESEND_CMD_OTA_GET_PARAM\r\n");
|
||||
SYS_LOG_DBG("RESEND_CMD_OTA_GET_PARAM\r\n");
|
||||
ota_parm_t ota_parm;
|
||||
resend_send_data(&sertrf.resend_device, RESEND_CMD_OTA_GET_PARAM, &ota_parm, sizeof(ota_parm_t), 1000);
|
||||
sertrf.resend_device.handle_flag = 0;//标志位清零
|
||||
break;
|
||||
case RESEND_CMD_FC_ISP_GET_PARAM:
|
||||
printf("RESEND_CMD_FC_ISP_GET_PARAM\r\n");
|
||||
SYS_LOG_DBG("RESEND_CMD_FC_ISP_GET_PARAM\r\n");
|
||||
stmisp_parm_t stmisp_parm;
|
||||
resend_send_data(&sertrf.resend_device, RESEND_CMD_FC_ISP_GET_PARAM, &stmisp_parm, sizeof(stmisp_parm), 1000);
|
||||
sertrf.resend_device.handle_flag = 0;//标志位清零
|
||||
@@ -172,22 +182,6 @@ void app_thread(void* arg)
|
||||
break;
|
||||
}
|
||||
resend_recv_data(&sertrf.resend_device, 0);
|
||||
// static uint8_t count = 0;
|
||||
// count++;
|
||||
// if(count > 100)
|
||||
// {
|
||||
// // resend_send_cmd(&sertrf.resend_device, RESEND_CMD_ACK, 0);
|
||||
// resend_send_data(&sertrf.resend_device, RESEND_CMD_GET_PARAM, NULL, 0, 0);
|
||||
// // count = 0;
|
||||
// }
|
||||
// uint32_t app_size = app_device_get_rx_length(&sertrf.device);
|
||||
|
||||
// if(app_size > 0)
|
||||
// {
|
||||
// uint8_t data[app_size];
|
||||
// app_device_read(&sertrf.device, data, app_size,0);
|
||||
// printf("data:%d:%s\n", app_size,data);
|
||||
// }
|
||||
os_thread_sleep(1);
|
||||
}
|
||||
|
||||
@@ -204,7 +198,8 @@ void task_thread(void* arg)
|
||||
static size_t end_time = 0;
|
||||
if(start_time - end_time > 2000)
|
||||
{
|
||||
switch(get_protocol_status())
|
||||
sertrf.fc_protocol_status = get_protocol_status();
|
||||
switch(sertrf.fc_protocol_status)
|
||||
{
|
||||
case PROTOCOL_STATUS_OK:
|
||||
// rgb_color_change(1, sertrf.device.last_color);
|
||||
@@ -346,37 +341,40 @@ void pc_link_rgb_color(device_t* device)
|
||||
case DISCONNECT:
|
||||
{
|
||||
if(device->init_device.wifi_mode == WIFI_NETIF_MODE_AP)
|
||||
new_color = RGB_COLOR_GREEN_WHITE;
|
||||
else
|
||||
new_color = RGB_COLOR_GREEN_PURPLE;
|
||||
new_color = NO_CONNECT_COLOR_BLE_AP;
|
||||
else if(device->init_device.wifi_mode == WIFI_NETIF_MODE_STA)
|
||||
new_color = NO_CONNECT_COLOR_BLE_STA;
|
||||
else if(device->init_device.wifi_mode == RC_OFF_NONE)
|
||||
new_color = RF_OFF_COLOR;
|
||||
break;
|
||||
}
|
||||
case CONNECT_WIFI_TCP:
|
||||
{
|
||||
if(device->init_device.wifi_mode == WIFI_NETIF_MODE_AP)
|
||||
new_color = RGB_COLOR_WHITE;
|
||||
else
|
||||
new_color = RGB_COLOR_PURPLE;
|
||||
|
||||
new_color = WIFI_AP_COLOR;
|
||||
else if(device->init_device.wifi_mode == WIFI_NETIF_MODE_STA)
|
||||
new_color = WIFI_STA_COLOR;
|
||||
else if(device->init_device.wifi_mode == RC_OFF_NONE)
|
||||
new_color = RF_OFF_COLOR;
|
||||
break;
|
||||
}
|
||||
case CONNECT_WIFI_UDP:
|
||||
{
|
||||
if(device->init_device.wifi_mode == WIFI_NETIF_MODE_AP)
|
||||
new_color = RGB_COLOR_WHITE;
|
||||
new_color = WIFI_AP_COLOR;
|
||||
else
|
||||
new_color = RGB_COLOR_PURPLE;
|
||||
new_color = WIFI_STA_COLOR;
|
||||
|
||||
break;
|
||||
}
|
||||
case CONNECT_BLE:
|
||||
{
|
||||
new_color = RGB_COLOR_GREEN;
|
||||
new_color = BLE_COLOR;
|
||||
}
|
||||
break;
|
||||
case CONNECT_RF_OFF:
|
||||
{
|
||||
new_color = RGB_COLOR_BLUE;
|
||||
new_color = RF_OFF_COLOR;
|
||||
}
|
||||
break;
|
||||
}
|
||||
@@ -429,7 +427,7 @@ void resend_user_parse(void *resend_device)
|
||||
// 减6的目的是因为华哥没对MAC进行处理,所以也不返回
|
||||
if(sizeof(sertrf_stauct_t) - 6 != resend_parse->rx_frame.len)
|
||||
{
|
||||
printf("RESEND_CMD_SET_PARAM len error\r\n");
|
||||
SYS_LOG_DBG("RESEND_CMD_SET_PARAM len error\r\n");
|
||||
}
|
||||
sertrf_stauct_t* sertrf_stauct = (sertrf_stauct_t*)resend_parse->rx_frame.payload;
|
||||
|
||||
@@ -446,10 +444,10 @@ void resend_user_parse(void *resend_device)
|
||||
{
|
||||
if(sizeof(ota_parm_t) != resend_parse->rx_frame.len)
|
||||
{
|
||||
printf("RESEND_CMD_OTA_GET_PARAM len error\r\n");
|
||||
SYS_LOG_DBG("RESEND_CMD_OTA_GET_PARAM len error\r\n");
|
||||
}
|
||||
ota_parm_t* ota_parm = (ota_parm_t*)resend_parse->rx_frame.payload;
|
||||
printf("RESEND_CMD_OTA_GET_PARAM %d\n", ota_parm->ota_file_size);
|
||||
SYS_LOG_DBG("RESEND_CMD_OTA_GET_PARAM %d\n", ota_parm->ota_file_size);
|
||||
resend_send_cmd(resend_device, RESEND_CMD_ACK, 0);
|
||||
}
|
||||
break;
|
||||
@@ -488,6 +486,7 @@ void resend_user_parse(void *resend_device)
|
||||
while (sertrf.mode_status.task_state != DATA_HANDLE_IDLE){
|
||||
os_thread_sleep(10);}
|
||||
otau_end(&sertrf.otau);
|
||||
protocol_set_message_status(MESSAGE_IDLE);
|
||||
resend_send_cmd(resend_device, RESEND_CMD_ACK, 0);
|
||||
os_thread_sleep(2);
|
||||
esp_restart();
|
||||
@@ -497,10 +496,10 @@ void resend_user_parse(void *resend_device)
|
||||
case RESEND_CMD_FC_ISP_GET_PARAM:
|
||||
if(sizeof(stmisp_parm_t) != resend_parse->rx_frame.len)
|
||||
{
|
||||
printf("RESEND_CMD_FC_ISP_GET_PARAM len error\r\n");
|
||||
SYS_LOG_DBG("RESEND_CMD_FC_ISP_GET_PARAM len error\r\n");
|
||||
}
|
||||
stmisp_parm_t* stmisp_parm = (stmisp_parm_t*)resend_parse->rx_frame.payload;
|
||||
printf("RESEND_CMD_FC_ISP_GET_PARAM %d\n", stmisp_parm->stmisp_file_size);
|
||||
SYS_LOG_DBG("RESEND_CMD_FC_ISP_GET_PARAM %d\n", stmisp_parm->stmisp_file_size);
|
||||
resend_send_cmd(resend_device, RESEND_CMD_ACK, 0);
|
||||
break;
|
||||
case RESEND_CMD_FC_ISP_START:
|
||||
@@ -508,51 +507,59 @@ void resend_user_parse(void *resend_device)
|
||||
使用sync与isp确定通讯波特率,并建立联系 解除其写保护 并重新sync建立连接后擦除全部区域内存*/
|
||||
//关闭其他线程中相同串口的使用
|
||||
sertrf.stmisp_device.flag = 1;
|
||||
// 重启飞控,并使其进入isp烧录模式
|
||||
// 修改灯珠颜色
|
||||
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);
|
||||
boot_set_2(0);
|
||||
os_thread_sleep(1000);
|
||||
//串口切换为偶校验模式,并清除缓存
|
||||
uart_set_parity_switch(sertrf.device.embedded_device, 0x02);
|
||||
os_thread_sleep(100);
|
||||
// 与isp确定通讯波特率,并建立联系
|
||||
if(!send_sync(&sertrf.stmisp_device, 5))
|
||||
printf("stmisp: sync error\n");
|
||||
{
|
||||
SYS_LOG_DBG("stmisp: sync error\n");
|
||||
// app_send_error_code(SERTRF_ERROR_FC_ISP_SYNC);
|
||||
break;
|
||||
}
|
||||
else
|
||||
printf("stmisp: sync ok\n");
|
||||
SYS_LOG_DBG("stmisp: sync ok\n");
|
||||
|
||||
os_thread_sleep(100);
|
||||
|
||||
// 解除写保护
|
||||
if(!cmd_write_unprotect(&sertrf.stmisp_device))
|
||||
printf("stmisp: write unprotect error\n");
|
||||
SYS_LOG_DBG("stmisp: write unprotect error\n");
|
||||
else
|
||||
printf("stmisp: write unprotect ok\n");
|
||||
SYS_LOG_DBG("stmisp: write unprotect ok\n");
|
||||
|
||||
os_thread_sleep(100);
|
||||
|
||||
|
||||
if(!send_sync(&sertrf.stmisp_device, 5))
|
||||
printf("stmisp: sync error\n");
|
||||
SYS_LOG_DBG("stmisp: sync error\n");
|
||||
else
|
||||
printf("stmisp: sync ok\n");
|
||||
SYS_LOG_DBG("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");
|
||||
SYS_LOG_DBG("stmisp: erase mass error\n");
|
||||
else
|
||||
printf("stmisp: erase mass ok\n");
|
||||
SYS_LOG_DBG("stmisp: erase mass ok\n");
|
||||
|
||||
os_thread_sleep(10);
|
||||
|
||||
printf("stmisp: isp start\n");
|
||||
SYS_LOG_DBG("stmisp: isp start\n");
|
||||
|
||||
sertrf.mode_status.task_state = DATA_HANDLE_ISP_DATA;
|
||||
resend_send_cmd(resend_device, RESEND_CMD_ACK, 0);
|
||||
break;
|
||||
case RESEND_CMD_FC_ISP_DATA:
|
||||
protocol_set_message_status(MESSAGE_FC_ISP);
|
||||
// 使用环形buff
|
||||
if(rb_size(&sertrf.data_handle_buffer) + sertrf.resend_device.rx_frame.len <= DATA_HANDLE_BUFFER_SIZE)
|
||||
{
|
||||
@@ -574,18 +581,20 @@ void resend_user_parse(void *resend_device)
|
||||
// ISP下跳转到应用层运行地址
|
||||
if(cmd_go(&sertrf.stmisp_device, sertrf.fc_address))
|
||||
{
|
||||
printf("stmisp: go ok\n");
|
||||
SYS_LOG_DBG("stmisp: go ok\n");
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("stmisp: go error\n");
|
||||
SYS_LOG_DBG("stmisp: go error\n");
|
||||
}
|
||||
//开启其他线程中相同串口的使用
|
||||
sertrf.stmisp_device.flag = 0;
|
||||
// 将串口切换为无校验模式
|
||||
uart_set_parity_switch(sertrf.device.embedded_device, 0x00);
|
||||
SYS_LOG_INF("RESEND_CMD_FC_ISP_END2");
|
||||
protocol_set_message_status(MESSAGE_IDLE);
|
||||
resend_send_cmd(resend_device, RESEND_CMD_ACK, 0);
|
||||
esp_restart();
|
||||
break;
|
||||
|
||||
default:
|
||||
@@ -606,35 +615,35 @@ void Examples_run(void)
|
||||
os_thread_sleep(500);
|
||||
// 与isp确定通讯波特率,并建立联系
|
||||
if(!send_sync(&sertrf.stmisp_device, 5))
|
||||
printf("stmisp: sync error\n");
|
||||
SYS_LOG_DBG("stmisp: sync error\n");
|
||||
else
|
||||
printf("stmisp: sync ok\n");
|
||||
SYS_LOG_DBG("stmisp: sync ok\n");
|
||||
|
||||
os_thread_sleep(100);
|
||||
|
||||
// 解除写保护
|
||||
if(!cmd_write_unprotect(&sertrf.stmisp_device))
|
||||
printf("stmisp: write unprotect error\n");
|
||||
SYS_LOG_DBG("stmisp: write unprotect error\n");
|
||||
else
|
||||
printf("stmisp: write unprotect ok\n");
|
||||
SYS_LOG_DBG("stmisp: write unprotect ok\n");
|
||||
|
||||
os_thread_sleep(100);
|
||||
if(!send_sync(&sertrf.stmisp_device, 5))
|
||||
printf("stmisp: sync error\n");
|
||||
SYS_LOG_DBG("stmisp: sync error\n");
|
||||
else
|
||||
printf("stmisp: sync ok\n");
|
||||
SYS_LOG_DBG("stmisp: sync ok\n");
|
||||
os_thread_sleep(100);
|
||||
|
||||
boot_set_high_z();
|
||||
// 全盘擦除
|
||||
if(!cmd_extended_erase_mass(&sertrf.stmisp_device))
|
||||
printf("stmisp: erase mass error\n");
|
||||
SYS_LOG_DBG("stmisp: erase mass error\n");
|
||||
else
|
||||
printf("stmisp: erase mass ok\n");
|
||||
SYS_LOG_DBG("stmisp: erase mass ok\n");
|
||||
|
||||
os_thread_sleep(10);
|
||||
|
||||
printf("stmisp: isp start\n");
|
||||
SYS_LOG_DBG("stmisp: isp start\n");
|
||||
|
||||
}
|
||||
int stmisp_send(void* data, uint16_t len, int timeout)
|
||||
@@ -658,3 +667,10 @@ int stmisp_get_length(void)
|
||||
{
|
||||
return embedded_device_get_rx_length(&sertrf.device);
|
||||
}
|
||||
|
||||
int app_send_error_code(uint8_t error_code)
|
||||
{
|
||||
sertrf.mode_status.sertrf_error_code = error_code;
|
||||
|
||||
return resend_send_data(&sertrf.resend_device, RESEND_CMD_ERROR_CODE, &sertrf.mode_status.sertrf_error_code, sizeof(sertrf_mode_status_t), 1000);
|
||||
}
|
||||
@@ -13,6 +13,13 @@
|
||||
|
||||
#define FC_ADDRESS "0x08000000"
|
||||
#define DATA_HANDLE_BUFFER_SIZE 4096
|
||||
|
||||
#define RF_OFF_COLOR RGB_COLOR_NONE //关闭射频灯的颜色指示
|
||||
#define WIFI_AP_COLOR RGB_COLOR_WHITE //连接WIFI AP模式指示
|
||||
#define WIFI_STA_COLOR RGB_COLOR_PURPLE //连接WIFI STA模式指示
|
||||
#define BLE_COLOR RGB_COLOR_GREEN //连接BLE模式指示
|
||||
#define NO_CONNECT_COLOR_BLE_AP RGB_COLOR_GREEN_WHITE //未连接模式指示BLE+AP
|
||||
#define NO_CONNECT_COLOR_BLE_STA RGB_COLOR_GREEN_PURPLE //未连接模式指示BLE+STA
|
||||
typedef enum
|
||||
{
|
||||
DATA_HANDLE_IDLE = 0,
|
||||
@@ -21,10 +28,22 @@ typedef enum
|
||||
DATA_HANDLE_ISP_DATA,
|
||||
DATA_HANDLE_ISP_DATA_END
|
||||
}data_handle_e;
|
||||
typedef struct
|
||||
typedef enum
|
||||
{
|
||||
SERTRF_ERROR_NONE = 0,
|
||||
SERTRF_ERROR_OTA_INIT = 10, // ota初始化失败
|
||||
SERTRF_ERROR_OTA_DATA, // ota数据传输异常
|
||||
SERTRF_ERROR_OTA_END, // ota 结束异常
|
||||
|
||||
SERTRF_ERROR_FC_ISP_UART_TYPE = 30, // 飞控ISP 无法识别其协议
|
||||
SERTRF_ERROR_FC_ISP_UART_DATA, // 飞控ISP 无法收到其数据
|
||||
SERTRF_ERROR_FC_ISP_SYNC, // 飞控ISP 无法与ISP建立连接,需判断BOOT键是否有效
|
||||
}sertrf_error_code_e;
|
||||
typedef struct __attribute__((packed))
|
||||
{
|
||||
data_handle_e task_state;
|
||||
|
||||
uint16_t sertrf_error_code;
|
||||
}sertrf_mode_status_t;
|
||||
typedef struct
|
||||
{
|
||||
@@ -55,6 +74,11 @@ typedef struct
|
||||
uint8_t efuse_mac[6];
|
||||
uint8_t efuse_mac_encrypt[6];
|
||||
|
||||
// 记录错误信息
|
||||
protocol_status_e fc_protocol_status; //飞控连接端的协议状态
|
||||
|
||||
// 判断是否使用强刷固件
|
||||
uint8_t force_update;
|
||||
}sertrf_t;
|
||||
|
||||
typedef struct __attribute__((packed))
|
||||
@@ -120,4 +144,6 @@ void data_handle_thread(void* arg);
|
||||
*/
|
||||
void pc_link_rgb_color(device_t* device);
|
||||
|
||||
int app_send_error_code(uint8_t error_code);
|
||||
|
||||
|
||||
|
||||
@@ -44,7 +44,7 @@ uint32_t parse_hex_or_dec(const char *s) {
|
||||
void aes_test(void)
|
||||
{
|
||||
// if(!esp_efuse_mac_get_default_id(efuse_mac))
|
||||
// printf("mac: %02X:%02X:%02X:%02X:%02X:%02X\n", efuse_mac[0], efuse_mac[1], efuse_mac[2], efuse_mac[3], efuse_mac[4], efuse_mac[5]);
|
||||
// SYS_LOG_DBG("mac: %02X:%02X:%02X:%02X:%02X:%02X\n", efuse_mac[0], efuse_mac[1], efuse_mac[2], efuse_mac[3], efuse_mac[4], efuse_mac[5]);
|
||||
|
||||
// const unsigned char key[16] = "1234567890abcdef"; // 128-bit key
|
||||
// unsigned char nonce_counter[16] = {0}; // 初始计数器块 (可用随机数 + 计数)
|
||||
@@ -62,10 +62,10 @@ void aes_test(void)
|
||||
// mbedtls_aes_crypt_ctr(&aes, sizeof(efuse_mac), &nc_off,
|
||||
// nonce_counter, stream_block, efuse_mac, output);
|
||||
|
||||
// printf("Ciphertext (hex): ");
|
||||
// SYS_LOG_DBG("Ciphertext (hex): ");
|
||||
// for (int i = 0; i < sizeof(efuse_mac); i++)
|
||||
// printf("%02X", output[i]);
|
||||
// printf("\n");
|
||||
// SYS_LOG_DBG("%02X", output[i]);
|
||||
// SYS_LOG_DBG("\n");
|
||||
|
||||
// // 解密(同一函数)
|
||||
// unsigned char decrypted[64] = {0};
|
||||
@@ -76,21 +76,21 @@ void aes_test(void)
|
||||
// mbedtls_aes_crypt_ctr(&aes, sizeof(efuse_mac), &nc_off,
|
||||
// nonce_counter, stream_block, output, decrypted);
|
||||
|
||||
// printf("Decrypted: %s\n", decrypted);
|
||||
// SYS_LOG_DBG("Decrypted: %s\n", decrypted);
|
||||
|
||||
// mbedtls_aes_free(&aes);
|
||||
|
||||
|
||||
if(!esp_efuse_mac_get_default_id(efuse_mac))
|
||||
printf("mac: %02X:%02X:%02X:%02X:%02X:%02X\n", efuse_mac[0], efuse_mac[1], efuse_mac[2], efuse_mac[3], efuse_mac[4], efuse_mac[5]);
|
||||
SYS_LOG_DBG("mac: %02X:%02X:%02X:%02X:%02X:%02X\n", efuse_mac[0], efuse_mac[1], efuse_mac[2], efuse_mac[3], efuse_mac[4], efuse_mac[5]);
|
||||
|
||||
uint8_t efuse_mac_encrypt[6] = {0};
|
||||
sertrf_aes_ctr_encrypt(efuse_mac, 6, efuse_mac_encrypt);
|
||||
printf("mac: %02X:%02X:%02X:%02X:%02X:%02X\n", efuse_mac_encrypt[0], efuse_mac_encrypt[1], efuse_mac_encrypt[2], efuse_mac_encrypt[3], efuse_mac_encrypt[4], efuse_mac_encrypt[5]);
|
||||
SYS_LOG_DBG("mac: %02X:%02X:%02X:%02X:%02X:%02X\n", efuse_mac_encrypt[0], efuse_mac_encrypt[1], efuse_mac_encrypt[2], efuse_mac_encrypt[3], efuse_mac_encrypt[4], efuse_mac_encrypt[5]);
|
||||
|
||||
uint8_t efuse_mac_decrypt[6] = {0};
|
||||
sertrf_aes_ctr_decrypt(efuse_mac_encrypt, 6, efuse_mac_decrypt);
|
||||
printf("mac: %02X:%02X:%02X:%02X:%02X:%02X\n", efuse_mac_decrypt[0], efuse_mac_decrypt[1], efuse_mac_decrypt[2], efuse_mac_decrypt[3], efuse_mac_decrypt[4], efuse_mac_decrypt[5]);
|
||||
SYS_LOG_DBG("mac: %02X:%02X:%02X:%02X:%02X:%02X\n", efuse_mac_decrypt[0], efuse_mac_decrypt[1], efuse_mac_decrypt[2], efuse_mac_decrypt[3], efuse_mac_decrypt[4], efuse_mac_decrypt[5]);
|
||||
}
|
||||
|
||||
void sertrf_aes_ctr_encrypt(uint8_t *data, uint32_t len,uint8_t* output)
|
||||
|
||||
@@ -29,3 +29,9 @@ CONFIG_LOG_DEFAULT_LEVEL_NONE=y
|
||||
#定义APP配置
|
||||
CONFIG_BOARD_NAME_SERTRF_ESP32C3=y
|
||||
CONFIG_PRODUCT_ID_SERTRF=y
|
||||
|
||||
|
||||
#关闭bootloard生成输出日志
|
||||
#CONFIG_BOOT_ROM_LOG_ON_GPIO_LOW=y
|
||||
#设置应用层输出日志等级
|
||||
#CONFIG_LOG_DEFAULT_LEVEL_INFO=y
|
||||
Reference in New Issue
Block a user