prettyprint

2025年4月26日 星期六

[STM32] STM32F407 using LVGL and XPT2046 touch screen and rotary encoder input device library

 本文章介紹STM32F407VET6 使用LVGL library與結合XPT2046 touch screen 與Rotary Encoder 等input devices。

有關移植LVGL到STM32F407的步驟請參閱前篇文章

STM32 HAL|| 16 bit parallel LCD-TFT driver using FSMC interface for LVGL || DMA


詳細步驟請參閱「成果影片」

成果影片:


程式碼:

  • rotary_encoder.c
/*
 * rotary_encoder.c

 */
#include <main.h>
#include "lvgl.h"

lv_indev_t *encoder_indev;
lv_group_t *encoder_group;

static TIM_HandleTypeDef *encoder_htim;

static uint32_t old_counter;

uint8_t re_key_press() {
    if (HAL_GPIO_ReadPin(Encoder_SW_GPIO_Port, Encoder_SW_Pin) == GPIO_PIN_RESET) {
        return 1;
    }
    return 0;
}

int16_t re_get_new_moves(void) {
    int16_t new_moves;
    new_moves = 0;
    uint32_t counter = __HAL_TIM_GET_COUNTER(encoder_htim);
    if (counter < old_counter) {
    	 new_moves = 1; // LV_KEY_RIGHT
    }
    if (counter > old_counter) {
    	new_moves = -1; // LV_KEY_LEFT
    }
    old_counter = counter;

    return new_moves;

}

void lvgl_encoder_read_cb(struct _lv_indev_drv_t * indev, lv_indev_data_t* data) {
  //data->key = get_key();;
	data->enc_diff = re_get_new_moves();    //rotation
	if (re_key_press()) {					// switch
		data->state = LV_INDEV_STATE_PRESSED;
	} else {
		data->state = LV_INDEV_STATE_RELEASED;
		//data->enc_diff = re_get_new_moves();
	}

 }





void lvgl_rotary_encoder_init(TIM_HandleTypeDef *htim){
	encoder_htim = htim;
	HAL_TIM_Encoder_Start(htim,  TIM_CHANNEL_1);
	__HAL_TIM_SET_COUNTER(encoder_htim,32768);
	old_counter = 32768;

	// setup rotary encoder input device
	static lv_indev_drv_t indev_drv;           /*Descriptor of a input device driver*/
	lv_indev_drv_init(&indev_drv);             /*Basic initialization*/
	indev_drv.type = LV_INDEV_TYPE_ENCODER;    /*Rotary Encoder device*/

	indev_drv.read_cb = lvgl_encoder_read_cb;      /*Set your driver function*/

	indev_drv.long_press_time=1000;
	indev_drv.long_press_repeat_time=100;
	encoder_indev = lv_indev_drv_register(&indev_drv);         /*Finally register the driver*/
	encoder_group = lv_group_create();

	//lv_group_set_default(kg);
	lv_indev_set_group(encoder_indev, encoder_group);
}


 
  • rotary_encoder.h
/*
 * rotary_incoder.h

 */

#ifndef ROTARY_ENCODER_ROTARY_ENCODER_H_
#define ROTARY_ENCODER_ROTARY_ENCODER_H_

extern lv_indev_t *encoder_indev;
extern lv_group_t *encoder_group;

void lvgl_rotary_encoder_init(TIM_HandleTypeDef *htim);

void lvgl_encoder_read_cb(struct _lv_indev_drv_t * indev, lv_indev_data_t* data);




#endif /* ROTARY_ENCODER_ROTARY_ENCODER_H_ */

 
  • STM32_LVGL_LIB_DEMO.ioc
#MicroXplorer Configuration settings - do not modify
CAD.formats=
CAD.pinconfig=
CAD.provider=
Dma.MEMTOMEM.0.Direction=DMA_MEMORY_TO_MEMORY
Dma.MEMTOMEM.0.FIFOMode=DMA_FIFOMODE_ENABLE
Dma.MEMTOMEM.0.FIFOThreshold=DMA_FIFO_THRESHOLD_FULL
Dma.MEMTOMEM.0.Instance=DMA2_Stream0
Dma.MEMTOMEM.0.MemBurst=DMA_MBURST_SINGLE
Dma.MEMTOMEM.0.MemDataAlignment=DMA_MDATAALIGN_HALFWORD
Dma.MEMTOMEM.0.MemInc=DMA_MINC_DISABLE
Dma.MEMTOMEM.0.Mode=DMA_NORMAL
Dma.MEMTOMEM.0.PeriphBurst=DMA_PBURST_SINGLE
Dma.MEMTOMEM.0.PeriphDataAlignment=DMA_PDATAALIGN_HALFWORD
Dma.MEMTOMEM.0.PeriphInc=DMA_PINC_ENABLE
Dma.MEMTOMEM.0.Priority=DMA_PRIORITY_LOW
Dma.MEMTOMEM.0.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority,FIFOMode,FIFOThreshold,MemBurst,PeriphBurst
Dma.Request0=MEMTOMEM
Dma.RequestsNb=1
FSMC.AddressSetupTime1=7
FSMC.BusTurnAroundDuration1=7
FSMC.DataSetupTime1=10
FSMC.IPParameters=DataSetupTime1,BusTurnAroundDuration1,AddressSetupTime1
File.Version=6
KeepUserPlacement=false
Mcu.CPN=STM32F407VET6
Mcu.Family=STM32F4
Mcu.IP0=DMA
Mcu.IP1=FSMC
Mcu.IP2=NVIC
Mcu.IP3=RCC
Mcu.IP4=SPI2
Mcu.IP5=SYS
Mcu.IP6=TIM2
Mcu.IP7=TIM3
Mcu.IPNb=8
Mcu.Name=STM32F407V(E-G)Tx
Mcu.Package=LQFP100
Mcu.Pin0=PC14-OSC32_IN
Mcu.Pin1=PC15-OSC32_OUT
Mcu.Pin10=PE7
Mcu.Pin11=PE8
Mcu.Pin12=PE9
Mcu.Pin13=PE10
Mcu.Pin14=PE11
Mcu.Pin15=PE12
Mcu.Pin16=PE13
Mcu.Pin17=PE14
Mcu.Pin18=PE15
Mcu.Pin19=PB12
Mcu.Pin2=PH0-OSC_IN
Mcu.Pin20=PB13
Mcu.Pin21=PB14
Mcu.Pin22=PB15
Mcu.Pin23=PD8
Mcu.Pin24=PD9
Mcu.Pin25=PD10
Mcu.Pin26=PD13
Mcu.Pin27=PD14
Mcu.Pin28=PD15
Mcu.Pin29=PA13
Mcu.Pin3=PH1-OSC_OUT
Mcu.Pin30=PA14
Mcu.Pin31=PD0
Mcu.Pin32=PD1
Mcu.Pin33=PD4
Mcu.Pin34=PD5
Mcu.Pin35=PD7
Mcu.Pin36=VP_SYS_VS_Systick
Mcu.Pin37=VP_TIM3_VS_ClockSourceINT
Mcu.Pin4=PA0-WKUP
Mcu.Pin5=PA1
Mcu.Pin6=PA5
Mcu.Pin7=PC4
Mcu.Pin8=PC5
Mcu.Pin9=PB1
Mcu.PinsNb=38
Mcu.ThirdPartyNb=0
Mcu.UserConstants=
Mcu.UserName=STM32F407VETx
MxCube.Version=6.12.0
MxDb.Version=DB.6.0.120
NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.ForceEnableDMAVector=true
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.SysTick_IRQn=true\:15\:0\:false\:false\:true\:false\:true\:false
NVIC.TIM3_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
PA0-WKUP.Signal=S_TIM2_CH1_ETR
PA1.Signal=S_TIM2_CH2
PA13.Mode=Serial_Wire
PA13.Signal=SYS_JTMS-SWDIO
PA14.Mode=Serial_Wire
PA14.Signal=SYS_JTCK-SWCLK
PA5.GPIOParameters=GPIO_PuPd,GPIO_Label
PA5.GPIO_Label=Encoder_SW
PA5.GPIO_PuPd=GPIO_PULLUP
PA5.Locked=true
PA5.Signal=GPIO_Input
PB1.GPIOParameters=GPIO_Label
PB1.GPIO_Label=LCD_BL
PB1.Locked=true
PB1.Signal=GPIO_Output
PB12.GPIOParameters=GPIO_Label
PB12.GPIO_Label=T_CS
PB12.Locked=true
PB12.Signal=GPIO_Output
PB13.Locked=true
PB13.Mode=Full_Duplex_Master
PB13.Signal=SPI2_SCK
PB14.Locked=true
PB14.Mode=Full_Duplex_Master
PB14.Signal=SPI2_MISO
PB15.Locked=true
PB15.Mode=Full_Duplex_Master
PB15.Signal=SPI2_MOSI
PC14-OSC32_IN.Mode=LSE-External-Oscillator
PC14-OSC32_IN.Signal=RCC_OSC32_IN
PC15-OSC32_OUT.Mode=LSE-External-Oscillator
PC15-OSC32_OUT.Signal=RCC_OSC32_OUT
PC4.Locked=true
PC4.Signal=GPIO_Input
PC5.GPIOParameters=GPIO_Label
PC5.GPIO_Label=T_IRQ
PC5.Locked=true
PC5.Signal=GPIO_Input
PD0.Mode=16b-d1
PD0.Signal=FSMC_D2
PD1.Mode=16b-d1
PD1.Signal=FSMC_D3
PD10.Mode=16b-d1
PD10.Signal=FSMC_D15
PD13.Mode=A18_1
PD13.Signal=FSMC_A18
PD14.Mode=16b-d1
PD14.Signal=FSMC_D0
PD15.Mode=16b-d1
PD15.Signal=FSMC_D1
PD4.Mode=Lcd1
PD4.Signal=FSMC_NOE
PD5.Mode=Lcd1
PD5.Signal=FSMC_NWE
PD7.Mode=NorPsramChipSelect1_1
PD7.Signal=FSMC_NE1
PD8.Mode=16b-d1
PD8.Signal=FSMC_D13
PD9.Mode=16b-d1
PD9.Signal=FSMC_D14
PE10.Mode=16b-d1
PE10.Signal=FSMC_D7
PE11.Mode=16b-d1
PE11.Signal=FSMC_D8
PE12.Mode=16b-d1
PE12.Signal=FSMC_D9
PE13.Mode=16b-d1
PE13.Signal=FSMC_D10
PE14.Mode=16b-d1
PE14.Signal=FSMC_D11
PE15.Mode=16b-d1
PE15.Signal=FSMC_D12
PE7.Mode=16b-d1
PE7.Signal=FSMC_D4
PE8.Mode=16b-d1
PE8.Signal=FSMC_D5
PE9.Mode=16b-d1
PE9.Signal=FSMC_D6
PH0-OSC_IN.Mode=HSE-External-Oscillator
PH0-OSC_IN.Signal=RCC_OSC_IN
PH1-OSC_OUT.Mode=HSE-External-Oscillator
PH1-OSC_OUT.Signal=RCC_OSC_OUT
PinOutPanel.RotationAngle=0
ProjectManager.AskForMigrate=true
ProjectManager.BackupPrevious=false
ProjectManager.CompilerOptimize=6
ProjectManager.ComputerToolchain=false
ProjectManager.CoupleFile=false
ProjectManager.CustomerFirmwarePackage=
ProjectManager.DefaultFWLocation=true
ProjectManager.DeletePrevious=true
ProjectManager.DeviceId=STM32F407VETx
ProjectManager.FirmwarePackage=STM32Cube FW_F4 V1.28.0
ProjectManager.FreePins=false
ProjectManager.HalAssertFull=false
ProjectManager.HeapSize=0x200
ProjectManager.KeepUserCode=true
ProjectManager.LastFirmware=false
ProjectManager.LibraryCopy=1
ProjectManager.MainLocation=Core/Src
ProjectManager.NoMain=false
ProjectManager.PreviousToolchain=
ProjectManager.ProjectBuild=false
ProjectManager.ProjectFileName=STM32_LVGL_LIB_DEMO.ioc
ProjectManager.ProjectName=STM32_LVGL_LIB_DEMO
ProjectManager.ProjectStructure=
ProjectManager.RegisterCallBack=
ProjectManager.StackSize=0x400
ProjectManager.TargetToolchain=STM32CubeIDE
ProjectManager.ToolChainLocation=
ProjectManager.UAScriptAfterPath=
ProjectManager.UAScriptBeforePath=
ProjectManager.UnderRoot=true
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_DMA_Init-DMA-false-HAL-true,4-MX_FSMC_Init-FSMC-false-HAL-true,5-MX_SPI2_Init-SPI2-false-HAL-true,6-MX_TIM2_Init-TIM2-false-HAL-true,7-MX_TIM3_Init-TIM3-false-HAL-true
RCC.48MHZClocksFreq_Value=48000000
RCC.AHBFreq_Value=168000000
RCC.APB1CLKDivider=RCC_HCLK_DIV4
RCC.APB1Freq_Value=42000000
RCC.APB1TimFreq_Value=84000000
RCC.APB2CLKDivider=RCC_HCLK_DIV2
RCC.APB2Freq_Value=84000000
RCC.APB2TimFreq_Value=168000000
RCC.CortexFreq_Value=168000000
RCC.EthernetFreq_Value=168000000
RCC.FCLKCortexFreq_Value=168000000
RCC.FamilyName=M
RCC.HCLKFreq_Value=168000000
RCC.HSE_VALUE=8000000
RCC.HSI_VALUE=16000000
RCC.I2SClocksFreq_Value=192000000
RCC.IPParameters=48MHZClocksFreq_Value,AHBFreq_Value,APB1CLKDivider,APB1Freq_Value,APB1TimFreq_Value,APB2CLKDivider,APB2Freq_Value,APB2TimFreq_Value,CortexFreq_Value,EthernetFreq_Value,FCLKCortexFreq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,HSI_VALUE,I2SClocksFreq_Value,LSI_VALUE,MCO2PinFreq_Value,PLLCLKFreq_Value,PLLM,PLLN,PLLQ,PLLQCLKFreq_Value,PLLSourceVirtual,RTCFreq_Value,RTCHSEDivFreq_Value,SYSCLKFreq_VALUE,SYSCLKSource,VCOI2SOutputFreq_Value,VCOInputFreq_Value,VCOOutputFreq_Value,VcooutputI2S
RCC.LSI_VALUE=32000
RCC.MCO2PinFreq_Value=168000000
RCC.PLLCLKFreq_Value=168000000
RCC.PLLM=4
RCC.PLLN=168
RCC.PLLQ=7
RCC.PLLQCLKFreq_Value=48000000
RCC.PLLSourceVirtual=RCC_PLLSOURCE_HSE
RCC.RTCFreq_Value=32000
RCC.RTCHSEDivFreq_Value=4000000
RCC.SYSCLKFreq_VALUE=168000000
RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK
RCC.VCOI2SOutputFreq_Value=384000000
RCC.VCOInputFreq_Value=2000000
RCC.VCOOutputFreq_Value=336000000
RCC.VcooutputI2S=192000000
SH.S_TIM2_CH1_ETR.0=TIM2_CH1,Encoder_Interface
SH.S_TIM2_CH1_ETR.ConfNb=1
SH.S_TIM2_CH2.0=TIM2_CH2,Encoder_Interface
SH.S_TIM2_CH2.ConfNb=1
SPI2.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_32
SPI2.CalculateBaudRate=1.3125 MBits/s
SPI2.Direction=SPI_DIRECTION_2LINES
SPI2.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,BaudRatePrescaler
SPI2.Mode=SPI_MODE_MASTER
SPI2.VirtualType=VM_MASTER
TIM2.EncoderMode=TIM_ENCODERMODE_TI1
TIM2.IC1Filter=0
TIM2.IC1Polarity=TIM_ICPOLARITY_FALLING
TIM2.IC2Filter=0
TIM2.IC2Polarity=TIM_ICPOLARITY_FALLING
TIM2.IPParameters=Period,IC2Polarity,IC1Polarity,EncoderMode,Prescaler,IC1Filter,IC2Filter
TIM2.Period=65535
TIM2.Prescaler=0
TIM3.IPParameters=Prescaler,Period
TIM3.Period=10-1
TIM3.Prescaler=42000-1
VP_SYS_VS_Systick.Mode=SysTick
VP_SYS_VS_Systick.Signal=SYS_VS_Systick
VP_TIM3_VS_ClockSourceINT.Mode=Internal
VP_TIM3_VS_ClockSourceINT.Signal=TIM3_VS_ClockSourceINT
board=custom
isbadioc=false

 
其餘程式碼請參閱前篇文章:




2025年4月14日 星期一

[Raspberry Pi Pico2 W] SNTP & RTC || RP2350

 本影片介紹了Raspberry Pi Pico 2 W對SNTP和RTC功能的實作。相同的程式碼可以在 Pico W 上運行。

專案的UI使用LVGL函式庫(TFT display & Rotary Encoder)

LwIP SNTP application API在專案中包裝程一組Libarary提供三個 functions:

bool pico_sntp_enable(int8_t tz);
bool pico_sntp_get_system_time_timeout_ms(uint32_t ms);
bool pico_sntp_restart_timeout_ms(int8_t tz, uint32_t ms);

Pico 2與Pico 使用RTC的Hardware 不一樣,新的aon_timer_xxx這組的api適用於RP2040與RP2350,詳細說明可參閱RP2040與RP2350 datasheet。

其他詳細內容與成果展示影片,附於文末。


成果影片:



程式碼:

sntp_lib:

  • CMakeLists.txt

add_library(sntp_lib INTERFACE)
target_sources(sntp_lib INTERFACE
    ${CMAKE_CURRENT_LIST_DIR}/sntp_lib.c
)

target_include_directories(sntp_lib INTERFACE
    ${CMAKE_CURRENT_LIST_DIR}
)

target_link_libraries(sntp_lib INTERFACE
        pico_aon_timer
        pico_lwip_sntp
)

  • sntp_lib.c

#include "stdio.h"
#include "pico/stdlib.h"
#include "sntp_lib.h"
#include "lwip/apps/sntp.h"
#include "pico/aon_timer.h"

//SNTP
static bool ntp_datetime_ok=false;
static int8_t sntp_timezone;
void sntp_set_system_time(u32_t sec)
{
    char buf[32];
    struct tm current_time_val;

    time_t current_time = (sec+sntp_timezone*60*60);
    struct tm* p= gmtime(&current_time);

    aon_timer_set_time_calendar(p);

    ntp_datetime_ok=true;
}

bool pico_sntp_enable(int8_t tz) {
    sntp_timezone = tz;
    sntp_setoperatingmode(SNTP_OPMODE_POLL);
    sntp_setservername(0, "pool.ntp.org");      //SNTP_SERVER_DNS (lwipop.h)
    //ip_addr_t ntpserver;
    //ipaddr_aton("118.163.81.63", &ntpserver);
    //sntp_setserver(0, &ntpserver);
    sntp_init();
    if (!sntp_enabled()) {
        printf("sntp not enable\n");
        return false;
    }
    return true;
}

bool pico_sntp_get_system_time_timeout_ms(uint32_t ms) {
    absolute_time_t curTime = get_absolute_time();
    bool ret = false;
    while (absolute_time_diff_us(curTime, get_absolute_time()) < ms*1000) {
        if (ntp_datetime_ok) {
            ret = true;
            break;
        } else {
            sleep_ms(100);
        }
    }
    return ret;
}

bool pico_sntp_restart_timeout_ms(int8_t tz, uint32_t ms) {
    sntp_stop();
    if (pico_sntp_enable(tz)) {
        return pico_sntp_get_system_time_timeout_ms(ms);
    } else {
        return false;
    }
}

  • sntp_lib.h

#ifndef __SNTP_LIB__
#define __SNTP_LIB__

bool pico_sntp_enable(int8_t tz);
bool pico_sntp_get_system_time_timeout_ms(uint32_t ms);
bool pico_sntp_restart_timeout_ms(int8_t tz, uint32_t ms);

#endif

  • CMakeLists.txt(root)

# Generated Cmake Pico project file

cmake_minimum_required(VERSION 3.13)

set(CMAKE_C_STANDARD 11)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)

# Initialise pico_sdk from installed location
# (note this can come from environment, CMake cache etc)

# == DO NOT EDIT THE FOLLOWING LINES for the Raspberry Pi Pico VS Code Extension to work ==
if(WIN32)
    set(USERHOME $ENV{USERPROFILE})
else()
    set(USERHOME $ENV{HOME})
endif()
set(sdkVersion 2.1.1)
set(toolchainVersion 13_3_Rel1)
set(picotoolVersion 2.1.1)
set(picoVscode ${USERHOME}/.pico-sdk/cmake/pico-vscode.cmake)
if (EXISTS ${picoVscode})
    include(${picoVscode})
endif()
# ====================================================================================
set(PICO_BOARD pico_w CACHE STRING "Board type")

# Pull in Raspberry Pi Pico SDK (must be before project)
include(pico_sdk_import.cmake)

project(pico2w_clock_ht C CXX ASM)

# Initialise the Raspberry Pi Pico SDK
pico_sdk_init()

# Add executable. Default name is the project name, version 0.1

add_executable(pico2w_clock_ht pico2w_clock_ht.c display.c)

pico_set_program_name(pico2w_clock_ht "pico2w_clock_ht")
pico_set_program_version(pico2w_clock_ht "0.1")

# Modify the below lines to enable/disable output over UART/USB
pico_enable_stdio_uart(pico2w_clock_ht 1)
pico_enable_stdio_usb(pico2w_clock_ht 0)

# Add the standard library to the build
target_link_libraries(pico2w_clock_ht
        pico_stdlib
        pico_aon_timer
        hardware_pio
        hardware_timer
        )

# Add the standard include files to the build
target_include_directories(pico2w_clock_ht PRIVATE
        ${CMAKE_CURRENT_LIST_DIR}
)

# Add any user requested libraries
target_link_libraries(pico2w_clock_ht 
        pico_cyw43_arch_lwip_threadsafe_background
        )



target_compile_definitions(pico2w_clock_ht PRIVATE
        WIFI_SSID="$ENV{WIFI_SSID}"
        WIFI_PASSWD="$ENV{WIFI_PASSWD}"
)


add_subdirectory(pico_lvgl)
add_subdirectory(sntp_lib)
add_subdirectory(aht10_lib)
target_link_libraries(pico2w_clock_ht
        pico_lvgl
        sntp_lib
        aht10_lib
        )

pico_add_extra_outputs(pico2w_clock_ht)

  • pico2w_clock_ht.c

#include <stdio.h>
#include "pico/stdlib.h"
#include "pico/cyw43_arch.h"
#include "hardware/pio.h"
#include "pico/aon_timer.h"

#include "pico_lvgl.h"
#include "sntp_lib.h"
#include "display.h"
#include "aht10.h"

#define TFT_PIO             pio0
#define TFT_SM              2
#define TFT_SDI_GPIO        9
#define TFT_CSX_DCX_SCK_GPIO 6 // CSX=8, DCX(A0)=7, SCK=6, SIDE_SET

#define TIME_ZONE           8

#define AHT10_I2C_PORT      i2c0
#define AHT10_SDA           16
#define AHT10_SCL           17


bool timer_callback(repeating_timer_t* rt) { 
    display_clock_meter();
    return true;
}
bool aht10_callback(repeating_timer_t* rt) {
    display_ht();
    return true;
}

int main()
{
    stdio_init_all();

    gpio_init(ALARM_BUZZER_PIN);
    gpio_set_dir(ALARM_BUZZER_PIN, true);
    gpio_put(ALARM_BUZZER_PIN, false);

    pico_lvgl_tft_init(TFT_PIO, TFT_SM, TFT_SDI_GPIO, TFT_CSX_DCX_SCK_GPIO);
    tft_set_orientation(TFT_ORIENTATION_LANDSCAPE_MIRROR);
    pico_lvgl_display_init(5);
    pico_lvgl_encoder_init(true);
    
    struct tm dt;
    dt.tm_year = 2025-1900;
    dt.tm_mon = 3;
    dt.tm_mday = 1;
    dt.tm_hour = 0;
    dt.tm_min = 0;
    dt.tm_sec = 0;
    if (!aon_timer_start_calendar(&dt)) {
        show_msgbox("Error", "Start RTC error");
        return 1;
    }
    char msgbuff[100];
    // Initialise the Wi-Fi chip
    if (cyw43_arch_init()) {
        printf("Wi-Fi init failed\n");
        show_msgbox( "Error", "Wi-Fi init failed");
        return -1;
    }

    // Enable wifi station
    cyw43_arch_enable_sta_mode();

    printf("Connecting to Wi-Fi...\n");
    show_msgbox("Message", "Connecting to Wi-Fi...");
    if (cyw43_arch_wifi_connect_timeout_ms(WIFI_SSID, WIFI_PASSWD, CYW43_AUTH_WPA2_AES_PSK, 30000)) {
        printf("failed to connect.\n");
        close_msgbox();
        show_msgbox("Error", "failed to connect.");
        return 1;
    } else {
        printf("Connected.\n");       
        // Read the ip address in a human readable way
        uint8_t *ip_address = (uint8_t*)&(cyw43_state.netif[0].ip_addr.addr);
        
        sprintf(msgbuff, "IP address %d.%d.%d.%d", ip_address[0], ip_address[1], ip_address[2], ip_address[3]);
        printf("%s\n",msgbuff);
        close_msgbox();
        show_msgbox( "Message", msgbuff);
        sleep_ms(2000);
        close_msgbox();        
    }
    // enable SNTP
    if (!pico_sntp_enable(TIME_ZONE)) {
        show_msgbox("Error", "Enable SNTP Error");
        return -1;
    }
    show_msgbox("Message", "Getting NTP Time...");
    if (pico_sntp_get_system_time_timeout_ms(20000)) {
        struct tm dt;
        aon_timer_get_time_calendar(&dt);
        sprintf(msgbuff, "Date:%04d-%02d-%02d\nTime:%02d:%02d:%02d\n", dt.tm_year+1900, dt.tm_mon+1, dt.tm_mday,
                    dt.tm_hour, dt.tm_min, dt.tm_sec);
        close_msgbox();
        show_msgbox("Info", msgbuff);
    } else {
        printf("sntp time out\n");
        close_msgbox();
        show_msgbox("Info", "Restarting SNTP");
        if (!pico_sntp_restart_timeout_ms(TIME_ZONE, 20000)) {
            close_msgbox();
            show_msgbox("Info", "Get NTP Time timeout");
            return -1;
        } else {
            close_msgbox();
            struct tm dt;
            aon_timer_get_time_calendar(&dt);
            sprintf(msgbuff, "Date:%04d-%02d-%02d\nTime:%02d:%02d:%02d\n", dt.tm_year+1900, dt.tm_mon+1, dt.tm_mday,
                        dt.tm_hour, dt.tm_min, dt.tm_sec);
            show_msgbox("Info", msgbuff);
        } 
    }
    close_msgbox();

    draw_screens();  // draw analog clock screen and Alarm setting screen
    lv_disp_load_scr(clock_scr); // load clock screen as default
    repeating_timer_t rt;
    add_repeating_timer_ms(-1000, timer_callback, NULL, &rt);

    //init AHT10 sensor and read Temperature/Humidity every 5 seconds
    aht10_init(AHT10_I2C_PORT, AHT10_SDA,AHT10_SCL);
    repeating_timer_t rt_ht;
    add_repeating_timer_ms(-5000, aht10_callback, NULL, &rt_ht);

    while (true) {
        lv_timer_handler();
        sleep_ms(10);
    }
}