summaryrefslogtreecommitdiff
path: root/os/arch/aarch32
diff options
context:
space:
mode:
Diffstat (limited to 'os/arch/aarch32')
-rw-r--r--os/arch/aarch32/armv7e_m/stm32f7/system_stm32f7xx.c12
-rw-r--r--os/arch/aarch32/armv7e_m/stm32f769/init.c120
-rw-r--r--os/arch/aarch32/armv7e_m/stm32f769/sys_io.h10
3 files changed, 78 insertions, 64 deletions
diff --git a/os/arch/aarch32/armv7e_m/stm32f7/system_stm32f7xx.c b/os/arch/aarch32/armv7e_m/stm32f7/system_stm32f7xx.c
index bf363777..695a9271 100644
--- a/os/arch/aarch32/armv7e_m/stm32f7/system_stm32f7xx.c
+++ b/os/arch/aarch32/armv7e_m/stm32f7/system_stm32f7xx.c
@@ -47,10 +47,6 @@
#include <config.h>
#include "stm32f7xx.h"
-#if !defined (HSE_VALUE)
- #define HSE_VALUE ((uint32_t)25000000) /*!< Default value of the External oscillator in Hz */
-#endif /* HSE_VALUE */
-
#if !defined (HSI_VALUE)
#define HSI_VALUE ((uint32_t)16000000) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
@@ -122,7 +118,7 @@
is no need to call the 2 first functions listed above, since SystemCoreClock
variable is updated automatically.
*/
- uint32_t SystemCoreClock = 16000000;
+ uint32_t SystemCoreClock = HSI_VALUE;
const uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
const uint8_t APBPrescTable[8] = {0, 0, 0, 0, 1, 2, 3, 4};
@@ -211,7 +207,7 @@ void SystemCoreClockUpdate(void)
SystemCoreClock = HSI_VALUE;
break;
case 0x04: /* HSE used as system clock source */
- SystemCoreClock = HSE_VALUE;
+ SystemCoreClock = CONFIG_BOARD_HSE_CLK;
break;
case 0x08: /* PLL used as system clock source */
@@ -224,7 +220,7 @@ void SystemCoreClockUpdate(void)
if (pllsource != 0)
{
/* HSE used as PLL clock source */
- pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ pllvco = (CONFIG_BOARD_HSE_CLK / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
}
else
{
@@ -233,7 +229,7 @@ void SystemCoreClockUpdate(void)
}
pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2;
- SystemCoreClock = pllvco/pllp;
+ SystemCoreClock = pllvco / pllp;
break;
default:
SystemCoreClock = HSI_VALUE;
diff --git a/os/arch/aarch32/armv7e_m/stm32f769/init.c b/os/arch/aarch32/armv7e_m/stm32f769/init.c
index 571e36e4..bda2c154 100644
--- a/os/arch/aarch32/armv7e_m/stm32f769/init.c
+++ b/os/arch/aarch32/armv7e_m/stm32f769/init.c
@@ -6,22 +6,18 @@
#include <drivers/memory/stm32f7_mpu.h>
#include <drivers/clock/stm32f769_clocks.h>
#include <drivers/clock/stm32f769_clock_control.h>
+#include <drivers/pinctrl/stm32f769_pinctrl.h>
#include <drivers/uart/stm32f7_uart.h>
#include <drivers/uart/uart.h>
+#include <drivers/gpio/gpio.h>
+#include <drivers/gpio/stm32f769_gpio.h>
#include "cortex.h"
struct device mpu;
struct device clkctrl;
struct device usart1;
-
-struct rcc_clk_init {
- uint32_t ClockType;
- uint32_t SYSCLKSource;
- uint32_t AHBCLKDivider;
- uint32_t APB1CLKDivider;
- uint32_t APB2CLKDivider;
-};
+struct device gpioj;
extern volatile uint64_t uptime_ctr;
@@ -40,62 +36,52 @@ static void __cpu_cache_enable(void)
SCB_EnableDCache();
}
-#define __FLASH_ART_ENABLE() sys_set_bit(FLASH->ACR, FLASH_ACR_ARTEN)
-#define __FLASH_PREFETCH_BUFFER_ENABLE() sys_set_bit(FLASH->ACR, FLASH_ACR_PRFTEN)
-#define TICK_INT_PRIORITY 0x0FU
-
-static void __nvic_setpriority(IRQn_Type IRQn, uint32_t PreemptPriority, uint32_t SubPriority)
+void WWDG_IRQHandler(void)
{
- uint32_t prioritygroup = 0x00;
- prioritygroup = NVIC_GetPriorityGrouping();
- NVIC_SetPriority(IRQn, NVIC_EncodePriority(prioritygroup, PreemptPriority, SubPriority));
+ while (1) {
+ }
}
-static void __rcc_get_clock_config(struct rcc_clk_init *clkinit, uint32_t *flash_latency)
+void NMI_Handler(void)
{
- /* Set all possible values for the Clock type parameter --------------------*/
- clkinit->ClockType = RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
-
- /* Get the SYSCLK configuration --------------------------------------------*/
- clkinit->SYSCLKSource = (uint32_t)(RCC->CFGR & RCC_CFGR_SW);
-
- /* Get the HCLK configuration ----------------------------------------------*/
- clkinit->AHBCLKDivider = (uint32_t)(RCC->CFGR & RCC_CFGR_HPRE);
-
- /* Get the APB1 configuration ----------------------------------------------*/
- clkinit->APB1CLKDivider = (uint32_t)(RCC->CFGR & RCC_CFGR_PPRE1);
-
- /* Get the APB2 configuration ----------------------------------------------*/
- clkinit->APB2CLKDivider = (uint32_t)((RCC->CFGR & RCC_CFGR_PPRE2) >> 3);
-
- /* Get the Flash Wait State (Latency) configuration ------------------------*/
- *flash_latency = (uint32_t)(FLASH->ACR & FLASH_ACR_LATENCY);
}
-
-static int __init_tick (uint32_t TickPriority)
+void HardFault_Handler(void)
{
- struct rcc_clk_init clkconfig;
- //uint32_t uwTimclock, uwAPB1Prescaler = 0U;
- uint32_t flash_latency;
-
- /*Configure the TIM6 IRQ priority */
- __nvic_setpriority(SysTick_IRQn, TickPriority, 0U);
+ while (1)
+ {
+ }
+}
- /* Enable the TIM6 global Interrupt */
- NVIC_EnableIRQ(SysTick_IRQn);
+void MemManage_Handler(void)
+{
+ while (1)
+ {
+ }
+}
- /* Get clock configuration */
- __rcc_get_clock_config(&clkconfig, &flash_latency);
+void BusFault_Handler(void)
+{
+ while (1)
+ {
+ }
+}
- uint32_t sys_rate = 0;
- stm32f769_clock_control_get_rate(STM32F769_RCC_SYS_SET_OFFSET, &sys_rate);
+void UsageFault_Handler(void)
+{
+ while (1)
+ {
+ }
+}
- sys_write32(((sys_rate / 1000) - 1) & SysTick_LOAD_RELOAD_Msk, SysTick->LOAD);
- sys_clear_bits(SysTick->CTRL, SysTick_CTRL_CLKSOURCE_Msk | SysTick_CTRL_ENABLE_Msk | SysTick_CTRL_TICKINT_Msk);
+#define __FLASH_ART_ENABLE() SET_BIT(FLASH->ACR, FLASH_ACR_ARTEN)
+#define __FLASH_PREFETCH_BUFFER_ENABLE() SET_BIT(FLASH->ACR, FLASH_ACR_PRFTEN)
- /* Return function status */
- return 0;
+static void __nvic_setpriority(IRQn_Type IRQn, uint32_t PreemptPriority, uint32_t SubPriority)
+{
+ uint32_t prioritygroup = 0x00;
+ prioritygroup = NVIC_GetPriorityGrouping();
+ NVIC_SetPriority(IRQn, NVIC_EncodePriority(prioritygroup, PreemptPriority, SubPriority));
}
void arch_init(void) {
@@ -112,10 +98,13 @@ void arch_init(void) {
#endif /* PREFETCH_ENABLE */
NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4);
- __init_tick(TICK_INT_PRIORITY);
+ stm32f769_init_tick();
- stm32f769_clock_control_init(&clkctrl);
+ if (stm32f769_clock_control_init(&clkctrl) < 0) {
+ while (1) {}
+ }
+ stm32f769_clock_control_on(STM32F769_CLOCK_GPIOA);
stm32f769_clock_control_on(STM32F769_CLOCK_USART1);
struct uart_data u1_data;
@@ -128,12 +117,33 @@ void arch_init(void) {
usart1.devptr = USART1;
usart1.data = &u1_data;
- stm32f7_uart_init(&usart1);
+ stm32f769_pinctrl_configure_pin(STM32F769_PINMUX_AF(STM32F769_PORTA, 9, AF7));
+ stm32f769_pinctrl_configure_pin(STM32F769_PINMUX_AF(STM32F769_PORTA, 10, AF7));
+
+ if (stm32f7_uart_init(&usart1) < 0) {
+ while (1) {
+ }
+ }
+
stm32f7_uart_tx(&usart1, "Start\r\n");
+ gpioj.devptr = GPIOJ;
+ stm32f769_gpio_init(&gpioj);
+ stm32f769_gpio_configure(&gpioj, 13, GPIO_OUTPUT);
+ int stat = 0;
+ uint32_t sys_rate = 0;
+
while (1) {
+ if (stat) {
+ stm32f769_gpio_write(&gpioj, 13, stat);
+ stat = 0;
+ } else {
+ stm32f769_gpio_write(&gpioj, 13, stat);
+ stat = 1;
+ }
stm32f7_uart_tx(&usart1, "Test\r\n");
wait(1000);
+ stm32f769_clock_control_get_rate(STM32F769_CLOCK_SYS, &sys_rate);
}
return;
}
diff --git a/os/arch/aarch32/armv7e_m/stm32f769/sys_io.h b/os/arch/aarch32/armv7e_m/stm32f769/sys_io.h
index 9f70d641..77a33dd1 100644
--- a/os/arch/aarch32/armv7e_m/stm32f769/sys_io.h
+++ b/os/arch/aarch32/armv7e_m/stm32f769/sys_io.h
@@ -10,6 +10,14 @@
#define BIT(x) ((uint32_t)((uint32_t)0x01U<<(x)))
#endif
+#define SET_BIT(r, b) (r |= (b))
+#define CLEAR_BIT(r, b) (r &= ~(b))
+#define READ_BIT(r, b) ((r) & (b))
+#define CLEAR_REG(r) ((r) = (0x0))
+#define WRITE_REG(r, v) ((r) = (v))
+#define READ_REG(r) ((r))
+#define MODIFY_REG(r, clear_mask, set_mask) WRITE_REG((r), (((READ_REG(r)) & (~(clear_mask))) | (set_mask)))
+
static inline uint8_t sys_read8(uint32_t addr)
{
return *(volatile uint8_t *)addr;
@@ -66,7 +74,7 @@ static inline void sys_clear_bit(uint32_t addr, unsigned int bit)
static inline int sys_test_bit(uint32_t addr, unsigned int bit)
{
- uint32_t temp = *(volatile uint32_t *)addr;
+ volatile uint32_t temp = *(volatile uint32_t *)addr;
return temp & (1 << bit);
}