Skip to content

Commit

Permalink
Update LA66 v1.3
Browse files Browse the repository at this point in the history
1.Compatible with the newer version of the ASR6601 chip.
2.Fixed the DR2 downlink limit of AS923 frequency to 11 bytes when AT+DWELLT=1.
3.Added Lora wireless upgrade program with bootload.
  • Loading branch information
engineer-lin committed Jan 3, 2024
1 parent 7f19188 commit bc58f75
Show file tree
Hide file tree
Showing 23 changed files with 224 additions and 81 deletions.
5 changes: 2 additions & 3 deletions Drivers/peripheral/inc/tremo_rcc.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,8 @@ extern "C" {
#define RCC_FREQ_32M ((uint32_t)32000000)
#define RCC_FREQ_30M ((uint32_t)30000000)
#define RCC_FREQ_24M ((uint32_t)24000000)
#define RCC_FREQ_4M ((uint32_t)4000000)
#define RCC_FREQ_32768 ((uint32_t)32768)
#define RCC_FREQ_32000 ((uint32_t)32000)
#define RCC_FREQ_4M ((uint32_t)3600000)
#define RCC_FREQ_32768 ((uint32_t)32768)

#define RCC_WAIT() \
do { \
Expand Down
12 changes: 6 additions & 6 deletions Drivers/peripheral/inc/tremo_regs.h
Original file line number Diff line number Diff line change
Expand Up @@ -464,8 +464,8 @@ typedef struct __RTC {
__IO uint32_t CALENDAR_H; /*!< time year/month/date*/
__IO uint32_t CYC_MAX; /*!< cyc max value*/
__IO uint32_t SR; /*!< status register*/
__I uint32_t SYN_DATA; /*!< syncronization time hour/minute/second*/
__I uint32_t SYN_DATA_H; /*!< syncronization time year/month/date*/
__I uint32_t ASYN_DATA; /*!< asynchronization time hour/minute/second*/
__I uint32_t ASYN_DATA_H; /*!< asynchronization time year/month/date*/
__IO uint32_t CR1; /*!< control register 1*/
__IO uint32_t SR1; /*!< status register 1*/
__IO uint32_t CR2; /*!< control register 2*/
Expand Down Expand Up @@ -524,11 +524,11 @@ typedef struct {

#define UART_CR_UART_EN ((uint32_t)0x00000001)

#define UART_CR_UART_MODE ((uint32_t)0x00000030)
#define UART_CR_UART_MODE ((uint32_t)0x00000300)
#define UART_CR_UART_MODE_NONE ((uint32_t)0x00000000)
#define UART_CR_UART_MODE_RX ((uint32_t)0x00000020)
#define UART_CR_UART_MODE_TX ((uint32_t)0x00000010)
#define UART_CR_UART_MODE_TXRX ((uint32_t)0x00000030)
#define UART_CR_UART_MODE_RX ((uint32_t)0x00000200)
#define UART_CR_UART_MODE_TX ((uint32_t)0x00000100)
#define UART_CR_UART_MODE_TXRX ((uint32_t)0x00000300)

#define UART_CR_FLOW_CTRL ((uint32_t)0x0000C000)
#define UART_CR_FLOW_CTRL_NONE ((uint32_t)0x00000000)
Expand Down
5 changes: 2 additions & 3 deletions Drivers/peripheral/inc/tremo_spi.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ extern "C" {
#define SSP_INTERRUPT_RX_TIMEOUT (1 << 1) /*!< RX timeout interrupt*/
#define SSP_INTERRUPT_RX_FIFO_TRIGGER (1 << 2) /*!< RX fifo trigger interrupt*/
#define SSP_INTERRUPT_TX_FIFO_TRIGGER (1 << 3) /*!< TX fifo trigger interrupt*/
#define SSP_INTERRUPT_RX_OVERRUN_AND_TIMEOUT (0x3) /*!< RX fifo overrun and RX timeout interrupt*/
#define SSP_INTERRUPT_ALL (0xf) /*!< All interrupt*/

#define SSP_DMA_TX_EN (1 << 1) /*!< TX DMA enable*/
Expand All @@ -76,9 +77,7 @@ typedef struct {
* @param ssp_interrupt SSP interrupt
* @arg SSP_INTERRUPT_RX_FIFO_OVERRUN: RX fifo overrun interrupt
* @arg SSP_INTERRUPT_RX_TIMEOUT: RX timeout interrupt
* @arg SSP_INTERRUPT_RX_FIFO_TRIGGER: RX fifo trigger interrupt
* @arg SSP_INTERRUPT_TX_FIFO_TRIGGER: TX fifo trigger interrupt
* @arg SSP_INTERRUPT_ALL: All interrupt
* @arg SSP_INTERRUPT_RX_OVERRUN_AND_TIMEOUT: RX fifo overrun and RX timeout interrupt
* @return
*/
__STATIC_INLINE void ssp_clear_interrupt(ssp_typedef_t* SSPx, uint8_t ssp_interrupt)
Expand Down
12 changes: 6 additions & 6 deletions Drivers/peripheral/src/tremo_dma.c
Original file line number Diff line number Diff line change
Expand Up @@ -78,9 +78,6 @@ void dma0_IRQHandler(void)
dma_ch = 3;
}

if (g_dma_callback_handler[0][dma_ch]) {
g_dma_callback_handler[0][dma_ch]();
}
if (dma_ch == 0) {
/*clear TFR int,channelx*/
TREMO_REG_WR(DMA_CLEAR_TFR_L_REG(0), 0x1);
Expand All @@ -102,6 +99,9 @@ void dma0_IRQHandler(void)
/*clear block int,channelx*/
TREMO_REG_WR(DMA_CLEAR_BLOCK_L_REG(0), 0x8);
}
if (g_dma_callback_handler[0][dma_ch]) {
g_dma_callback_handler[0][dma_ch]();
}
}

void dma1_IRQHandler(void)
Expand All @@ -118,9 +118,6 @@ void dma1_IRQHandler(void)
dma_ch = 3;
}

if (g_dma_callback_handler[1][dma_ch]) {
g_dma_callback_handler[1][dma_ch]();
}
if (dma_ch == 0) {
/*clear TFR int,channelx*/
TREMO_REG_WR(DMA_CLEAR_TFR_L_REG(1), 0x1);
Expand All @@ -142,6 +139,9 @@ void dma1_IRQHandler(void)
/*clear block int,channelx*/
TREMO_REG_WR(DMA_CLEAR_BLOCK_L_REG(1), 0x8);
}
if (g_dma_callback_handler[1][dma_ch]) {
g_dma_callback_handler[1][dma_ch]();
}
}

static void set_dma_mode(dma_dev_t* dma, dma_config_reg_t* config_reg)
Expand Down
38 changes: 31 additions & 7 deletions Drivers/peripheral/src/tremo_gpio.c
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ void gpio_init(gpio_t* gpiox, uint8_t gpio_pin, gpio_mode_t mode)
gpiox->ODR &= ~(1 << gpio_pin);
gpiox->IER &= ~(1 << gpio_pin);
gpiox->OER |= (1 << gpio_pin);
gpiox->PSR &= ~(1 << gpio_pin);
gpiox->PSR |= (1 << gpio_pin);
} else {
gpiox->OER &= ~(1 << gpio_pin);
gpiox->IER &= ~(1 << gpio_pin);
Expand All @@ -111,7 +111,7 @@ void gpio_init(gpio_t* gpiox, uint8_t gpio_pin, gpio_mode_t mode)
gpiox->ODR &= ~(1 << gpio_pin);
gpiox->IER &= ~(1 << gpio_pin);
gpiox->OER &= ~(1 << gpio_pin);
gpiox->PSR &= ~(1 << gpio_pin);
gpiox->PSR |= (1 << gpio_pin);
} else {
gpiox->OER &= ~(1 << gpio_pin);
gpiox->IER &= ~(1 << gpio_pin);
Expand Down Expand Up @@ -160,11 +160,35 @@ void gpio_init(gpio_t* gpiox, uint8_t gpio_pin, gpio_mode_t mode)
void gpio_write(gpio_t* gpiox, uint8_t gpio_pin, gpio_level_t level)
{
assert_param(IS_GPIO_PIN(gpiox, gpio_pin));

if (level != GPIO_LEVEL_LOW)
gpiox->BSR |= 1 << gpio_pin;
else
gpiox->BRR |= 1 << gpio_pin;
if (gpiox == GPIOD && gpio_pin > GPIO_PIN_7) {
if (((gpiox->ODR & (1 << gpio_pin)) == 0 ) && ((gpiox->IER & (1 << gpio_pin)) == 0 ) \
&& ((gpiox->OER & (1 << gpio_pin)) != 0) && ((gpiox->PSR & (1 << gpio_pin)) != 0)) {
if (level == GPIO_LEVEL_LOW) {
gpiox->ODR &= ~(1 << gpio_pin);
gpiox->IER &= ~(1 << gpio_pin);
gpiox->OER &= ~(1 << gpio_pin);
gpiox->PSR |= (1 << gpio_pin);
}
} else if (((gpiox->ODR & (1 << gpio_pin)) == 0 ) && ((gpiox->IER & (1 << gpio_pin)) == 0 ) && \
((gpiox->OER & (1 << gpio_pin)) == 0) && ((gpiox->PSR & (1 << gpio_pin)) != 0)) {
if (level != GPIO_LEVEL_LOW) {
gpiox->ODR &= ~(1 << gpio_pin);
gpiox->IER &= ~(1 << gpio_pin);
gpiox->OER |= (1 << gpio_pin);
gpiox->PSR |= (1 << gpio_pin);
}
} else {
if (level != GPIO_LEVEL_LOW)
gpiox->BSR |= 1 << gpio_pin;
else
gpiox->BRR |= 1 << gpio_pin;
}
} else {
if (level != GPIO_LEVEL_LOW)
gpiox->BSR |= 1 << gpio_pin;
else
gpiox->BRR |= 1 << gpio_pin;
}
}

/**
Expand Down
8 changes: 3 additions & 5 deletions Drivers/peripheral/src/tremo_lpuart.c
Original file line number Diff line number Diff line change
Expand Up @@ -217,12 +217,10 @@ void lpuart_init(lpuart_t* lpuart, lpuart_init_t* uart_init)
uint32_t freq = 0;

lpuart_clk_freq = rcc_get_lpuart_clk_source();
if (lpuart_clk_freq == RCC_CR1_LPUART_CLK_SEL_XO32K) {
freq = 32768;
} else if (lpuart_clk_freq == RCC_CR1_LPUART_CLK_SEL_RCO32K) {
freq = 32000;
if (lpuart_clk_freq == RCC_CR1_LPUART_CLK_SEL_XO32K || lpuart_clk_freq == RCC_CR1_LPUART_CLK_SEL_RCO32K) {
freq = RCC_FREQ_32768;
} else {
freq = 4000000;
freq = RCC_FREQ_4M;
}
if (uart_init->low_level_wakeup == true) {
tmp_value |= LPUART_CR0_LOW_LEVEL_WAKEUP;
Expand Down
2 changes: 2 additions & 0 deletions Drivers/peripheral/src/tremo_pwr.c
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,8 @@

void deepsleep(uint32_t mode, uint32_t wfi)
{
PWR->CR1 |= 1<<4;

if((TREMO_REG_RD(0x10002010) & 0x3) == 0)
TREMO_REG_SET(PWR->CR1, (0xF<<20), (1<<20));

Expand Down
37 changes: 31 additions & 6 deletions Drivers/peripheral/src/tremo_rcc.c
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
#include "tremo_delay.h"
#include "tremo_rcc.h"

/**
Expand All @@ -17,10 +18,7 @@ uint32_t rcc_get_clk_freq(rcc_clk_t clk)
sysclk_freq = RCC_FREQ_48M;
break;
}
case RCC_CR0_SYSCLK_SEL_RCO32K: {
sysclk_freq = RCC_FREQ_32000;
break;
}
case RCC_CR0_SYSCLK_SEL_RCO32K:
case RCC_CR0_SYSCLK_SEL_XO32K: {
sysclk_freq = RCC_FREQ_32768;
break;
Expand Down Expand Up @@ -328,6 +326,7 @@ void rcc_set_lptimer0_clk_source(rcc_lptimer0_clk_source_t clk_source)
if (clk_source == RCC_LPTIMER0_CLK_SOURCE_EXTCLK) {
TREMO_REG_EN(RCC->CR1, RCC_CR1_LPTIMER0_EXTCLK_SEL_MASK, true);
} else {
TREMO_REG_EN(RCC->CR1, RCC_CR1_LPTIMER0_EXTCLK_SEL_MASK, false);
TREMO_REG_SET(RCC->CR1, RCC_CR1_LPTIMER0_CLK_SEL_MASK, clk_source);
}
}
Expand All @@ -354,6 +353,7 @@ void rcc_set_lptimer1_clk_source(rcc_lptimer1_clk_source_t clk_source)
if (clk_source == RCC_LPTIMER1_CLK_SOURCE_EXTCLK) {
TREMO_REG_EN(RCC->CR1, RCC_CR1_LPTIMER1_EXTCLK_SEL_MASK, true);
} else {
TREMO_REG_EN(RCC->CR1, RCC_CR1_LPTIMER1_EXTCLK_SEL_MASK, false);
TREMO_REG_SET(RCC->CR1, RCC_CR1_LPTIMER1_CLK_SEL_MASK, clk_source);
}
}
Expand Down Expand Up @@ -812,6 +812,8 @@ void rcc_enable_peripheral_clk(rcc_peripheral_t peripheral, bool new_state)
while ((RCC->SR & RCC_SR_ALL_DONE) != RCC_SR_ALL_DONE)
;
TREMO_REG_EN(RCC->CGR2, RCC_CGR2_LPUART_AON_CLK_EN_MASK, new_state);
while ((RCC->SR & RCC_SR_LPUART_AON_CLK_EN_DONE) != RCC_SR_LPUART_AON_CLK_EN_DONE)
;
break;
}
case RCC_PERIPHERAL_SSP0: {
Expand Down Expand Up @@ -860,6 +862,8 @@ void rcc_enable_peripheral_clk(rcc_peripheral_t peripheral, bool new_state)
while ((RCC->SR & RCC_SR_ALL_DONE) != RCC_SR_ALL_DONE)
;
TREMO_REG_EN(RCC->CGR2, RCC_CGR2_LCD_AON_CLK_EN_MASK, new_state);
while ((RCC->SR & RCC_SR_LCD_AON_CLK_EN_DONE) != RCC_SR_LCD_AON_CLK_EN_DONE)
;
break;
}
case RCC_PERIPHERAL_LORA: {
Expand Down Expand Up @@ -913,6 +917,8 @@ void rcc_enable_peripheral_clk(rcc_peripheral_t peripheral, bool new_state)
while ((RCC->SR & RCC_SR_ALL_DONE) != RCC_SR_ALL_DONE)
;
TREMO_REG_EN(RCC->CGR2, RCC_CGR2_LPTIMER0_AON_CLK_EN_MASK, new_state);
while ((RCC->SR & RCC_SR_LPTIM_AON_CLK_EN_DONE) != RCC_SR_LPTIM_AON_CLK_EN_DONE)
;

TREMO_REG_EN(RCC->CGR1, RCC_CGR1_LPTIMER0_CLK_EN_MASK, new_state);
} else {
Expand All @@ -921,8 +927,10 @@ void rcc_enable_peripheral_clk(rcc_peripheral_t peripheral, bool new_state)
while ((RCC->SR & RCC_SR_ALL_DONE) != RCC_SR_ALL_DONE)
;
TREMO_REG_EN(RCC->CGR2, RCC_CGR2_LPTIMER0_AON_CLK_EN_MASK, new_state);
while ((RCC->SR & RCC_SR_LPTIM_AON_CLK_EN_DONE) != RCC_SR_LPTIM_AON_CLK_EN_DONE)
;

TREMO_REG_EN(RCC->CGR1, RCC_CGR1_LPTIMER0_PCLK_EN_MASK, new_state);
//TREMO_REG_EN(RCC->CGR1, RCC_CGR1_LPTIMER0_PCLK_EN_MASK, new_state);
}

break;
Expand All @@ -935,6 +943,8 @@ void rcc_enable_peripheral_clk(rcc_peripheral_t peripheral, bool new_state)
while ((RCC->SR & RCC_SR_ALL_DONE) != RCC_SR_ALL_DONE)
;
TREMO_REG_EN(RCC->CGR2, RCC_CGR2_LPTIMER1_AON_CLK_EN_MASK, new_state);
while ((RCC->SR & RCC_SR_LPTIMER1_AON_CLK_EN_DONE) != RCC_SR_LPTIMER1_AON_CLK_EN_DONE)
;

TREMO_REG_EN(RCC->CGR1, RCC_CGR1_LPTIMER1_CLK_EN_MASK, new_state);
} else {
Expand All @@ -943,8 +953,10 @@ void rcc_enable_peripheral_clk(rcc_peripheral_t peripheral, bool new_state)
while ((RCC->SR & RCC_SR_ALL_DONE) != RCC_SR_ALL_DONE)
;
TREMO_REG_EN(RCC->CGR2, RCC_CGR2_LPTIMER1_AON_CLK_EN_MASK, new_state);
while ((RCC->SR & RCC_SR_LPTIMER1_AON_CLK_EN_DONE) != RCC_SR_LPTIMER1_AON_CLK_EN_DONE)
;

TREMO_REG_EN(RCC->CGR1, RCC_CGR1_LPTIMER1_PCLK_EN_MASK, new_state);
//TREMO_REG_EN(RCC->CGR1, RCC_CGR1_LPTIMER1_PCLK_EN_MASK, new_state);
}

break;
Expand All @@ -955,6 +967,8 @@ void rcc_enable_peripheral_clk(rcc_peripheral_t peripheral, bool new_state)
while ((RCC->SR & RCC_SR_ALL_DONE) != RCC_SR_ALL_DONE)
;
TREMO_REG_EN(RCC->CGR2, RCC_CGR2_IWDG_CLK_EN_MASK, new_state);
while ((RCC->SR & RCC_SR_IWDG_AON_CLK_EN_DONE) != RCC_SR_IWDG_AON_CLK_EN_DONE)
;

break;
}
Expand All @@ -969,6 +983,8 @@ void rcc_enable_peripheral_clk(rcc_peripheral_t peripheral, bool new_state)
while ((RCC->SR & RCC_SR_ALL_DONE) != RCC_SR_ALL_DONE)
;
TREMO_REG_EN(RCC->CGR2, RCC_CGR2_RTC_AON_CLK_EN_MASK, new_state);
while ((RCC->SR & RCC_SR_RTC_AON_CLK_EN_DONE) != RCC_SR_RTC_AON_CLK_EN_DONE)
;
break;
}
case RCC_PERIPHERAL_CRC: {
Expand Down Expand Up @@ -1085,6 +1101,15 @@ void rcc_rst_peripheral(rcc_peripheral_t peripheral, bool new_state)

TREMO_REG_EN(RCC->RST0, 1 << pos, !new_state);
}

if((!new_state) && (peripheral == RCC_PERIPHERAL_LPTIMER1 ||
peripheral == RCC_PERIPHERAL_LPTIMER0 ||
peripheral == RCC_PERIPHERAL_LCD ||
peripheral == RCC_PERIPHERAL_RTC ||
peripheral == RCC_PERIPHERAL_IWDG ||
peripheral == RCC_PERIPHERAL_LPUART)) {
delay_us(92);
}
}

/**
Expand Down
14 changes: 3 additions & 11 deletions Drivers/peripheral/src/tremo_rtc.c
Original file line number Diff line number Diff line change
Expand Up @@ -445,7 +445,7 @@ void rtc_get_calendar(rtc_calendar_t* rtc_calendar)
uint32_t syn_data_h;
uint8_t temp;
uint16_t subsecond_cnt;
float subsecond;
float subsecond = 0;

if (rtc_calendar == NULL) {
return;
Expand All @@ -460,11 +460,7 @@ void rtc_get_calendar(rtc_calendar_t* rtc_calendar)
} while (syn_data_h != RTC->CALENDAR_R_H);
} while ((subsecond_cnt != rtc_get_subsecond_cnt()) || subsecond_cnt<1);

if (RCC_RTC_CLK_SOURCE_XO32K == rcc_get_rtc_clk_source()) {
subsecond = ((float)(((float)RTC_MICROSECOND) / 32768) * subsecond_cnt) + 0.5;
} else {
subsecond = ((float)(((float)RTC_MICROSECOND) / 32000) * subsecond_cnt) + 0.5;
}
subsecond = ((float)(((float)RTC_MICROSECOND) / 32768) * subsecond_cnt) + 0.5;
rtc_calendar->subsecond = (uint32_t)subsecond;

temp = syn_data & 0x0F;
Expand Down Expand Up @@ -605,11 +601,7 @@ void rtc_set_alarm(uint8_t alarm_index, rtc_alarm_mask_t* alarm_mask, rtc_calend
return;
}
if (alarm_mask->subsecMask != 0) {
if (RCC_RTC_CLK_SOURCE_XO32K == rcc_get_rtc_clk_source()) {
temp = ((float)(time->subsecond)) / ((float)(((float)RTC_MICROSECOND) / 32768)) + 0.5;
} else {
temp = ((float)(time->subsecond)) / ((float)(((float)RTC_MICROSECOND) / 32000)) + 0.5;
}
temp = ((float)(time->subsecond)) / ((float)(((float)RTC_MICROSECOND) / 32768)) + 0.5;
rtc_check_syn();
*alarm_subsec_reg &= 0xFFFF0000;
rtc_check_syn();
Expand Down
10 changes: 8 additions & 2 deletions Drivers/peripheral/src/tremo_timer.c
Original file line number Diff line number Diff line change
Expand Up @@ -789,8 +789,14 @@ int32_t timer_clear_ocxref(timer_gp_t* TIMERx, timer_clear_ocxref_t* clear_ocxre
*/
void timer_config_pwm(timer_gp_t* TIMERx, timer_oc_init_t* oc_init, timer_init_t* timerx_init, uint8_t channel)
{
if (((oc_init->oc_mode).oc0m_mode != TIMER_OC0M_PWM1) && ((oc_init->oc_mode).oc0m_mode != TIMER_OC0M_PWM2)) {
return;
if ((channel == 0) || (channel == 2)) {
if (((oc_init->oc_mode).oc0m_mode != TIMER_OC0M_PWM1) && ((oc_init->oc_mode).oc0m_mode != TIMER_OC0M_PWM2)) {
return;
}
} else {
if (((oc_init->oc_mode).oc1m_mode != TIMER_OC1M_PWM1) && ((oc_init->oc_mode).oc1m_mode != TIMER_OC1M_PWM2)) {
return;
}
}

timer_config_oc(TIMERx, oc_init, channel);
Expand Down
Loading

0 comments on commit bc58f75

Please sign in to comment.