chen
6 天以前 33a728fdc172f59a313cee92da153b37c14c450e
keil/include/main/main.c
@@ -40,252 +40,244 @@
#include "mk_trace.h"
#include "mk_wdt.h"
#include "mk_calib.h"
#include "mk_reset.h"
#include "mk_gpio.h"
#include "mk_misc.h"
#include "mk_sleep_timer.h"
#include "mk_power.h"
#include "mk_uwb.h"
#include "mk_calib.h"
#include "mk_uart.h"
#include "mk_spi.h"
#include "mk_flash.h"
#include "libc_rom.h"
#include "Usart.h"
#include <serial_at_cmd_app.h>
#include <global_param.h>
#include "board.h"
#include "pal_sys.h"
#include "wsf_os.h"
#include "wsf_timer.h"
#include "wsf_buf.h"
#include "wsf_nvm.h"
#include "mk_power.h"
#include "mk_sleep_timer.h"
#include "Usart.h"
#include "mk_adc.h"
extern int TagRange(void);
extern void parameter_init(void);
uint8_t trx_buf[10] = {0};
#define TEST_UART_POLL_MODE 0
#define TEST_UART_INTERUPT_MODE 1
#define TEST_UART_DMA_MODE 2
#define TEST_UART_MODE TEST_UART_DMA_MODE
#define NUM_SAMPLES 1
#define SLEEP_START_TIME 60
#define FREQ_LOST_TIME 5
#define NOTAG_FREQ  1
#define BATTERY_GET_TIME 3600
uint8_t enable_sleep_count,sleep_flag;
uint32_t battery_get_count;
//#define DEBUG_MODE
#include "app.h"
#include "ranging_fira.h"
#include "uwb_api.h"
#include "lib_ranging.h"
#include "uci_tl_task.h"
#include "libc_rom.h"
struct UART_CFG_T test_uart_cfg =
{
        .parity = UART_PARITY_NONE,
        .stop = UART_STOP_BITS_1,
        .data = UART_DATA_BITS_8,
        .flow = UART_FLOW_CONTROL_NONE,
        .rx_level = UART_RXFIFO_CHAR_1,
        .tx_level = UART_TXFIFO_EMPTY,
        .baud = BAUD_115200,
#if (TEST_UART_MODE == TEST_UART_POLL_MODE)
        .dma_en = false,
        .int_rx = false,
        .int_tx = false,
#elif (TEST_UART_MODE == TEST_UART_INTERUPT_MODE)
        .dma_en = false,
        .int_rx = true,
        .int_tx = true,
#elif (TEST_UART_MODE == TEST_UART_DMA_MODE)
        .dma_en = true,
        .int_rx = false,
        .int_tx = false,
#ifdef UWB_UCI_TEST_EN
#include "uwb_test.h"
#endif
      };
static void app_wdt_callback(void *dev, uint32_t status)
{
    ASSERT(status, "WDT TIMEOUT,程序复位");
      //LOG_INFO(TRACE_MODULE_APP, "程序卡死,看门狗复位");
}
static uint32_t sample[NUM_SAMPLES] = {0};
static struct ADC_CFG_T usr_adc_cfg = {
    .mode = ADC_MODE_CONTINUE,    /* Selected single conversion mode  */
    .clk_sel = ADC_CLK_HIGH,      /* Selected 62.4M high speed clock */
    .vref_sel = ADC_SEL_VREF_INT, /* Using internal reference voltage (1.2V)*/
    .rate = 500000,               /* ADC works at high frequency system clock, the maximum sampling rate is 2M */
    .channel_p = ADC_IN_EXTPIN0,  /* ADC positive channel --> GPIO0 */
    .channel_n = ADC_IN_VREF,     /* ADC negative channel --> Vref */
    .int_en = false,
    .dma_en = false, /* DMA support only in continue mode */
    .acc_num = 0,
    .high_pulse_time = 4,
    .settle_time = 1,
};
 struct WDT_CFG_T app_wdt_cfg = {
        .timeout = 32768 * 30,
        .rst_en = true,
        .int_en = true,
        .callback = app_wdt_callback,
    };
uint8_t state5v = 1;
uint8_t bat_percent=0,g_start_send_flag=1;
int16_t fVoltage_mv;
uint8_t bat_percent;
extern uint32_t dev_id;
extern uint8_t group_id;
extern float freqlost_count;
uint8_t tag_frequency;
void UartDeinit(void);
void UartInit(void);
void Program_Init(void);
void IdleTask(void);
void boot_deinit(void);
void Get_batterty_Voltage(void);
void Calculate_battery_percent(void);
static void uart_receive_callback(void *dev, uint32_t err_code)
{
uart_receive(UART_ID0,m_EUART_DMA_RXBuf,EUART_RX_BUF_SIZE,uart_receive_callback);
}
void UartInit(void)
#ifdef CELL_PHONE_EN
#include "mk_efuse.h"
#define EFUSE_FLASH_EN_ADDR (0x67)
#define EFUSE_FLASH_EN_BIT (0x80)
bool check_flash_bit_of_efuse(void);
bool program_efuse(void);
bool check_flash_bit_of_efuse(void)
{
board_pins_config();
uart_open(UART_ID1, &test_uart_cfg);
board_debug_console_open(TRACE_PORT_UART0);
uart_receive(UART_ID1,m_EUART_DMA_RXBuf,EUART_RX_BUF_SIZE,uart_receive_callback);
    uint8_t val;
    val = efuse_read_byte(EFUSE_FLASH_EN_ADDR);
    return ((val & EFUSE_FLASH_EN_BIT) ? true : false);
}
void UartDeinit(void)
bool program_efuse(void)
{
uart_close(UART_ID0);
uart_close(UART_ID1);
    efuse_program_byte(EFUSE_FLASH_EN_ADDR, EFUSE_FLASH_EN_BIT);
    if (check_flash_bit_of_efuse())
    {
        LOG_INFO(TRACE_MODULE_APP, "Program eFuse INT_FLASH bit successfully.\r\n");
        return true;
    }
    else
    {
        LOG_INFO(TRACE_MODULE_APP, "Program eFuse INT_FLASH bit failed.\r\n");
        return false;
    }
    return true;
}
void Get_batterty_Voltage(void)
{
    battery_monitor_open();
    fVoltage_mv=battery_monitor_get();
   battery_monitor_close();
   Calculate_battery_percent();
}
void Calculate_battery_percent(void)
{
            if(fVoltage_mv < 3000)
        {
            bat_percent = 0;
        }
        else if(fVoltage_mv > 3500)
        {
            bat_percent = 100;
        }
        else
        {
            bat_percent = ((fVoltage_mv - 3000) /8);
        }
            //LOG_INFO(TRACE_MODULE_APP, "The voltage is %d ,percent is %%%d \r\n",fVoltage_mv,bat_percent);
}
#endif
//*****************************************************************************
//
// WSF buffer pools.
//
//*****************************************************************************
#define WSF_BUF_POOLS 5
void Fira_Change_Task(void);
extern uint8_t normal_flag,log_4g_enable_flag,lora_tx_flag;
extern uint16_t ip0,ip1,ip2,ip3,port;
uint8_t group_id,enable_sleep_count;
uint32_t dev_id;
uint16_t disoffset;
uint8_t flag_sleeptimer,flag_secondtask,secondtask_count;
float nomove_count;
// Default pool descriptor.
static wsfBufPoolDesc_t poolDescriptors[WSF_BUF_POOLS] = {
    {32, 26}, {64, 24}, {128, 4}, {256 + 32, 4}, {1024 + 32, 2},
};
static void sleep_timer_callback(void *dev, uint32_t time)
{
    //sleep_timer_start(__MS_TO_32K_CNT(1000));
   static uint8_t lost_jumpcount=0;
      enable_sleep_count++;
   if(enable_sleep_count==SLEEP_START_TIME){
      enable_sleep_count=0;
      sleep_flag=1;
   }
   if(battery_get_count++>=BATTERY_GET_TIME)
   {
   Get_batterty_Voltage();
   battery_get_count=0;
   }
//   if(freqlost_count++>FREQ_LOST_TIME)
//   {
//            tag_frequency = NOTAG_FREQ;
//        if(lost_jumpcount++>=4) //无测距情况下,每5秒发一次;
//        {
//            lost_jumpcount = 0;
//            g_start_send_flag=1;
//        }
//   }else{
//      g_start_send_flag=1;
//   }
   g_start_send_flag=1;
    // LOG_INFO(TRACE_MODULE_APP, "Wake up by sleep timer %d\r\n", time);
}
static void adc_callback(void *data, uint32_t number)
static void sleep_timer_callback_normal(void *dev, uint32_t time)
{
    uint32_t *result = (uint32_t *)data;
    for (uint16_t i = 0; i < number; i++)
   if(secondtask_count++%2==0)
    {
//        LOG_INFO(TRACE_MODULE_APP, "The voltage measured %d mv\r\n",
//        ADC_INTERNAL_VREF_MV + adc_code_to_mv((int16_t)*result, ADC_INTERNAL_VREF_MV));
        fVoltage_mv=ADC_INTERNAL_VREF_MV + adc_code_to_mv((int16_t)*result, ADC_INTERNAL_VREF_MV);
        fVoltage_mv=fVoltage_mv*2;
        if(fVoltage_mv < 3300)
        {
            bat_percent = 0;
        }
        else if(fVoltage_mv > 4100)
        {
            bat_percent = 100;
        }
        else
        {
            bat_percent = ((fVoltage_mv - 3300) /8);
        }
        flag_secondtask = 1;
    }else{
        flag_secondtask = 0;
    }
       //LOG_INFO(TRACE_MODULE_APP, "The voltage is %%%d \r\n",bat_percent);
}
static void voltage_input_handler(enum IO_PIN_T pin)
{
//LOG_INFO(TRACE_MODULE_APP, "中断唤醒\r\n");
// if(delaysleep_count>0)
//     delaysleep_count--;
}
void Program_Init(void)
{
Usart1ParseDataCallback = UsartParseDataHandler;
parameter_init();//g_com_map表初始化
group_id=g_com_map[GROUP_ID];
memcpy(&dev_id ,&g_com_map[DEV_ID],2);
tag_frequency=1000/g_com_map[COM_INTERVAL];
g_com_map[VERSION] = (1<<8)|10;
LOG_INFO(TRACE_MODULE_APP,"设备ID: %x .\r\n",dev_id);
LOG_INFO(TRACE_MODULE_APP,"固件版本:UWB-标签 V%d.%d. \r\n",g_com_map[VERSION]>>8,g_com_map[VERSION]&0xff);
{
    Usart1ParseDataCallback = UsartParseDataHandler;//需改为默认为gps处理,UsartParseDataHandler为升级处理当调试时候改为
    parameter_init_anchor();//g_com_map表初始化角色默认为基站
    dev_id=g_com_map[DEV_ID];//这里不太对
    group_id=(uint8_t)g_com_map[GROUP_ID];//组ID
//    tag_frequency = 1000/g_com_map[COM_INTERVAL];//测距频率这个存的是测距时间
    memcpy(&disoffset,&g_com_map[DIST_OFFSET],2);
//    g_com_map[ALARM_DISTANCE1] = 40;
//    g_com_map[ALARM_DISTANCE2] = 40;
//    warning_distance=g_com_map[ALARM_DISTANCE1];
//    prewarning_distance=g_com_map[ALARM_DISTANCE2];
      //g_com_map[SEND_4G_SECOND]
//    if(g_com_map[SEND_4G_SECOND]<30)
//      {
//      gps_open_flag=0;
//      }else{
//      gps_open_flag=1;
//      }
    g_com_map[MODBUS_MODE] = 0;
      log_4g_enable_flag=g_com_map[LOG_4G_ENABLE];
    ip0 = (g_com_map[TCP_IP_0]>>12&0xf)*1000+(g_com_map[TCP_IP_0]>>8&0xf)*100+(g_com_map[TCP_IP_0]>>4&0xf)*10+(g_com_map[TCP_IP_0]&0xf);
    ip1 = (g_com_map[TCP_IP_1]>>12&0xf)*1000+(g_com_map[TCP_IP_1]>>8&0xf)*100+(g_com_map[TCP_IP_1]>>4&0xf)*10+(g_com_map[TCP_IP_1]&0xf);
    ip2 = (g_com_map[TCP_IP_2]>>12&0xf)*1000+(g_com_map[TCP_IP_2]>>8&0xf)*100+(g_com_map[TCP_IP_2]>>4&0xf)*10+(g_com_map[TCP_IP_2]&0xf);
    ip3 = (g_com_map[TCP_IP_3]>>12&0xf)*1000+(g_com_map[TCP_IP_3]>>8&0xf)*100+(g_com_map[TCP_IP_3]>>4&0xf)*10+(g_com_map[TCP_IP_3]&0xf);
    port = g_com_map[TCP_PORT];
    g_com_map[VERSION] = (1<<8)|0;
    LOG_INFO(TRACE_MODULE_APP,"设备ID: %x .\r\n",dev_id);
//      if(gpio_pin_get_val(MODE_CHANGE_PIN))
//    LOG_INFO(TRACE_MODULE_APP,"固件版本:MK_Air_tag模式 V%d.%d. \r\n",g_com_map[VERSION]>>8,g_com_map[VERSION]&0xff);
//      else{
//      LOG_INFO(TRACE_MODULE_APP,"固件版本:MK_免布线模式 V%d.%d. \r\n",g_com_map[VERSION]>>8,g_com_map[VERSION]&0xff);
//      }
    LOG_INFO(TRACE_MODULE_APP,"服务器地址: %d.%d.%d.%d:%d.\r\n",ip0,ip1,ip2,ip3,port);
}
void IdleTask(void)
{ UART0_CheckReceive();
   if(gpio_pin_get_val(INPUT_5V_Pin))
   {
      //UART_CheckSend();
// bat_percent=Get_Battary();
      if(state5v==0)
      {
         state5v=1;
      }
   }else{
        if(state5v==1)
        {
            state5v=0;
               //UartDeinit();
        }
void MinuteTask(void)
{
//    adc_get(&sample[0], NUM_SAMPLES, adc_callback);//adc采样
}
/********************************************************************************************************/
static void Lora_irq_handler(enum IO_PIN_T pin)
{
   RadioIrqProcess();
}
void SecondTask(void)
{static uint8_t second_count;
   
    if(second_count++>60)
    {
        second_count = 0;
        MinuteTask();
    }
   lora_tx_flag=1;
      //Lora_Tx_Poll();
//    //UWB状态检测
//if(!power_low_flag)//低供电下不需要检测重连
//   {
//    if(IfTCPConnected())
//    {
//        TCP_reconnect_timer =0;
//        flag_TCP_reconnectting = 0;
//    } else {
//        if(TCP_reconnect_timer<30)//如果TCP没有连接,每隔10分钟尝试连接30秒
//        {
//            flag_TCP_reconnectting = 1;
//        } else {
//            flag_TCP_reconnectting = 0;
//        }
//        if(TCP_reconnect_timer++>600)
//        {
//            TCP_reconnect_timer = 0;
//        }
//    }
//   }
    HIDO_TimerTick();
      if(nomove_count<=g_com_map[NOMOVESLEEP_TIME])//防止溢出
    nomove_count++;
      else{
      nomove_count=g_com_map[NOMOVESLEEP_TIME]+1;
      }
}
void boot_deinit(void)
void spi_init(void)
{
   //将boot中串口返回普通gpio
// UART0 TX/RX
    io_pin_mux_set(IO_PIN_5, IO_FUNC0);
    io_pin_mux_set(IO_PIN_6, IO_FUNC0);
    // UART1 RX/TX
    io_pin_mux_set(IO_PIN_10, IO_FUNC0);
    io_pin_mux_set(IO_PIN_9, IO_FUNC0);
    uart_close(UART_ID1);//解绑原来串口1
    uart_close(UART_ID0);//解绑原来串口0
  struct SPI_CFG_T usr_spi_cfg =
    {
        .bit_rate = 1000000,
        .data_bits = 8,
//#if TEST_SPI_MASTER
        .slave = 0,
//#else
//        .slave = 1,
//#endif
        .clk_phase = 0,
        .clk_polarity = 0,
        .ti_mode = 0,
//#if (TEST_SPI_MODE == TEST_SPI_POLL_MODE)
        .dma_rx = false,
        .dma_tx = false,
        .int_rx = false,
        .int_tx = false,
//#elif (TEST_SPI_MODE == TEST_SPI_INTERUPT_MODE)
//        .dma_rx = false,
//        .dma_tx = false,
//        .int_rx = true,
//        .int_tx = true,
//#elif (TEST_SPI_MODE == TEST_SPI_DMA_MODE)
//        .dma_rx = true,
//        .dma_tx = true,
//        .int_rx = false,
//        .int_tx = false,
//#endif
    };
     spi_open(SPI_ID0, &usr_spi_cfg);
}
int main(void)
static void board_init(void)
{
    board_clock_run();
      boot_deinit();
    board_pins_config();
    board_debug_console_open(TRACE_PORT_UART0);
       // Reset reason
    reset_cause_get();
    reset_cause_clear();
    // Load calibration parameters from NVM
    uint32_t internal_flash = (REG_READ(0x40000018) >> 17) & 0x1;
    uint32_t external_flash = (REG_READ(0x40010030) >> 28) & 0x3;
    // Clock configuration
    board_clock_run();
      boot_deinit();//新加的
    // Pin configuration
    board_pins_config();
    // Trace configuration
    board_debug_console_open(TRACE_PORT_UART1);
    // Reset reason
    reset_cause_get();
    reset_cause_clear();
#ifndef CELL_PHONE_EN
    // Load calibration parameters from NVM
    if (internal_flash || external_flash == 1)
    {
        WsfNvmInit();
@@ -296,73 +288,232 @@
    {
        board_calibration_params_default();
    }
#else
    if (internal_flash)
    {
        program_efuse();
    }
    board_calibration_params_default();
#endif
    // Chip calibration
    calib_chip();
    // Disable watchdog timer
    wdt_close(WDT_ID0);
      wdt_open(WDT_ID0,&app_wdt_cfg);//30s最大上限检测喂狗
    //LOG_INFO(TRACE_MODULE_APP, "UWB qiang  test example\r\n");
    // open system timer
    //sys_timer_open();
    gpio_open();
    board_led_init();
       //uart_open(UART_ID0, &test_uart_cfg);
         Program_Init();
       //power_wakeup_enable((enum POWER_WAKEUP_SOURCE_T)POWER_WAKEUP_BY_GPIO_0, POWER_WAKEUP_LEVEL_LOW);
       uart_receive(UART_ID0,m_EUART_DMA_RXBuf,EUART_RX_BUF_SIZE,uart_receive_callback);
      // Initialize low power mode
    power_init();
      Get_batterty_Voltage();//获取当前内部电压
      //Calculate_battery_percent();
      //adc_open(&usr_adc_cfg);
      //adc_get(&sample[0], NUM_SAMPLES, adc_callback);//adc采样
    // Enable sleep timer
      Tag_uwb_init();
    sleep_timer_open(true, SLEEP_TIMER_MODE_RELOAD, sleep_timer_callback);
      //sleep_timer_start(__MS_TO_32K_CNT(g_com_map[COM_INTERVAL]));//测试
      sleep_timer_start(__MS_TO_32K_CNT(SLEEP_COUNT));//测试
      //board_5V_input_init(voltage_input_handler);//有修改3.3V会一直高电平导致无法进入休眠
      #ifdef BOXING
            io_pin_mux_set(IO_PIN_5, IO_FUNC0);//波形测试
         gpio_pin_set_dir( IO_PIN_5, GPIO_DIR_OUT, 0);
         io_pull_set(IO_PIN_5 , IO_PULL_DOWN, IO_PULL_UP_LEVEL4);
   #endif
      //Serial0_PutString("进入app测试\r\n");
    while (1)
    {  wdt_ping(WDT_ID0);//喂狗
         if(g_start_send_flag)
         {
         //LOG_INFO(TRACE_MODULE_APP, "测距ing");
         g_start_send_flag = 0;
         gpio_pin_set(LED_PIN);//亮
         TagRange();
         gpio_pin_clr(LED_PIN);//灭
         IdleTask();
         }else{
         IdleTask();
         }
         LoraUp_Poll();
#ifndef DEBUG_MODE
         if(sleep_flag){//开始一段时间无休眠
                  trace_flush();
            uint32_t lock = int_lock();
                  //LOG_INFO(TRACE_MODULE_APP, "进入低功耗");
                  //唤醒源设置MK8000修改
                  //board_5V_input_init(voltage_input_handler);
                  //sleep_timer_start(g_com_map[COM_INTERVAL]);
            power_enter_power_down_mode(0);
                  uart_receive(UART_ID0,m_EUART_DMA_RXBuf,EUART_RX_BUF_SIZE,uart_receive_callback);
               //LOG_INFO(TRACE_MODULE_APP, "进入低功耗");
            int_unlock(lock);
         }
#endif
    }
#ifdef CELL_PHONE_EN
    // Configure IO_04 for RF Switch
    gpio_pin_set_dir(IO_PIN_4, GPIO_DIR_OUT, 0);
#else
      spi_init();
    // 模式判断脚和spi nrst脚初始化
    board_mode_pin_init();
            Program_Init();
//    board_led_on(BOARD_LED_1);
#endif
      Board_LORA_NVIC_Init(Lora_irq_handler);
    board_configure();
}
void app_process_handle(uint8_t msg_id, const void *param)
{
    switch (msg_id)
    {
        case APP_TEST_TIMER1_MSG:
        {
#if ANT_DELAY_CAL_EN
            // stop calibration
            uwbapi_session_stop(uwb_app_config.session_id);
            uwbapi_session_deinit(uwb_app_config.session_id);
            // restart UCI RX
            uci_tl_rx_restart();
#endif
        }
        break;
        default:
            break;
    }
}
void Fira_Change_Task(void)
{
}
static void uart_receive_callback(void *dev, uint32_t err_code)
{
    uart_receive(UART_ID1,m_EUART_DMA_RXBuf,EUART_RX_BUF_SIZE,uart_receive_callback);
}
void uart0_receive_callback(void *dev, uint32_t err_code)
{
    uart_receive(UART_ID0,m_EUART0_DMA_RXBuf,EUART0_RX_BUF_SIZE,uart0_receive_callback);
}
uint8_t bat_percent;
uint8_t  stationary_flag;
void mcu_deep_sleep(void)
{
            uint32_t lock;
            trace_flush();
            lock = int_lock();
                     sleep_timer_stop();
            power_enter_power_down_mode(1);
            int_unlock(lock);
}
int main(void)
{
   // Initialize MCU system
    board_init();
    // Disable watchdog timer
    wdt_close(WDT_ID0);
    LOG_INFO(TRACE_MODULE_APP, "UCI FiRa example\r\n");
   //delay_ms(300);//使log打印完毕
   if(gpio_pin_get_val(SLEEP_PIN))
   {
   if(gpio_pin_get_val(MODE_CHANGE_PIN))//记得改回来与正式的相反
   {
      LOG_INFO(TRACE_MODULE_APP,"固件版本:MK_Air_tag模式 V%d.%d. \r\n",g_com_map[VERSION]>>8,g_com_map[VERSION]&0xff);
      // Platform init for WSF
    PalSysInit();
    // Initialize os
    //
    // Set up timers for the WSF scheduler.
    //
    WsfOsInit();
    WsfTimerInit();
    sys_tick_callback_set(WsfTimerUpdateTicks);
    //
    // Initialize a buffer pool for WSF dynamic memory needs.
    //
    uint32_t wsfBufMemLen = WsfBufInit(WSF_BUF_POOLS, poolDescriptors);
    if (wsfBufMemLen > FREE_MEM_SIZE)
    {
        LOG_INFO(TRACE_MODULE_APP, "Memory pool is not enough %d\r\n", wsfBufMemLen - FREE_MEM_SIZE);
    }
//
    // Create app task
    //
   wsfHandlerId_t handlerId = WsfOsSetNextHandler(app_handler);
    app_init(handlerId);
    //
    // Create ranging task or test task
    //
    handlerId = WsfOsSetNextHandler(ranging_handler);
    ranging_init(handlerId);
#ifdef UWB_UCI_TEST_EN
    // Create test task
    handlerId = WsfOsSetNextHandler(uwb_test_handler);
    uwb_test_init(handlerId);
#endif
#ifndef MY_MODE
    uwb_open();
    // set advanced parameters
    struct PHY_ADV_CONFIG_T adv_config =
    {
        // RPM0: 40, RPM3: 60
        .thres_fap_detect = 60,
        // RPM0: 4, RPM3: 8
        .nth_scale_factor = 8,
        // RFrame SP0: 0/1, Others: 0/1/2/3
        .ranging_performance_mode = 3,
#if RX_ANT_PORTS_NUM == 4
        .skip_weakest_port_en = 1,
#else
        .skip_weakest_port_en = 0,
#endif
    };
    phy_adv_params_configure(&adv_config);
    // which RX ports will be used for AoA/PDoA
    phy_rx_ant_mode_set(RX_ANT_PORTS_COMBINATION);
    uwbs_init();
    uwb_app_config.ranging_flow_mode = (uint8_t)(RANGING_FLOW_FIRA);
    uwb_app_config.filter_en = (uint8_t)(FILTER_EN);
    uwb_app_config.session_param.tx_power_level = board_param.tx_power_fcc[CALIB_CH(uwb_app_config.ppdu_params.ch_num)];
    uwb_app_config.ppdu_params.rx_ant_id = (uint8_t)(RX_MAIN_ANT_PORT);
#elif defined MY_MODE
      Uwb_init();//默认为我们测距配置
      OpenUWB();
      uart_receive(UART_ID1,m_EUART_DMA_RXBuf,EUART_RX_BUF_SIZE,uart_receive_callback);
#endif
    //
    // Create UCI transmission layer task
    //
    handlerId = WsfOsSetNextHandler(uci_tl_handler);
    uci_tl_init(handlerId);
    // Initialize low power mode
    power_init();
#if LOW_POWER_EN
    power_mode_request(POWER_UNIT_USER, POWER_MODE_POWER_DOWN);
    uwb_app_config.low_power_en = 1;
#else
    power_mode_request(POWER_UNIT_USER, POWER_MODE_SLEEP);
    uwb_app_config.low_power_en = 0;
#endif
    // Enable sleep timer
    sleep_timer_open(true, SLEEP_TIMER_MODE_ONESHOT, sleep_timer_callback);
    while (1)
    {
        wsfOsDispatcher();
        power_manage();
            if(!gpio_pin_get_val(SLEEP_PIN))
            {
            LOG_INFO(TRACE_MODULE_APP, "进入休眠模式\r\n");
            mcu_deep_sleep();
            }
    }
    }else{
      LOG_INFO(TRACE_MODULE_APP,"固件版本:MK_免布线模式 V%d.%d. \r\n",g_com_map[VERSION]>>8,g_com_map[VERSION]&0xff);
      uart0_Init_normal();
      Lora_1268_Init();
      SwitchLoraSettings(478,7,22);
      Uwb_init();//默认为我们测距配置
      OpenUWB();
      uart_receive(UART_ID1,m_EUART_DMA_RXBuf,EUART_RX_BUF_SIZE,uart_receive_callback);
      uart_receive(UART_ID0,m_EUART0_DMA_RXBuf,EUART0_RX_BUF_SIZE,uart0_receive_callback);
    power_init();
    sleep_timer_open(true, SLEEP_TIMER_MODE_RELOAD, sleep_timer_callback_normal);
      sleep_timer_start(__MS_TO_32K_CNT(SLEEP_TIMER_NUM));//测试
          while (1)
            {
            uwb_app_poll();//我们的测距逻辑
            if(flag_secondtask)
        {
            flag_secondtask = 0;
            SecondTask();
               //Lora_Tx_Poll();
        }
            Lora_Tx_Poll();
            if(!gpio_pin_get_val(SLEEP_PIN))
            {
            LOG_INFO(TRACE_MODULE_APP, "进入休眠模式\r\n");
            mcu_deep_sleep();
            }
            IdleTask();
            }
   }
}else{
//delay_ms(300);
   LOG_INFO(TRACE_MODULE_APP, "进入休眠模式\r\n");
    power_init();
   mcu_deep_sleep();
}
}
void app_restore_from_power_down(void)
{
}