diff --git a/lib/CMSIS/Device/ST/STM32F7xx/Include/stm32f722xx.h b/lib/CMSIS/Device/ST/STM32F7xx/Include/stm32f722xx.h index 92742840..a2fa045c 100644 --- a/lib/CMSIS/Device/ST/STM32F7xx/Include/stm32f722xx.h +++ b/lib/CMSIS/Device/ST/STM32F7xx/Include/stm32f722xx.h @@ -9,7 +9,7 @@ * This file contains: * - Data structures and the address mapping for all peripherals * - Peripheral's registers declarations and bits definition - * - Macros to access peripheral’s registers hardware + * - Macros to access peripheral�s registers hardware * ****************************************************************************** * @attention diff --git a/lib/STM32F0xx_HAL_Driver/Inc/stm32_assert_template.h b/lib/STM32F0xx_HAL_Driver/Inc/stm32_assert_template.h index 1ec32703..cd2bab25 100644 --- a/lib/STM32F0xx_HAL_Driver/Inc/stm32_assert_template.h +++ b/lib/STM32F0xx_HAL_Driver/Inc/stm32_assert_template.h @@ -62,7 +62,9 @@ /* Exported functions ------------------------------------------------------- */ void assert_failed(uint8_t* file, uint32_t line); #else - #define assert_param(expr) ((void)0U) +#ifndef assert_param +#define assert_param(expr) ((void)0U) +#endif #endif /* USE_FULL_ASSERT */ #ifdef __cplusplus diff --git a/lib/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_conf_template.h b/lib/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_conf_template.h index 4c42f155..22520b37 100644 --- a/lib/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_conf_template.h +++ b/lib/STM32F0xx_HAL_Driver/Inc/stm32f0xx_hal_conf_template.h @@ -300,7 +300,9 @@ /* Exported functions ------------------------------------------------------- */ void assert_failed(uint8_t* file, uint32_t line); #else - #define assert_param(expr) ((void)0U) +#ifndef assert_param +#define assert_param(expr) ((void)0U) +#endif #endif /* USE_FULL_ASSERT */ #ifdef __cplusplus diff --git a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_adc.c b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_adc.c index 1818f8b8..bcfc8934 100644 --- a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_adc.c +++ b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_adc.c @@ -43,7 +43,9 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else - #define assert_param(expr) ((void)0U) +#ifndef assert_param +#define assert_param(expr) ((void)0U) +#endif #endif /** @addtogroup STM32F0xx_LL_Driver diff --git a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_comp.c b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_comp.c index e02a5cd7..09438133 100644 --- a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_comp.c +++ b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_comp.c @@ -42,7 +42,9 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else - #define assert_param(expr) ((void)0U) +#ifndef assert_param +#define assert_param(expr) ((void)0U) +#endif #endif /** @addtogroup STM32F0xx_LL_Driver diff --git a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_crc.c b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_crc.c index 482d7aea..4b606d54 100644 --- a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_crc.c +++ b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_crc.c @@ -42,8 +42,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F0xx_LL_Driver * @{ diff --git a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_dac.c b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_dac.c index f647912d..f0efe4d4 100644 --- a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_dac.c +++ b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_dac.c @@ -43,7 +43,9 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else - #define assert_param(expr) ((void)0U) +#ifndef assert_param +#define assert_param(expr) ((void)0U) +#endif #endif /** @addtogroup STM32F0xx_LL_Driver diff --git a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_dma.c b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_dma.c index c142b08d..04c67305 100644 --- a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_dma.c +++ b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_dma.c @@ -42,8 +42,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F0xx_LL_Driver * @{ diff --git a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_exti.c b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_exti.c index b11740c8..5d89221b 100644 --- a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_exti.c +++ b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_exti.c @@ -41,8 +41,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F0xx_LL_Driver * @{ diff --git a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_gpio.c b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_gpio.c index 7f9d5c8c..3fb88660 100644 --- a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_gpio.c +++ b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_gpio.c @@ -42,8 +42,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F0xx_LL_Driver * @{ diff --git a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_i2c.c b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_i2c.c index 84d7691a..003406ac 100644 --- a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_i2c.c +++ b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_i2c.c @@ -42,8 +42,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F0xx_LL_Driver * @{ diff --git a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_rcc.c b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_rcc.c index df2d1ecc..eb112440 100644 --- a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_rcc.c +++ b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_rcc.c @@ -41,7 +41,9 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else - #define assert_param(expr) ((void)0U) +#ifndef assert_param +#define assert_param(expr) ((void)0U) +#endif #endif /* USE_FULL_ASSERT */ /** @addtogroup STM32F0xx_LL_Driver * @{ diff --git a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_rtc.c b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_rtc.c index e43857d9..60fd100e 100644 --- a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_rtc.c +++ b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_rtc.c @@ -42,8 +42,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F0xx_LL_Driver * @{ diff --git a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_spi.c b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_spi.c index bf24ce8c..863634e3 100644 --- a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_spi.c +++ b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_spi.c @@ -44,8 +44,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F0xx_LL_Driver * @{ diff --git a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_tim.c b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_tim.c index a1f2e1ee..2a89e2d5 100644 --- a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_tim.c +++ b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_tim.c @@ -43,8 +43,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F0xx_LL_Driver * @{ diff --git a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_usart.c b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_usart.c index 452f0cf6..41dcf85a 100644 --- a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_usart.c +++ b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_usart.c @@ -43,8 +43,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F0xx_LL_Driver * @{ diff --git a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_utils.c b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_utils.c index d92ae80b..4fa8bfcc 100644 --- a/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_utils.c +++ b/lib/STM32F0xx_HAL_Driver/Src/stm32f0xx_ll_utils.c @@ -41,8 +41,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F0xx_LL_Driver * @{ diff --git a/lib/STM32F3xx_HAL_Driver/Inc/stm32_assert_template.h b/lib/STM32F3xx_HAL_Driver/Inc/stm32_assert_template.h index 1bba96ae..af4d9170 100644 --- a/lib/STM32F3xx_HAL_Driver/Inc/stm32_assert_template.h +++ b/lib/STM32F3xx_HAL_Driver/Inc/stm32_assert_template.h @@ -62,7 +62,9 @@ /* Exported functions ------------------------------------------------------- */ void assert_failed(uint8_t* file, uint32_t line); #else - #define assert_param(expr) ((void)0U) +#ifndef assert_param +#define assert_param(expr) ((void)0U) +#endif #endif /* USE_FULL_ASSERT */ #ifdef __cplusplus diff --git a/lib/STM32F3xx_HAL_Driver/Inc/stm32f3xx_hal_conf_template.h b/lib/STM32F3xx_HAL_Driver/Inc/stm32f3xx_hal_conf_template.h index 2e50b6af..ba65732a 100644 --- a/lib/STM32F3xx_HAL_Driver/Inc/stm32f3xx_hal_conf_template.h +++ b/lib/STM32F3xx_HAL_Driver/Inc/stm32f3xx_hal_conf_template.h @@ -325,7 +325,9 @@ /* Exported functions ------------------------------------------------------- */ void assert_failed(uint8_t* file, uint32_t line); #else - #define assert_param(expr) ((void)0U) +#ifndef assert_param +#define assert_param(expr) ((void)0U) +#endif #endif /* USE_FULL_ASSERT */ #ifdef __cplusplus diff --git a/lib/STM32F7xx_HAL_Driver/Inc/stm32_assert_template.h b/lib/STM32F7xx_HAL_Driver/Inc/stm32_assert_template.h index b08bbd34..b62a9d3d 100644 --- a/lib/STM32F7xx_HAL_Driver/Inc/stm32_assert_template.h +++ b/lib/STM32F7xx_HAL_Driver/Inc/stm32_assert_template.h @@ -62,7 +62,9 @@ /* Exported functions ------------------------------------------------------- */ void assert_failed(uint8_t* file, uint32_t line); #else - #define assert_param(expr) ((void)0U) +#ifndef assert_param +#define assert_param(expr) ((void)0U) +#endif #endif /* USE_FULL_ASSERT */ #ifdef __cplusplus diff --git a/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_adc.h b/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_adc.h index 696628ad..50f20b8b 100644 --- a/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_adc.h +++ b/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_adc.h @@ -4365,6 +4365,7 @@ __STATIC_INLINE void LL_ADC_ClearFlag_AWD1(ADC_TypeDef *ADCx) */ __STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_MST_EOCS(ADC_Common_TypeDef *ADCxy_COMMON) { + (void)(ADCxy_COMMON); return (READ_BIT(ADC1->SR, LL_ADC_FLAG_EOCS) == (LL_ADC_FLAG_EOCS)); } diff --git a/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_crc.h b/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_crc.h index f100cadd..7976da59 100644 --- a/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_crc.h +++ b/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_crc.h @@ -352,10 +352,13 @@ __STATIC_INLINE void LL_CRC_FeedData32(CRC_TypeDef *CRCx, uint32_t InData) * @param InData 16 bit value to be provided to CRC calculator between between Min_Data=0 and Max_Data=0xFFFF * @retval None */ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wstrict-aliasing" __STATIC_INLINE void LL_CRC_FeedData16(CRC_TypeDef *CRCx, uint16_t InData) { *(uint16_t __IO *)(&CRCx->DR) = (uint16_t) InData; } +#pragma GCC diagnostic pop /** * @brief Write given 8-bit data to the CRC calculator diff --git a/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_rcc.h b/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_rcc.h index b3fa6eb9..f3031b12 100644 --- a/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_rcc.h +++ b/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_rcc.h @@ -2757,6 +2757,7 @@ __STATIC_INLINE uint32_t LL_RCC_GetI2CClockSource(uint32_t I2Cx) */ __STATIC_INLINE uint32_t LL_RCC_GetLPTIMClockSource(uint32_t LPTIMx) { + (void)(LPTIMx); return (uint32_t)(READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL)); } diff --git a/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_rtc.h b/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_rtc.h index 417ca4ce..00b5a9ef 100644 --- a/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_rtc.h +++ b/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_rtc.h @@ -2077,6 +2077,7 @@ __STATIC_INLINE void LL_RTC_ALMB_DisableWeekday(RTC_TypeDef *RTCx) */ __STATIC_INLINE void LL_RTC_ALMB_SetDay(RTC_TypeDef *RTCx, uint32_t Day) { + (void)(RTCx); MODIFY_REG(RTC->ALRMBR, (RTC_ALRMBR_DT | RTC_ALRMBR_DU), (((Day & 0xF0U) << (RTC_ALRMBR_DT_Pos - 4U)) | ((Day & 0x0FU) << RTC_ALRMBR_DU_Pos))); } diff --git a/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_spi.h b/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_spi.h index d0b4a208..af711342 100644 --- a/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_spi.h +++ b/lib/STM32F7xx_HAL_Driver/Inc/stm32f7xx_ll_spi.h @@ -1385,10 +1385,13 @@ __STATIC_INLINE void LL_SPI_TransmitData8(SPI_TypeDef *SPIx, uint8_t TxData) * @param TxData Value between Min_Data=0x00 and Max_Data=0xFFFF * @retval None */ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wstrict-aliasing" __STATIC_INLINE void LL_SPI_TransmitData16(SPI_TypeDef *SPIx, uint16_t TxData) { *((__IO uint16_t *)&SPIx->DR) = TxData; } +#pragma GCC diagnostic pop /** * @} diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_crc.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_crc.c index 1e482624..1e9f511d 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_crc.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_crc.c @@ -415,6 +415,8 @@ uint32_t HAL_CRC_Calculate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t * @param BufferLength: input data buffer length * @retval uint32_t CRC (returned value LSBs for CRC shorter than 32 bits) */ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wstrict-aliasing" static uint32_t CRC_Handle_8(CRC_HandleTypeDef *hcrc, uint8_t pBuffer[], uint32_t BufferLength) { uint32_t i = 0; /* input data buffer index */ @@ -475,6 +477,7 @@ static uint32_t CRC_Handle_16(CRC_HandleTypeDef *hcrc, uint16_t pBuffer[], uint3 /* Return the CRC computed value */ return hcrc->Instance->DR; } +#pragma GCC diagnostic pop /** * @} diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pcd.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pcd.c index 9fd5838c..f707a819 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pcd.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pcd.c @@ -1251,9 +1251,9 @@ static HAL_StatusTypeDef PCD_WriteEmptyTxFifo(PCD_HandleTypeDef *hpcd, uint32_t { USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; USB_OTG_EPTypeDef *ep; - int32_t len = 0; - int32_t len32b; - int32_t fifoemptymsk = 0; + uint32_t len = 0; + uint32_t len32b; + uint32_t fifoemptymsk = 0; ep = &hpcd->IN_ep[epnum]; len = ep->xfer_len - ep->xfer_count; diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim.c index 7416ed62..7dc88e88 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim.c @@ -2117,6 +2117,7 @@ __weak void HAL_TIM_OnePulse_MspDeInit(TIM_HandleTypeDef *htim) */ HAL_StatusTypeDef HAL_TIM_OnePulse_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel) { + (void)(OutputChannel); /* Enable the Capture compare and the Input Capture channels (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and @@ -2151,6 +2152,7 @@ HAL_StatusTypeDef HAL_TIM_OnePulse_Start(TIM_HandleTypeDef *htim, uint32_t Outpu */ HAL_StatusTypeDef HAL_TIM_OnePulse_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel) { + (void)(OutputChannel); /* Disable the Capture compare and the Input Capture channels (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and @@ -2185,6 +2187,7 @@ HAL_StatusTypeDef HAL_TIM_OnePulse_Stop(TIM_HandleTypeDef *htim, uint32_t Output */ HAL_StatusTypeDef HAL_TIM_OnePulse_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) { + (void)(OutputChannel); /* Enable the Capture compare and the Input Capture channels (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and @@ -2225,6 +2228,7 @@ HAL_StatusTypeDef HAL_TIM_OnePulse_Start_IT(TIM_HandleTypeDef *htim, uint32_t Ou */ HAL_StatusTypeDef HAL_TIM_OnePulse_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) { + (void)(OutputChannel); /* Disable the TIM Capture/Compare 1 interrupt */ __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_adc.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_adc.c index 653691ab..a7e95e0d 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_adc.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_adc.c @@ -43,7 +43,9 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else - #define assert_param(expr) ((void)0U) + #ifndef assert_param + #define assert_param(expr) ((void)0U) + #endif #endif /** @addtogroup STM32F7xx_LL_Driver @@ -301,6 +303,7 @@ */ ErrorStatus LL_ADC_CommonDeInit(ADC_Common_TypeDef *ADCxy_COMMON) { + (void)(ADCxy_COMMON); /* Check the parameters */ assert_param(IS_ADC_COMMON_INSTANCE(ADCxy_COMMON)); diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_crc.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_crc.c index 7b67999c..1d80b835 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_crc.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_crc.c @@ -43,8 +43,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F7xx_LL_Driver * @{ diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_dac.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_dac.c index fa81ec0b..7f1bf187 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_dac.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_dac.c @@ -43,7 +43,9 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else - #define assert_param(expr) ((void)0U) + #ifndef assert_param + #define assert_param(expr) ((void)0U) + #endif #endif /** @addtogroup STM32F7xx_LL_Driver @@ -146,6 +148,7 @@ */ ErrorStatus LL_DAC_DeInit(DAC_TypeDef *DACx) { + (void)(DACx); /* Check the parameters */ assert_param(IS_DAC_ALL_INSTANCE(DACx)); diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_dma.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_dma.c index c0b1d240..25462ba1 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_dma.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_dma.c @@ -42,8 +42,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F7xx_LL_Driver * @{ diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_dma2d.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_dma2d.c index 4ac3bcf4..e40f29ae 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_dma2d.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_dma2d.c @@ -42,8 +42,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F7xx_LL_Driver * @{ diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_exti.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_exti.c index 9df522df..6293dfcb 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_exti.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_exti.c @@ -41,8 +41,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F7xx_LL_Driver * @{ diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_gpio.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_gpio.c index b37b1d74..c82d4b19 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_gpio.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_gpio.c @@ -42,8 +42,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F7xx_LL_Driver * @{ diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_i2c.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_i2c.c index 83485f8a..d5848111 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_i2c.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_i2c.c @@ -42,8 +42,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F7xx_LL_Driver * @{ diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_lptim.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_lptim.c index 0751157d..74a354ad 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_lptim.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_lptim.c @@ -43,7 +43,9 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else - #define assert_param(expr) ((void)0U) +#ifndef assert_param +#define assert_param(expr) ((void)0U) +#endif #endif /** @addtogroup STM32F7xx_LL_Driver diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_rcc.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_rcc.c index c3e7b836..86ea6676 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_rcc.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_rcc.c @@ -41,7 +41,9 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else - #define assert_param(expr) ((void)0U) +#ifndef assert_param +#define assert_param(expr) ((void)0U) +#endif #endif /** @addtogroup STM32F7xx_LL_Driver diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_rng.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_rng.c index 58f3dbf7..1986ec07 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_rng.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_rng.c @@ -43,8 +43,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F7xx_LL_Driver * @{ @@ -80,6 +82,7 @@ */ ErrorStatus LL_RNG_DeInit(RNG_TypeDef *RNGx) { + (void)(RNGx); /* Check the parameters */ assert_param(IS_RNG_ALL_INSTANCE(RNGx)); diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_rtc.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_rtc.c index 0a367e46..87a6abc6 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_rtc.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_rtc.c @@ -42,8 +42,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F7xx_LL_Driver * @{ diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_spi.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_spi.c index c1f386dc..9528145a 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_spi.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_spi.c @@ -44,8 +44,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F7xx_LL_Driver * @{ diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_tim.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_tim.c index f942a24e..d1f7891c 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_tim.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_tim.c @@ -43,8 +43,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F7xx_LL_Driver * @{ diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_usart.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_usart.c index 34fc2e32..6b0775e8 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_usart.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_usart.c @@ -43,8 +43,10 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) #endif +#endif /** @addtogroup STM32F7xx_LL_Driver * @{ diff --git a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_utils.c b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_utils.c index acc2289a..a10216e6 100644 --- a/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_utils.c +++ b/lib/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_utils.c @@ -42,7 +42,9 @@ #ifdef USE_FULL_ASSERT #include "stm32_assert.h" #else +#ifndef assert_param #define assert_param(expr) ((void)0U) +#endif #endif /* USE_FULL_ASSERT */ /** @addtogroup STM32F7xx_LL_Driver diff --git a/make.py b/make.py index 10510d56..5f13ee4e 100755 --- a/make.py +++ b/make.py @@ -163,6 +163,33 @@ def configure_target(TARGET): FEATURES.extend(["usb_fs"]) OPTIMIZE_FLAGS = "-Og" + elif TARGET == "STRIXF10": + FC_NAME = "STRIXF10" + TARGET_DEVICE_LC = "stm32f722xx" + PROJECT = "flight_controller" + TARGET_DEVICE = "STM32F722xx" + TARGET_SCRIPT = "stm32_flash_f722.ld" + TARGET_PROCESSOR_TYPE = "f7" + FEATURES.extend(["usb_otg_fs"]) + FEATURES.extend(["imuf9001/spi"]) + OPTIMIZE_FLAGS = "-O3" + THIS_ADDRESS = str(0x08020000) + EXTRA_DEF_FLAGS = "" + STM32F7_ARCH_FLAGS_ADD = "" + + elif TARGET == "STRIXF10_nrecovery": + FC_NAME = "STRIXF10" + TARGET_DEVICE_LC = "stm32f722xx" + PROJECT = "new_bootloader" + TARGET_DEVICE = "STM32F722xx" + TARGET_SCRIPT = "stm32_flash_f722_recovery.ld" + TARGET_PROCESSOR_TYPE = "f7" + FEATURES.extend(["usb_otg_fs"]) + OPTIMIZE_FLAGS = "-Os" + THIS_ADDRESS = str(0x08000000) + EXTRA_DEF_FLAGS = "" + STM32F7_ARCH_FLAGS_ADD = "" + elif TARGET == "HELIO_SPRING": if args.debug: os.system("PID=\"$(ps -elf | grep openocd | grep -v 'grep' | sed -e 's/ / /g' | sed -e 's/ / /g' | sed -e 's/ / /g' | cut -d ' ' -f 3)\";kill $PID") @@ -179,7 +206,6 @@ def configure_target(TARGET): THIS_ADDRESS = str(0x08020000) EXTRA_DEF_FLAGS = "" STM32F4_ARCH_FLAGS_ADD = "" - #STM32F4_ARCH_FLAGS_ADD = "-s -fdata-sections -ffunction-sections -flto" elif TARGET == "HELIO_SPRING_nrecovery": if args.debug: @@ -348,13 +374,13 @@ def configure_target(TARGET): STM32F3_ARCH_FLAGS = "-mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16" if TARGET_DEVICE == "STM32F446xx": - STM32F4_DEF_FLAGS = "-DUSE_HAL_DRIVER -DHSE_VALUE=12000000 -D" + FC_NAME +" -D" + TARGET_DEVICE + " -DARM_MATH_CM4 -D" + TARGET + " -D" + TARGET_DEVICE_LC + " -D" + TARGET_PROCESSOR_TYPE + EXTRA_DEF_FLAGS + STM32F4_DEF_FLAGS = "-DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER -DHSE_VALUE=12000000 -D" + FC_NAME +" -D" + TARGET_DEVICE + " -DARM_MATH_CM4 -D" + TARGET + " -D" + TARGET_DEVICE_LC + " -D" + TARGET_PROCESSOR_TYPE + EXTRA_DEF_FLAGS STM32F4_ARCH_FLAGS = "-mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -mtune=cortex-m4" else: - STM32F4_DEF_FLAGS = "-DUSE_HAL_DRIVER -DHSE_VALUE=8000000 -D" + FC_NAME +" -D" + TARGET_DEVICE + " -DARM_MATH_CM4 -D" + TARGET + " -D" + TARGET_DEVICE_LC + " -D" + TARGET_PROCESSOR_TYPE + EXTRA_DEF_FLAGS + STM32F4_DEF_FLAGS = "-DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER -DHSE_VALUE=8000000 -D" + FC_NAME +" -D" + TARGET_DEVICE + " -DARM_MATH_CM4 -D" + TARGET + " -D" + TARGET_DEVICE_LC + " -D" + TARGET_PROCESSOR_TYPE + EXTRA_DEF_FLAGS STM32F4_ARCH_FLAGS = "-mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -mtune=cortex-m4" + " " + STM32F4_ARCH_FLAGS_ADD - STM32F7_DEF_FLAGS = "-DUSE_HAL_DRIVER -DHSE_VALUE=8000000 -D" + FC_NAME +" -D" + TARGET_DEVICE + " -DARM_MATH_CM7 -DUSE_HAL_DRIVER -D__FPU_PRESENT -D" + TARGET + " -D" + TARGET_DEVICE_LC + " -D" + TARGET_PROCESSOR_TYPE + EXTRA_DEF_FLAGS + STM32F7_DEF_FLAGS = "-DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER -DHSE_VALUE=8000000 -D" + FC_NAME +" -D" + TARGET_DEVICE + " -DARM_MATH_CM7 -DUSE_HAL_DRIVER -D__FPU_PRESENT -D" + TARGET + " -D" + TARGET_DEVICE_LC + " -D" + TARGET_PROCESSOR_TYPE + EXTRA_DEF_FLAGS # STM32F7_DEF_FLAGS = "-DUSE_HAL_DRIVER -DHSE_VALUE=8000000 -D" + TARGET_DEVICE + " -DARM_MATH_CM7=1 -D" + TARGET + " -D" + TARGET_DEVICE_LC + " -D" + TARGET_PROCESSOR_TYPE STM32F7_ARCH_FLAGS = "-mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant -mtune=cortex-m7" @@ -404,6 +430,7 @@ def configure_target(TARGET): INCLUDE_DIRS = [ "src/low_level_driver/" + MCU_FAMILY, + "src/low_level_driver/", MCU_DIR, "src/%s/inc" % PROJECT, "lib/CMSIS/Include", diff --git a/src/flight_controller/inc/drivers/serial.h b/src/flight_controller/inc/drivers/serial.h index 59fca674..92212b14 100644 --- a/src/flight_controller/inc/drivers/serial.h +++ b/src/flight_controller/inc/drivers/serial.h @@ -3,6 +3,9 @@ extern uint32_t lastRXPacket; extern volatile int32_t processRxCodeNow; +extern uint8_t uartRxBuffer[MAX_USARTS][RXBUFFERSIZE]; +extern uint8_t serialBuffer[]; +extern uint32_t iiiii; unsigned char txTransimissionReady; @@ -16,4 +19,5 @@ extern void USARTx_DMA_RX_IRQHandler(void); extern void USARTx_DMA_TX_IRQHandler(void); extern void USARTx_IRQHandler(void); extern void SerialTxCallback(uint32_t callbackNumber); -extern void ProcessSerialRx(void); \ No newline at end of file +extern void ProcessSerialRx(void); +extern void UsartIrqCallback(uint32_t serialNumber); \ No newline at end of file diff --git a/src/flight_controller/inc/includes.h b/src/flight_controller/inc/includes.h index 2cbb65b5..bcf603fd 100644 --- a/src/flight_controller/inc/includes.h +++ b/src/flight_controller/inc/includes.h @@ -18,7 +18,7 @@ extern volatile int retValChk; #include "usb_device.h" //low level drivers and driver based functions -#include "../../low_level_driver/boarddef.h" +#include "boarddef.h" #include "mcu_include.h" #include "general_functions.h" #include "exti.h" diff --git a/src/flight_controller/src/config.c b/src/flight_controller/src/config.c index eceb4974..b3cd2302 100644 --- a/src/flight_controller/src/config.c +++ b/src/flight_controller/src/config.c @@ -210,7 +210,6 @@ const config_variables_rec valueTable[] = { { "man_gy_yaw_angle", typeFLOAT, "gyro", &mainConfig.gyroConfig.minorBoardRotation[Z], -360.0f, 360.0f, 0, "" }, { "imuf_filter_mode", typeUINT, "gyro", &mainConfig.gyroConfig.imufMode, 0, 255, GTBCM_DEFAULT, "" }, - { "rf_loop_ctrl", typeUINT, "gyro", &mainConfig.gyroConfig.loopCtrl, 0, LOOP_UH32, LOOP_UH32, "" }, { "drunk", typeINT, "gyro", &mainConfig.gyroConfig.drunk, 0, 2, 1, "" }, { "skunk", typeINT, "gyro", &mainConfig.gyroConfig.skunk, 0, 2, 2, "" }, @@ -248,9 +247,9 @@ const config_variables_rec valueTable[] = { { "sld1", typeFLOAT, "pids", &mainConfig.tuneProfile[0].pidConfig[PITCH].sld, 0, 0.90, 0.03, "" }, { "res_redux1", typeINT, "filt", &mainConfig.tuneProfile[0].filterConfig[0].resRedux, 0, 1, 0, "" }, - { "yaw_rap1", typeUINT, "filt", &mainConfig.tuneProfile[0].filterConfig[YAW].gyro.w, 0, 300, 6.0f, "" }, - { "roll_rap1", typeUINT, "filt", &mainConfig.tuneProfile[0].filterConfig[ROLL].gyro.w, 0, 300, 6.0f, "" }, - { "pitch_rap1", typeUINT, "filt", &mainConfig.tuneProfile[0].filterConfig[PITCH].gyro.w, 0, 300, 6.0f, "" }, + { "yaw_rap1", typeUINT, "filt", &mainConfig.tuneProfile[0].filterConfig[YAW].gyro.w, 0, 300, 32.0f, "" }, + { "roll_rap1", typeUINT, "filt", &mainConfig.tuneProfile[0].filterConfig[ROLL].gyro.w, 0, 300, 32.0f, "" }, + { "pitch_rap1", typeUINT, "filt", &mainConfig.tuneProfile[0].filterConfig[PITCH].gyro.w, 0, 300, 32.0f, "" }, { "yaw_lpf1", typeFLOAT, "filt", &mainConfig.tuneProfile[0].filterConfig[YAW].gyro.lpf, 0, 1000, 150.0f, "" }, { "roll_lpf1", typeFLOAT, "filt", &mainConfig.tuneProfile[0].filterConfig[ROLL].gyro.lpf, 0, 1000, 150.0f, "" }, { "pitch_lpf1", typeFLOAT, "filt", &mainConfig.tuneProfile[0].filterConfig[PITCH].gyro.lpf, 0, 1000, 150.0f, "" }, @@ -309,9 +308,9 @@ const config_variables_rec valueTable[] = { { "sld2", typeFLOAT, "pids", &mainConfig.tuneProfile[1].pidConfig[PITCH].sld, 0, 0.90, 0.03, "" }, { "res_redux2", typeINT, "filt", &mainConfig.tuneProfile[1].filterConfig[0].resRedux, 0, 1, 0, "" }, - { "yaw_rap2", typeUINT, "filt", &mainConfig.tuneProfile[1].filterConfig[YAW].gyro.w, 0, 300, 10.0f, "" }, - { "roll_rap2", typeUINT, "filt", &mainConfig.tuneProfile[1].filterConfig[ROLL].gyro.w, 0, 300, 10.0f, "" }, - { "pitch_rap2", typeUINT, "filt", &mainConfig.tuneProfile[1].filterConfig[PITCH].gyro.w, 0, 300, 10.0f, "" }, + { "yaw_rap2", typeUINT, "filt", &mainConfig.tuneProfile[1].filterConfig[YAW].gyro.w, 0, 300, 32.0f, "" }, + { "roll_rap2", typeUINT, "filt", &mainConfig.tuneProfile[1].filterConfig[ROLL].gyro.w, 0, 300, 32.0f, "" }, + { "pitch_rap2", typeUINT, "filt", &mainConfig.tuneProfile[1].filterConfig[PITCH].gyro.w, 0, 300, 32.0f, "" }, { "yaw_lpf2", typeFLOAT, "filt", &mainConfig.tuneProfile[1].filterConfig[YAW].gyro.lpf, 0, 1000, 150.0f, "" }, { "roll_lpf2", typeFLOAT, "filt", &mainConfig.tuneProfile[1].filterConfig[ROLL].gyro.lpf, 0, 1000, 150.0f, "" }, { "pitch_lpf2", typeFLOAT, "filt", &mainConfig.tuneProfile[1].filterConfig[PITCH].gyro.lpf, 0, 1000, 150.0f, "" }, @@ -371,9 +370,9 @@ const config_variables_rec valueTable[] = { { "sld3", typeFLOAT, "pids", &mainConfig.tuneProfile[2].pidConfig[PITCH].sld, 0, 0.90, 0.03, "" }, { "res_redux3", typeINT, "filt", &mainConfig.tuneProfile[2].filterConfig[0].resRedux, 0, 1, 0, "" }, - { "yaw_rap3", typeUINT, "filt", &mainConfig.tuneProfile[2].filterConfig[YAW].gyro.w, 0, 300, 10.0f, "" }, - { "roll_rap3", typeUINT, "filt", &mainConfig.tuneProfile[2].filterConfig[ROLL].gyro.w, 0, 300, 10.0f, "" }, - { "pitch_rap3", typeUINT, "filt", &mainConfig.tuneProfile[2].filterConfig[PITCH].gyro.w, 0, 300, 10.0f, "" }, + { "yaw_rap3", typeUINT, "filt", &mainConfig.tuneProfile[2].filterConfig[YAW].gyro.w, 0, 300, 32.0f, "" }, + { "roll_rap3", typeUINT, "filt", &mainConfig.tuneProfile[2].filterConfig[ROLL].gyro.w, 0, 300, 32.0f, "" }, + { "pitch_rap3", typeUINT, "filt", &mainConfig.tuneProfile[2].filterConfig[PITCH].gyro.w, 0, 300, 32.0f, "" }, { "yaw_lpf3", typeFLOAT, "filt", &mainConfig.tuneProfile[2].filterConfig[YAW].gyro.lpf, 0, 1000, 150.0f, "" }, { "roll_lpf3", typeFLOAT, "filt", &mainConfig.tuneProfile[2].filterConfig[ROLL].gyro.lpf, 0, 1000, 150.0f, "" }, { "pitch_lpf3", typeFLOAT, "filt", &mainConfig.tuneProfile[2].filterConfig[PITCH].gyro.lpf, 0, 1000, 150.0f, "" }, diff --git a/src/flight_controller/src/drivers/adc.c b/src/flight_controller/src/drivers/adc.c index 90797fff..ad0c377f 100644 --- a/src/flight_controller/src/drivers/adc.c +++ b/src/flight_controller/src/drivers/adc.c @@ -1,4 +1,5 @@ #include "includes.h" +#include "stm32f722xx.h" #define CHARGED_VOLTAGE 4.0 #define RUNNING_VOLTAGE 3.80 @@ -210,7 +211,7 @@ void InitAdc(void) HAL_GPIO_Init(ports[board.boardADC[0].port], &gpioInit); //##-1- Configure the ADC peripheral ####################################### - adcHandle[board.boardADC[1].adcHandle].Instance = adcInstance[board.boardADC[1].adcInstance]; + adcHandle[board.boardADC[1].adcHandle].Instance = ADC3; adcHandle[board.boardADC[1].adcHandle].Init.ClockPrescaler = ADC_CLOCKPRESCALER_PCLK_DIV2; adcHandle[board.boardADC[1].adcHandle].Init.Resolution = ADC_RESOLUTION_12B; adcHandle[board.boardADC[1].adcHandle].Init.ScanConvMode = ENABLE; @@ -271,7 +272,7 @@ void InitAdc(void) board.dmasActive[ENUM_DMA2_STREAM_1].priority = 6; //set DMA handle - dmaHandles[board.dmasActive[ENUM_DMA2_STREAM_1].dmaHandle].Instance = dmaStream[board.dmasActive[ENUM_DMA2_STREAM_1].dmaStream]; + dmaHandles[board.dmasActive[ENUM_DMA2_STREAM_1].dmaHandle].Instance = DMA2_Stream1; dmaHandles[board.dmasActive[ENUM_DMA2_STREAM_1].dmaHandle].Init.Channel = board.dmasActive[ENUM_DMA2_STREAM_1].dmaChannel; dmaHandles[board.dmasActive[ENUM_DMA2_STREAM_1].dmaHandle].Init.Direction = board.dmasActive[ENUM_DMA2_STREAM_1].dmaDirection; dmaHandles[board.dmasActive[ENUM_DMA2_STREAM_1].dmaHandle].Init.PeriphInc = board.dmasActive[ENUM_DMA2_STREAM_1].dmaPeriphInc; diff --git a/src/flight_controller/src/drivers/serial.c b/src/flight_controller/src/drivers/serial.c index 3d9c3420..c29f5dec 100644 --- a/src/flight_controller/src/drivers/serial.c +++ b/src/flight_controller/src/drivers/serial.c @@ -1,22 +1,260 @@ #include "includes.h" -uint8_t dmaRxBuffer[MAX_USARTS] = {0,}; +uint32_t iiiii = 0; +uint8_t serialBuffer[RXBUFFERSIZE] = {0,}; +uint8_t dmaRxBuffer[MAX_USARTS][RXBUFFERSIZE] = {0,}; uint32_t dmaIndex[MAX_USARTS] = {0,}; //todo: change assumption that we have 6 usarts uint32_t dmaTxCallbackToUsartHandle[IRQH_FP_TOT] = { 0 }; volatile int32_t processRxCodeNow = -1; uint32_t lastRXPacket; -void UsartInit(uint32_t serialNumber) +static USART_TypeDef* getUsartFromSerialNumber(uint32_t serialNumber); + + +static inline USART_TypeDef* getUsartFromSerialNumber(uint32_t serialNumber) +{ + switch (serialNumber) + { + case 0: + return USART1; //Should be defined in the target H file + break; + case 1: + return USART2; //Should be defined in the target H file + break; + case 2: + return USART3; //Should be defined in the target H file + break; + case 3: + return UART4; //Should be defined in the target H file + break; + case 4: + return UART5; //Should be defined in the target H file + break; + case 5: + default: + return USART6; //Should be defined in the target H file + break; + } +} + +static void ll_hardware_init(USART_TypeDef *usart, uint32_t irqN, GPIO_TypeDef *txPort, uint32_t txPin, uint32_t txInv, uint8_t txAlt, GPIO_TypeDef *rxPort, uint32_t rxPin, uint32_t rxInv, uint8_t rxAlt, uint32_t baudrate, uint32_t wordlength, uint32_t stopbits, uint32_t parity, uint32_t flow, uint32_t mode) { GPIO_InitTypeDef GPIO_InitStruct; + LL_USART_InitTypeDef USART_InitStruct; + //LL_DMA_InitTypeDef DMA_InitStruct; + + //####################################################################### + //## 1 Configure peripheral GPIO ######################################## + //####################################################################### + if (mode != UART_MODE_RX) + HAL_GPIO_DeInit(txPort, txPin); //no need for TX pin is serial is in RX only mode. + + if (mode != UART_MODE_TX) + HAL_GPIO_DeInit(rxPort, rxPin); + + if (mode != UART_MODE_RX) + GPIO_InitStruct.Pin = txPin; //no need for TX pin is serial is in RX only mode. + + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; + GPIO_InitStruct.Alternate = txAlt; + #ifdef USART_USED_ADVANCED //f0,f3,f7 + GPIO_InitStruct.Pull = (txInv) ? GPIO_PULLDOWN : GPIO_PULLUP; //tx pin inverted or not? + #else + GPIO_InitStruct.Pull = GPIO_PULLUP; + #endif + + // UART TX GPIO pin configuration + if (mode != UART_MODE_RX) + HAL_GPIO_Init(txPort, &GPIO_InitStruct); + + // UART RX GPIO pin configuration + if (mode != UART_MODE_TX) + { + GPIO_InitStruct.Pin = rxPin; + GPIO_InitStruct.Alternate = rxAlt; + #ifdef USART_USED_ADVANCED //f0,f3,f7 + GPIO_InitStruct.Pull = (rxInv) ? GPIO_PULLDOWN : GPIO_PULLUP; //rx pin inverted or not? + #else + GPIO_InitStruct.Pull = GPIO_PULLUP; + #endif + HAL_GPIO_Init(rxPort, &GPIO_InitStruct); + } + //####################################################################### + //## 1 Configure peripheral GPIO ######################################## + //####################################################################### + - uint32_t txPin; - uint32_t rxPin; + + //####################################################################### + //## 2 Configure the UART peripheral #################################### + //####################################################################### + + LL_USART_Disable(usart); + LL_USART_DeInit(usart); + + LL_USART_StructInit(&USART_InitStruct); + USART_InitStruct.BaudRate = baudrate; + USART_InitStruct.DataWidth = wordlength; + USART_InitStruct.StopBits = stopbits; + USART_InitStruct.Parity = parity; + USART_InitStruct.HardwareFlowControl = flow; + USART_InitStruct.TransferDirection = mode; + USART_InitStruct.OverSampling = LL_USART_OVERSAMPLING_16; + LL_USART_Init(usart, &USART_InitStruct); + + // Enable USART and enable interrupt for IDLE line detection + LL_USART_Enable(usart); + + //give USART time to init. + DelayMs(3); + // // Polling USART initialisation + // while((!(LL_USART_IsActiveFlag_TEACK(usart))) || (!(LL_USART_IsActiveFlag_REACK(usart)))) + // { + // //TODO: timeout with error? + // } + + #ifdef USART_USED_ADVANCED //f0,f3,f7 + + if(rxInv) + LL_USART_SetRXPinLevel(usart, LL_USART_RXPIN_LEVEL_INVERTED); + else + LL_USART_SetRXPinLevel(usart, LL_USART_RXPIN_LEVEL_STANDARD); + + if(txInv) + LL_USART_SetTXPinLevel(usart, LL_USART_TXPIN_LEVEL_INVERTED); + else + LL_USART_SetTXPinLevel(usart, LL_USART_TXPIN_LEVEL_STANDARD); + + #endif + + // Clear Overrun flag, in case characters have already been sent to USART + LL_USART_ClearFlag_ORE(usart); + + //LL_USART_EnableDMAReq_RX(usart); + //LL_USART_EnableIT_IDLE(usart); + + // Enable RXNE and Error interrupts + LL_USART_EnableIT_RXNE(usart); + //LL_USART_EnableIT_ERROR(usart); + + // Enable USART global interrupts + NVIC_SetPriority(irqN, 1); + NVIC_EnableIRQ(irqN); + + //####################################################################### + //## 2 Configure the UART peripheral #################################### + //####################################################################### + + + // /* Configure DMA for USART RX */ + // LL_DMA_StructInit(&DMA_InitStruct); + // DMA_InitStruct.Channel = LL_DMA_CHANNEL_4; + // DMA_InitStruct.Direction = LL_DMA_DIRECTION_PERIPH_TO_MEMORY; + // DMA_InitStruct.MemoryOrM2MDstAddress = (uint32_t)DMA_RX_Buffer; + // DMA_InitStruct.NbData = DMA_RX_BUFFER_SIZE; + // DMA_InitStruct.MemoryOrM2MDstIncMode = LL_DMA_MEMORY_INCREMENT; + // DMA_InitStruct.PeriphOrM2MSrcAddress = (uint32_t)&USART2->DR; + // LL_DMA_Init(DMA1, LL_DMA_STREAM_5, &DMA_InitStruct); + + // LL_DMA_EnableIT_TC(DMA1, LL_DMA_STREAM_5); + // LL_DMA_EnableStream(DMA1, LL_DMA_STREAM_5); + + // /* Enable global DMA stream interrupts */ + // NVIC_SetPriority(DMA1_Stream5_IRQn, 0); + // NVIC_EnableIRQ(DMA1_Stream5_IRQn); + + // while (1) { + // if (Read != Write) { + // LL_USART_TransmitData8(USART2, UART_Buffer[Read++]); + // while (!LL_USART_IsActiveFlag_TXE(USART2)) {} + // if (Read == UART_BUFFER_SIZE) { + // Read = 0; + // } + // } + // } + +} + +void UsartInit(uint32_t serialNumber) +{ + + uint32_t txPin, rxPin, txAlt, rxAlt, irqN; GPIO_TypeDef *txPort; GPIO_TypeDef *rxPort; + USART_TypeDef *usartToUse; + //fillout USART and PIN settings + switch (serialNumber) + { + case 0: + usartToUse = USART1; //Should be defined in the target H file + txPin = USART1_TXPIN_N; + txPort = USART1_TXPORT_N; + txAlt = USART1_TXALT; + rxPin = USART1_RXPIN_N; + rxPort = USART1_RXPORT_N; + rxAlt = USART1_RXALT; + irqN = USART1_RXTX_IRQn; + break; + case 1: + usartToUse = USART2; //Should be defined in the target H file + txPin = USART2_TXPIN_N; + txPort = USART2_TXPORT_N; + txAlt = USART2_TXALT; + rxPin = USART2_RXPIN_N; + rxPort = USART2_RXPORT_N; + rxAlt = USART2_RXALT; + irqN = USART2_RXTX_IRQn; + break; + case 2: + usartToUse = USART3; //Should be defined in the target H file + txPin = USART3_TXPIN_N; + txPort = USART3_TXPORT_N; + txAlt = USART3_TXALT; + rxPin = USART3_RXPIN_N; + rxPort = USART3_RXPORT_N; + rxAlt = USART3_RXALT; + irqN = USART3_RXTX_IRQn; + break; + case 3: + usartToUse = UART4; //Should be defined in the target H file + txPin = USART4_TXPIN_N; + txPort = USART4_TXPORT_N; + txAlt = USART4_TXALT; + rxPin = USART4_RXPIN_N; + rxPort = USART4_RXPORT_N; + rxAlt = USART4_RXALT; + irqN = USART4_RXTX_IRQn; + break; + case 4: + usartToUse = UART5; //Should be defined in the target H file + txPin = USART5_TXPIN_N; + txPort = USART5_TXPORT_N; + txAlt = USART5_TXALT; + rxPin = USART5_RXPIN_N; + rxPort = USART5_RXPORT_N; + rxAlt = USART5_RXALT; + irqN = USART5_RXTX_IRQn; + break; + case 5: + usartToUse = USART6; //Should be defined in the target H file + txPin = USART6_TXPIN_N; + txPort = USART6_TXPORT_N; + txAlt = USART6_TXALT; + rxPin = USART6_RXPIN_N; + rxPort = USART6_RXPORT_N; + rxAlt = USART6_RXALT; + irqN = USART6_RXTX_IRQn; + break; + default: + //no usart exist!!!! + return; + } + + //init serial based on protocol switch (board.serials[serialNumber].Protocol) { case USING_SPEK_R: @@ -28,10 +266,6 @@ void UsartInit(uint32_t serialNumber) board.serials[serialNumber].Parity = UART_PARITY_NONE; board.serials[serialNumber].HwFlowCtl = UART_HWCONTROL_NONE; board.serials[serialNumber].Mode = UART_MODE_TX_RX; - txPin = board.serials[serialNumber].TXPin; - rxPin = board.serials[serialNumber].RXPin; - txPort = ports[board.serials[serialNumber].TXPort]; - rxPort = ports[board.serials[serialNumber].RXPort]; break; case USING_SPEK_T: case USING_DSM2_T: @@ -42,62 +276,24 @@ void UsartInit(uint32_t serialNumber) board.serials[serialNumber].Parity = UART_PARITY_NONE; board.serials[serialNumber].HwFlowCtl = UART_HWCONTROL_NONE; board.serials[serialNumber].Mode = UART_MODE_TX_RX; - txPin = board.serials[serialNumber].TXPin; - rxPin = board.serials[serialNumber].TXPin; - txPort = ports[board.serials[serialNumber].TXPort]; - rxPort = ports[board.serials[serialNumber].TXPort]; break; case USING_SBUS_R: + ll_hardware_init(usartToUse, irqN, txPort, txPin, 1, txAlt, rxPort, rxPin, 1, rxAlt, 100000, LL_USART_DATAWIDTH_8B, LL_USART_STOPBITS_2, LL_USART_PARITY_EVEN, LL_USART_HWCONTROL_NONE, LL_USART_DIRECTION_RX); board.serials[serialNumber].FrameSize = 25; - board.serials[serialNumber].BaudRate = 100000; - board.serials[serialNumber].WordLength = UART_WORDLENGTH_8B; - board.serials[serialNumber].StopBits = UART_STOPBITS_2; - board.serials[serialNumber].Parity = UART_PARITY_EVEN; - board.serials[serialNumber].HwFlowCtl = UART_HWCONTROL_NONE; - board.serials[serialNumber].Mode = UART_MODE_RX; //sbus only has input, TX is handled via soft serial - txPin = board.serials[serialNumber].TXPin; - rxPin = board.serials[serialNumber].RXPin; - txPort = ports[board.serials[serialNumber].TXPort]; - rxPort = ports[board.serials[serialNumber].RXPort]; break; case USING_SBUS_T: + //TX AND RX PINS THE SAME since we're using the TX pin as an RX pin. + ll_hardware_init(usartToUse, irqN, txPort, txPin, 1, txAlt, txPort, txPin, 1, txAlt, 100000, LL_USART_DATAWIDTH_8B, LL_USART_STOPBITS_2, LL_USART_PARITY_EVEN, LL_USART_HWCONTROL_NONE, LL_USART_DIRECTION_TX_RX); board.serials[serialNumber].FrameSize = 25; - board.serials[serialNumber].BaudRate = 100000; - board.serials[serialNumber].WordLength = UART_WORDLENGTH_8B; - board.serials[serialNumber].StopBits = UART_STOPBITS_2; - board.serials[serialNumber].Parity = UART_PARITY_EVEN; - board.serials[serialNumber].HwFlowCtl = UART_HWCONTROL_NONE; - board.serials[serialNumber].Mode = UART_MODE_TX_RX; - txPin = board.serials[serialNumber].TXPin; - rxPin = board.serials[serialNumber].TXPin; - txPort = ports[board.serials[serialNumber].TXPort]; - rxPort = ports[board.serials[serialNumber].TXPort]; break; case USING_SUMD_R: + ll_hardware_init(usartToUse, irqN, txPort, txPin, 0, txAlt, rxPort, rxPin, 0, rxAlt, 115200, LL_USART_DATAWIDTH_8B, LL_USART_STOPBITS_1, LL_USART_PARITY_NONE, LL_USART_HWCONTROL_NONE, LL_USART_DIRECTION_RX); board.serials[serialNumber].FrameSize = 21; //variable packet size. Will be set based on data - board.serials[serialNumber].BaudRate = 115200; - board.serials[serialNumber].WordLength = UART_WORDLENGTH_8B; - board.serials[serialNumber].StopBits = UART_STOPBITS_1; - board.serials[serialNumber].Parity = UART_PARITY_NONE; - board.serials[serialNumber].HwFlowCtl = UART_HWCONTROL_NONE; - board.serials[serialNumber].Mode = UART_MODE_RX; - txPin = board.serials[serialNumber].TXPin; - rxPin = board.serials[serialNumber].RXPin; - txPort = ports[board.serials[serialNumber].TXPort]; - rxPort = ports[board.serials[serialNumber].RXPort]; break; case USING_SUMD_T: + //TX AND RX PINS THE SAME since we're using the TX pin as an RX pin. + ll_hardware_init(usartToUse, irqN, txPort, txPin, 0, txAlt, txPort, txPin, 0, txAlt, 115200, LL_USART_DATAWIDTH_8B, LL_USART_STOPBITS_1, LL_USART_PARITY_NONE, LL_USART_HWCONTROL_NONE, LL_USART_DIRECTION_TX_RX); board.serials[serialNumber].FrameSize = 21; //variable packet size. Will be set based on data - board.serials[serialNumber].BaudRate = 115200; - board.serials[serialNumber].WordLength = UART_WORDLENGTH_8B; - board.serials[serialNumber].StopBits = UART_STOPBITS_1; - board.serials[serialNumber].Parity = UART_PARITY_NONE; - board.serials[serialNumber].HwFlowCtl = UART_HWCONTROL_NONE; - board.serials[serialNumber].Mode = UART_MODE_TX_RX; - txPin = board.serials[serialNumber].TXPin; - rxPin = board.serials[serialNumber].TXPin; - txPort = ports[board.serials[serialNumber].TXPort]; - rxPort = ports[board.serials[serialNumber].TXPort]; break; case USING_IBUS_T: board.serials[serialNumber].FrameSize = 32; @@ -107,10 +303,6 @@ void UsartInit(uint32_t serialNumber) board.serials[serialNumber].Parity = UART_PARITY_NONE; board.serials[serialNumber].HwFlowCtl = UART_HWCONTROL_NONE; board.serials[serialNumber].Mode = UART_MODE_TX_RX; - txPin = board.serials[serialNumber].TXPin; - rxPin = board.serials[serialNumber].TXPin; - txPort = ports[board.serials[serialNumber].TXPort]; - rxPort = ports[board.serials[serialNumber].TXPort]; break; case USING_CRSF_R: board.serials[serialNumber].FrameSize = 26; //variable @@ -120,10 +312,6 @@ void UsartInit(uint32_t serialNumber) board.serials[serialNumber].Parity = UART_PARITY_NONE; board.serials[serialNumber].HwFlowCtl = UART_HWCONTROL_NONE; board.serials[serialNumber].Mode = UART_MODE_RX; - txPin = board.serials[serialNumber].TXPin; - rxPin = board.serials[serialNumber].RXPin; - txPort = ports[board.serials[serialNumber].TXPort]; - rxPort = ports[board.serials[serialNumber].RXPort]; break; case USING_CRSF_T: board.serials[serialNumber].FrameSize = 26; //variable @@ -133,10 +321,6 @@ void UsartInit(uint32_t serialNumber) board.serials[serialNumber].Parity = UART_PARITY_NONE; board.serials[serialNumber].HwFlowCtl = UART_HWCONTROL_NONE; board.serials[serialNumber].Mode = UART_MODE_TX_RX; - txPin = board.serials[serialNumber].TXPin; - rxPin = board.serials[serialNumber].TXPin; - txPort = ports[board.serials[serialNumber].TXPort]; - rxPort = ports[board.serials[serialNumber].TXPort]; break; case USING_CRSF_TELEM: board.serials[serialNumber].FrameSize = 26; //variable @@ -146,10 +330,6 @@ void UsartInit(uint32_t serialNumber) board.serials[serialNumber].Parity = UART_PARITY_NONE; board.serials[serialNumber].HwFlowCtl = UART_HWCONTROL_NONE; board.serials[serialNumber].Mode = UART_MODE_TX; - txPin = board.serials[serialNumber].TXPin; - rxPin = board.serials[serialNumber].TXPin; - txPort = ports[board.serials[serialNumber].TXPort]; - rxPort = ports[board.serials[serialNumber].TXPort]; break; case USING_CRSF_B: board.serials[serialNumber].FrameSize = 26; //variable @@ -159,10 +339,6 @@ void UsartInit(uint32_t serialNumber) board.serials[serialNumber].Parity = UART_PARITY_NONE; board.serials[serialNumber].HwFlowCtl = UART_HWCONTROL_NONE; board.serials[serialNumber].Mode = UART_MODE_TX_RX; - txPin = board.serials[serialNumber].TXPin; - rxPin = board.serials[serialNumber].RXPin; - txPort = ports[board.serials[serialNumber].TXPort]; - rxPort = ports[board.serials[serialNumber].RXPort]; break; case USING_IBUS_R: board.serials[serialNumber].FrameSize = 32; @@ -172,10 +348,6 @@ void UsartInit(uint32_t serialNumber) board.serials[serialNumber].Parity = UART_PARITY_NONE; board.serials[serialNumber].HwFlowCtl = UART_HWCONTROL_NONE; board.serials[serialNumber].Mode = UART_MODE_RX; - txPin = board.serials[serialNumber].TXPin; - rxPin = board.serials[serialNumber].RXPin; - txPort = ports[board.serials[serialNumber].TXPort]; - rxPort = ports[board.serials[serialNumber].RXPort]; break; case USING_TRAMP: board.serials[serialNumber].enabled = 1; @@ -186,12 +358,6 @@ void UsartInit(uint32_t serialNumber) board.serials[serialNumber].Parity = UART_PARITY_NONE; board.serials[serialNumber].HwFlowCtl = UART_HWCONTROL_NONE; board.serials[serialNumber].Mode = UART_MODE_TX_RX; - board.serials[serialNumber].serialTxInverted = 0; - board.serials[serialNumber].serialRxInverted = 0; - txPin = board.serials[serialNumber].TXPin; - rxPin = board.serials[serialNumber].TXPin; - txPort = ports[board.serials[serialNumber].TXPort]; - rxPort = ports[board.serials[serialNumber].TXPort]; break; case USING_MSP: case USING_RFOSD: @@ -200,98 +366,175 @@ void UsartInit(uint32_t serialNumber) case USING_SMARTAUDIO: case USING_MANUAL: default: - txPin = board.serials[serialNumber].TXPin; - rxPin = board.serials[serialNumber].RXPin; - txPort = ports[board.serials[serialNumber].TXPort]; - rxPort = ports[board.serials[serialNumber].RXPort]; break; } - if ( (serialNumber == 0) && (mainConfig.rcControlsConfig.rxInvertDirection) ) - PowerInveter(ENUM_PORTC, GPIO_PIN_0, mainConfig.rcControlsConfig.rxInvertDirection); - /*##-2- Configure peripheral GPIO ##########################################*/ - if (board.serials[serialNumber].Mode != UART_MODE_RX) - HAL_GPIO_DeInit(txPort, txPin); //no need for TX pin is serial is in RX only mode. + DelayMs(100); + DelayMs(100); + DelayMs(100); + DelayMs(100); + DelayMs(100); + DelayMs(100); + DelayMs(100); + DelayMs(100); + DelayMs(100); + DelayMs(100); + //ll_hardware_init(usartToUse, txPort, txPin, txInv, rxPort, rxPin, rxInv, baudrate, wordlength, stopbits, parity, flow, mode); + //ll_hardware_init(USART_TypeDef *usart, GPIO_TypeDef *txPort, uint32_t txPin, uint32_t txInv, GPIO_TypeDef *rxPort, uint32_t rxPin, uint32_t rxInv, uint32_t baudrate, uint32_t wordlength, uint32_t stopbits, uint32_t parity, uint32_t flow, uint32_t mode ); + //GPIO_TypeDef * + return; + + +// /*##-1- Configure the UART peripheral ######################################*/ +// /* Put the USART peripheral in the Asynchronous mode (UART Mode) */ +// uartHandles[board.serials[serialNumber].usartHandle].Instance = usarts[board.serials[serialNumber].SerialInstance].port; + +// uartHandles[board.serials[serialNumber].usartHandle].Init.BaudRate = board.serials[serialNumber].BaudRate; +// uartHandles[board.serials[serialNumber].usartHandle].Init.WordLength = board.serials[serialNumber].WordLength; +// uartHandles[board.serials[serialNumber].usartHandle].Init.StopBits = board.serials[serialNumber].StopBits; +// uartHandles[board.serials[serialNumber].usartHandle].Init.Parity = board.serials[serialNumber].Parity; +// uartHandles[board.serials[serialNumber].usartHandle].Init.HwFlowCtl = board.serials[serialNumber].HwFlowCtl; +// uartHandles[board.serials[serialNumber].usartHandle].Init.Mode = board.serials[serialNumber].Mode; + +// #ifdef USART_USED_ADVANCED +// //f0, f3, f7 usart advanced features. +// //setup inversion +// uartHandles[board.serials[serialNumber].usartHandle].AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT; +// if (board.serials[serialNumber].serialTxInverted) +// { +// uartHandles[board.serials[serialNumber].usartHandle].AdvancedInit.AdvFeatureInit |= UART_ADVFEATURE_TXINVERT_INIT; +// uartHandles[board.serials[serialNumber].usartHandle].AdvancedInit.TxPinLevelInvert = UART_ADVFEATURE_TXINV_ENABLE; +// } +// if (board.serials[serialNumber].serialRxInverted) +// { +// uartHandles[board.serials[serialNumber].usartHandle].AdvancedInit.AdvFeatureInit |= UART_ADVFEATURE_RXINVERT_INIT; +// uartHandles[board.serials[serialNumber].usartHandle].AdvancedInit.RxPinLevelInvert = UART_ADVFEATURE_RXINV_ENABLE; +// } +// #endif + +// //uartHandle.Init.OverSampling = UART_OVERSAMPLING_16; + + +// //Config uart as half duplex if TX and RX pins are the same +// if ( (txPin == rxPin) && (txPort == rxPort) ) +// { +// if (HAL_HalfDuplex_Init(&uartHandles[board.serials[serialNumber].usartHandle]) != HAL_OK) +// { +// ErrorHandler(SERIAL_HALF_DUPLEX_INIT_FAILURE); +// } +// } +// else +// { +// if(HAL_UART_Init(&uartHandles[board.serials[serialNumber].usartHandle]) != HAL_OK) +// { +// ErrorHandler(SERIAL_INIT_FAILURE); +// } +// } + +// //only enable DMA if the DMA is supposed to be enabled +// if ( (board.dmasSerial[board.serials[serialNumber].TXDma].enabled) || (board.dmasSerial[board.serials[serialNumber].RXDma].enabled)) +// { + +// __HAL_UART_FLUSH_DRREGISTER(&uartHandles[board.serials[serialNumber].usartHandle]); +// UsartDmaInit(serialNumber); +// if (board.serials[serialNumber].Mode != UART_MODE_TX) //need to receive via DMA +// { + + +// if(HAL_UART_Receive(&uartHandles[board.serials[serialNumber].usartHandle], dmaRxBuffer[serialNumber], 20, 50000) != HAL_OK) +// { +// //Error_Handler(); +// } + +// HAL_NVIC_SetPriority(USART2_RXTX_IRQn, 0, 1); +// HAL_NVIC_EnableIRQ(USART2_RXTX_IRQn); +// HAL_UART_Receive_IT(&uartHandles[board.serials[serialNumber].usartHandle], dmaRxBuffer[serialNumber], RXBUFFERSIZE); + +// //HAL_UART_Receive_DMA(&uartHandles[board.serials[serialNumber].usartHandle], dmaRxBuffer[serialNumber], RXBUFFERSIZE); // Start reception +// //HAL_UART_Receive_DMA(&uartHandles[board.serials[serialNumber].usartHandle], dmaRxBuffer[serialNumber], RXBUFFERSIZE); // Start reception +// //HAL_UART_Receive_DMA(&uartHandles[board.serials[serialNumber].usartHandle], dmaRxBuffer[serialNumber], 20); // Start reception +// //__HAL_UART_ENABLE_IT(&uartHandles[board.serials[serialNumber].usartHandle], UART_IT_IDLE); // enable idle line interrupt +// //__HAL_DMA_ENABLE_IT(&dmaHandles[board.dmasActive[board.serials[serialNumber].RXDma].dmaHandle], DMA_IT_TC); // enable DMA Tx cplt interrupt +// //dmaHandles[board.dmasActive[board.serials[serialNumber].RXDma].dmaHandle].Instance->CR &= ~DMA_SxCR_HTIE; // disable uart half tx interrupt + +// } +// } - if (board.serials[serialNumber].Mode != UART_MODE_TX) - HAL_GPIO_DeInit(rxPort, rxPin); +} - /* UART TX GPIO pin configuration */ - if (board.serials[serialNumber].Mode != UART_MODE_RX) - GPIO_InitStruct.Pin = txPin; //no need for TX pin is serial is in RX only mode. +void UsartIrqCallback(uint32_t serialNumber) +{ - GPIO_InitStruct.Mode = board.serials[serialNumber].PinMode; - GPIO_InitStruct.Pull = board.serials[serialNumber].Pull; - GPIO_InitStruct.Speed = board.serials[serialNumber].Speed; - GPIO_InitStruct.Alternate = board.serials[serialNumber].TXAlternate; + volatile uint32_t tmp1, tmp2, tmpIsr, tmpIcr, tmpCr1; + //get the peripheral + USART_TypeDef* usart = getUsartFromSerialNumber(serialNumber); - if (board.serials[serialNumber].Mode != UART_MODE_RX) - HAL_GPIO_Init(txPort, &GPIO_InitStruct); +//0000. 0000. 0100. 0010. 0000 0000 1100 0010 +// 0100 0010 0000 0000 1101 1011 - /* UART RX GPIO pin configuration */ - if (board.serials[serialNumber].Mode != UART_MODE_TX) - { - GPIO_InitStruct.Pin = rxPin; - GPIO_InitStruct.Alternate = board.serials[serialNumber].RXAlternate; +//USART_ISR_FE Framing Error +//USART_ISR_TXE Transmit Data Register Empty +//USART_ISR_LBDF LIN Break Detection Flag - HAL_GPIO_Init(rxPort, &GPIO_InitStruct); - } +//USART_ISR_SBKF Send Break Flag + tmpIsr = usart->ISR; + tmpIcr = usart->ICR; + tmpCr1 = usart->CR1; + if((tmpIsr & USART_ISR_RXNE) == USART_ISR_RXNE) + { + volatile char t = usart->RDR; + serialBuffer[iiiii++] = t; + } - /*##-1- Configure the UART peripheral ######################################*/ - /* Put the USART peripheral in the Asynchronous mode (UART Mode) */ - uartHandles[board.serials[serialNumber].usartHandle].Instance = usarts[board.serials[serialNumber].SerialInstance].port; + if( LL_USART_IsEnabledIT_IDLE(usart) && (tmpIsr & USART_ISR_IDLE) == USART_ISR_IDLE) + { + volatile char f = usart->RDR; + serialBuffer[iiiii++] = f; + iiiii = 0; + } - uartHandles[board.serials[serialNumber].usartHandle].Init.BaudRate = board.serials[serialNumber].BaudRate; - uartHandles[board.serials[serialNumber].usartHandle].Init.WordLength = board.serials[serialNumber].WordLength; - uartHandles[board.serials[serialNumber].usartHandle].Init.StopBits = board.serials[serialNumber].StopBits; - uartHandles[board.serials[serialNumber].usartHandle].Init.Parity = board.serials[serialNumber].Parity; - uartHandles[board.serials[serialNumber].usartHandle].Init.HwFlowCtl = board.serials[serialNumber].HwFlowCtl; - uartHandles[board.serials[serialNumber].usartHandle].Init.Mode = board.serials[serialNumber].Mode; + if((tmpIsr & USART_ISR_ORE) == USART_ISR_ORE) + { + volatile char g = usart->RDR; + serialBuffer[iiiii++] = g; + } -#ifdef USART_USED_ADVANCED - //f0, f3, f7 usart advanced features. - //setup inversion - uartHandles[board.serials[serialNumber].usartHandle].AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT; - if (board.serials[serialNumber].serialTxInverted) - { - uartHandles[board.serials[serialNumber].usartHandle].AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_TXINVERT_INIT; - uartHandles[board.serials[serialNumber].usartHandle].AdvancedInit.TxPinLevelInvert = UART_ADVFEATURE_TXINV_ENABLE; - } - if (board.serials[serialNumber].serialRxInverted) + if(iiiii > 20) { - uartHandles[board.serials[serialNumber].usartHandle].AdvancedInit.AdvFeatureInit = (uartHandles[board.serials[serialNumber].usartHandle].AdvancedInit.AdvFeatureInit | UART_ADVFEATURE_RXINVERT_INIT); - uartHandles[board.serials[serialNumber].usartHandle].AdvancedInit.RxPinLevelInvert = UART_ADVFEATURE_RXINV_ENABLE; + iiiii = 0; } -#endif + return; - //uartHandle.Init.OverSampling = UART_OVERSAMPLING_16; + if (LL_USART_IsActiveFlag_RXNE(usart) || LL_USART_IsActiveFlag_ORE(usart)) + LL_USART_ReceiveData8(usart); + return; - //Config uart as half duplex if TX and RX pins are the same - if ( (txPin == rxPin) && (txPort == rxPort) ) + if ( LL_USART_IsActiveFlag_ORE(usart) ) { - if (HAL_HalfDuplex_Init(&uartHandles[board.serials[serialNumber].usartHandle]) != HAL_OK) + if ( !LL_USART_IsEnabledIT_RXNE(usart) ) { - ErrorHandler(SERIAL_HALF_DUPLEX_INIT_FAILURE); + LL_USART_ReceiveData8(usart); } } else { - if(HAL_UART_Init(&uartHandles[board.serials[serialNumber].usartHandle]) != HAL_OK) - { - ErrorHandler(SERIAL_INIT_FAILURE); + tmp1 = LL_USART_IsActiveFlag_IDLE(usart); + if (tmp1) { + LL_USART_ClearFlag_IDLE(usart); + serialBuffer[iiiii++] = tmp2 = LL_USART_ReceiveData8(usart); + iiiii = 0; + //LL_DMA_DisableStream(DMA1, LL_DMA_STREAM_5); } - } - //only enable DMA if the DMA is supposed to be enabled - if ( (board.dmasSerial[board.serials[serialNumber].TXDma].enabled) || (board.dmasSerial[board.serials[serialNumber].RXDma].enabled)) - { - UsartDmaInit(serialNumber); - __HAL_UART_FLUSH_DRREGISTER(&uartHandles[board.serials[serialNumber].usartHandle]); - if (board.serials[serialNumber].Mode != UART_MODE_TX) - HAL_UART_Receive_DMA(&uartHandles[board.serials[serialNumber].usartHandle], &dmaRxBuffer[serialNumber], 1); + tmp1 = LL_USART_IsActiveFlag_RXNE(usart); + if ( tmp1 && LL_USART_IsEnabledIT_RXNE(usart) ) + { + //receive into buffer + serialBuffer[iiiii++] = tmp2 = LL_USART_ReceiveData8(usart); + } } } @@ -580,7 +823,7 @@ void InitBoardUsarts (void) { board.dmasSerial[board.serials[serialNumber].RXDma].dmaDirection = DMA_PERIPH_TO_MEMORY; board.dmasSerial[board.serials[serialNumber].RXDma].dmaPeriphInc = DMA_PINC_DISABLE; - board.dmasSerial[board.serials[serialNumber].RXDma].dmaMemInc = DMA_MINC_DISABLE; + board.dmasSerial[board.serials[serialNumber].RXDma].dmaMemInc = DMA_MINC_ENABLE; board.dmasSerial[board.serials[serialNumber].RXDma].dmaPeriphAlignment = DMA_PDATAALIGN_BYTE; board.dmasSerial[board.serials[serialNumber].RXDma].dmaMemAlignment = DMA_MDATAALIGN_BYTE; board.dmasSerial[board.serials[serialNumber].RXDma].dmaMode = DMA_CIRCULAR; @@ -683,19 +926,21 @@ void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart) //works for all serials, we check huart against each serial handle to decide which one has interrupted then deal with it. //todo move arrays to init function - volatile uint32_t timeSinceLastPacket[MAX_USARTS] = {0,}; - uint32_t currentTime; - static uint32_t timeOfLastPacket[MAX_USARTS] = {0,}; + //volatile uint32_t timeSinceLastPacket[MAX_USARTS] = {0,}; + //uint32_t currentTime; + //static uint32_t timeOfLastPacket[MAX_USARTS] = {0,}; - currentTime = InlineMillis(); + //currentTime = InlineMillis(); + for (uint32_t serialNumber = 0;serialNumber <​Type​> <​CRC​> @@ -721,29 +966,36 @@ void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart) { //Sumd packet 2 (third one) is number of channels. //total frame length is header (3) + number of channels * 2 (variable) + crc length (2). - board.serials[serialNumber].FrameSize = CONSTRAIN( (5 + (dmaRxBuffer[serialNumber] * 2) ), 9, 47); //sumd can be between 7 and 37 long +// board.serials[serialNumber].FrameSize = CONSTRAIN( (5 + (dmaRxBuffer[serialNumber] * 2) ), 9, 47); //sumd can be between 7 and 37 long } - if (timeSinceLastPacket[serialNumber] > 3) - { - if (dmaIndex[serialNumber] < board.serials[serialNumber].FrameSize) - { - __HAL_UART_FLUSH_DRREGISTER(&uartHandles[board.serials[serialNumber].usartHandle]); // Clear the buffer to prevent overrun - } + // if (timeSinceLastPacket[serialNumber] > 3) + // { + // if (dmaIndex[serialNumber] < board.serials[serialNumber].FrameSize) + // { + // __HAL_UART_FLUSH_DRREGISTER(&uartHandles[board.serials[serialNumber].usartHandle]); // Clear the buffer to prevent overrun + // } +// +// dmaIndex[serialNumber] = 0; +// +// } - dmaIndex[serialNumber] = 0; - } - - - serialRxBuffer[board.serials[serialNumber].serialRxBuffer-1][dmaIndex[serialNumber]++] = dmaRxBuffer[serialNumber]; // Add that character to the string + memcpy(serialRxBuffer[board.serials[serialNumber].serialRxBuffer-1], dmaRxBuffer[serialNumber], RXBUFFERSIZE); + memset(dmaRxBuffer[serialNumber], 0, RXBUFFERSIZE); + //serialRxBuffer[board.serials[serialNumber].serialRxBuffer-1][dmaIndex[serialNumber]++] = dmaRxBuffer[serialNumber]; // Add that character to the string - if (dmaIndex[serialNumber] >= board.serials[serialNumber].FrameSize) - { + //if (dmaIndex[serialNumber] >= board.serials[serialNumber].FrameSize) + //{ processRxCodeNow = serialNumber; ProcessSerialRx(); dmaIndex[serialNumber] = 0; - } + //} + //UsartDmaInit(serialNumber); + //UART_HandleTypeDef *huart = &uartHandles[board.serials[serialNumber].usartHandle]; + //HAL_UART_Receive_DMA(&uartHandles[board.serials[serialNumber].usartHandle], dmaRxBuffer[serialNumber], RXBUFFERSIZE); + //__HAL_UART_ENABLE_IT(&uartHandles[board.serials[serialNumber].usartHandle], UART_IT_IDLE); // enable idle line interrupt + //__HAL_DMA_ENABLE_IT(huart->hdmarx, DMA_IT_TC); // enable DMA Tx cplt interrupt break; } } diff --git a/src/flight_controller/src/drivers/spring_imuf9001.c b/src/flight_controller/src/drivers/spring_imuf9001.c index efdae7ec..28a77cfb 100644 --- a/src/flight_controller/src/drivers/spring_imuf9001.c +++ b/src/flight_controller/src/drivers/spring_imuf9001.c @@ -3,7 +3,7 @@ #define IMUF_COMMAND_HEADER 'h' #define IMUF_COMMAND_RST '13' -static const uint16_t imufCurrentVersion = 106; +static uint16_t imufCurrentVersion = 106; volatile gyroToBoardCommMode_t currentCommMode; @@ -227,17 +227,29 @@ int AccGyroDeviceInit(loopCtrl_e gyroLoop) imufCommand_t reply; imufCommand_t data; - mainConfig.gyroConfig.imufMode = VerifyAllowedCommMode(mainConfig.gyroConfig.imufMode); - - data.param1 = mainConfig.gyroConfig.imufMode; //todo verify this is allowed - data.param2 = ( (uint16_t)2 << 16) ; //speed, 1 = 32KHz, 2 = 16 KHz, 3 = 8 KHz, 4 = 4 KHz, does nothing right now - data.param3 = ( ( (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[PITCH].gyro.q) << 16 ) | (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[PITCH].gyro.w; - data.param4 = ( ( (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[ROLL].gyro.q) << 16 ) | (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[ROLL].gyro.w; - data.param5 = ( ( (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[YAW].gyro.q) << 16 ) | (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[YAW].gyro.w; - data.param6 = ( ( (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[PITCH].gyro.lpf) << 16 ) | (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[ROLL].gyro.lpf; - data.param7 = ( ( (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[YAW].gyro.lpf) << 16 ) | 0; - data.param8 = ( (int16_t)mainConfig.gyroConfig.minorBoardRotation[X] << 16 ) | (uint16_t)mainConfig.gyroConfig.gyroRotation; - data.param9 = ( (int16_t)mainConfig.gyroConfig.minorBoardRotation[Z] << 16 ) | (int16_t)mainConfig.gyroConfig.minorBoardRotation[Y]; + data.param1 = mainConfig.gyroConfig.imufMode = VerifyAllowedCommMode(mainConfig.gyroConfig.imufMode); + + if (imufCurrentVersion < 107) { + //backwards compatibility for Caprica + data.param2 = ( (uint16_t)2 << 16) ; //speed, 1 = 32KHz, 2 = 16 KHz, 3 = 8 KHz, 4 = 4 KHz, does nothing right now + data.param3 = ( ( (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[PITCH].gyro.q) << 16 ) | (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[PITCH].gyro.w; + data.param4 = ( ( (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[ROLL].gyro.q) << 16 ) | (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[ROLL].gyro.w; + data.param5 = ( ( (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[YAW].gyro.q) << 16 ) | (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[YAW].gyro.w; + data.param6 = ( ( (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[PITCH].gyro.lpf) << 16 ) | (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[ROLL].gyro.lpf; + data.param7 = ( ( (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[YAW].gyro.lpf) << 16 ) | 0; + data.param8 = ( (int16_t)mainConfig.gyroConfig.minorBoardRotation[X] << 16 ) | (uint16_t)mainConfig.gyroConfig.gyroRotation; + data.param9 = ( (int16_t)mainConfig.gyroConfig.minorBoardRotation[Z] << 16 ) | (int16_t)mainConfig.gyroConfig.minorBoardRotation[Y]; + } else { + //Odin contract. + data.param2 = ( (uint16_t)2 << 16) | (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[PITCH].gyro.w; + data.param3 = ( ( (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[ROLL].gyro.q) << 16 ) | (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[PITCH].gyro.q; + data.param4 = ( ( (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[YAW].gyro.q) << 16 ) | (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[ROLL].gyro.lpf; + data.param5 = ( ( (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[PITCH].gyro.lpf) << 16 ) | (uint16_t)mainConfig.tuneProfile[activeProfile].filterConfig[YAW].gyro.lpf; + data.param6 = 0; + data.param7 = 0; + data.param8 = ( (int16_t)mainConfig.gyroConfig.minorBoardRotation[X] << 16 ) | (uint16_t)mainConfig.gyroConfig.gyroRotation; + data.param9 = ( (int16_t)mainConfig.gyroConfig.minorBoardRotation[Z] << 16 ) | (int16_t)mainConfig.gyroConfig.minorBoardRotation[Y]; + } for (attempt = 0; attempt < 4; attempt++) { @@ -280,6 +292,7 @@ int AccGyroDeviceDetect(void) //init crc CrcHandle.Instance = CRC; + CrcHandle.InputDataFormat = CRC_INPUTDATA_FORMAT_WORDS; HAL_CRC_Init(&CrcHandle); for (attempt = 0; attempt < 4; attempt++) @@ -300,7 +313,7 @@ int AccGyroDeviceDetect(void) SystemReset(); deviceWhoAmI = 6662; } else { - deviceWhoAmI = (*(imufVersion_t *)&(reply.param1)).firmware; + imufCurrentVersion = deviceWhoAmI = (*(imufVersion_t *)&(reply.param1)).firmware; return deviceWhoAmI; } } @@ -308,6 +321,8 @@ int AccGyroDeviceDetect(void) return (0); } +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wstrict-aliasing" void ImuDeviceRead(void) { //need to calibrate the imuf, we wait 1000 cycles to do it, or about 7ms at 16 KHz input. @@ -329,6 +344,7 @@ void ImuDeviceRead(void) inlineDigitalLo(ports[board.gyros[0].csPort], board.gyros[0].csPin); AccGyroReadWriteData((uint8_t*)&imuTxCommFrame.gyroFrame, (uint8_t*)&imuRxCommFrame.gyroFrame, currentCommMode, 1); } +#pragma GCC diagnostic pop void ImuDeviceReadComplete(void) { @@ -347,21 +363,21 @@ void ImuDeviceReadComplete(void) else { julian[1]++; + dpsGyroArray[0] = -imuRxCommFrame.gyroFrame.gyroZ; + dpsGyroArray[1] = imuRxCommFrame.gyroFrame.gyroX; + dpsGyroArray[2] = -imuRxCommFrame.gyroFrame.gyroY; + geeForceAccArray[0] = imuRxCommFrame.gyroFrame.accelX; + geeForceAccArray[1] = imuRxCommFrame.gyroFrame.accelY; + geeForceAccArray[2] = imuRxCommFrame.gyroFrame.accelZ; + + if(currentCommMode == GTBCM_GYRO_ACC_QUAT_FILTER_F) + { + attitudeFrameQuat.w = imuRxCommFrame.imuFrame.w; + attitudeFrameQuat.x = imuRxCommFrame.imuFrame.x; + attitudeFrameQuat.y = imuRxCommFrame.imuFrame.y; + attitudeFrameQuat.z = imuRxCommFrame.imuFrame.z; + } + InlineFlightCode(dpsGyroArray); } - dpsGyroArray[0] = -imuRxCommFrame.gyroFrame.gyroZ; - dpsGyroArray[1] = imuRxCommFrame.gyroFrame.gyroX; - dpsGyroArray[2] = -imuRxCommFrame.gyroFrame.gyroY; - geeForceAccArray[0] = imuRxCommFrame.gyroFrame.accelX; - geeForceAccArray[1] = imuRxCommFrame.gyroFrame.accelY; - geeForceAccArray[2] = imuRxCommFrame.gyroFrame.accelZ; - - if(currentCommMode == GTBCM_GYRO_ACC_QUAT_FILTER_F) - { - attitudeFrameQuat.w = imuRxCommFrame.imuFrame.w; - attitudeFrameQuat.x = imuRxCommFrame.imuFrame.x; - attitudeFrameQuat.y = imuRxCommFrame.imuFrame.y; - attitudeFrameQuat.z = imuRxCommFrame.imuFrame.z; - } - InlineFlightCode(dpsGyroArray); } } \ No newline at end of file diff --git a/src/flight_controller/src/flight.c b/src/flight_controller/src/flight.c index 7ebf055e..4f830c80 100644 --- a/src/flight_controller/src/flight.c +++ b/src/flight_controller/src/flight.c @@ -645,7 +645,8 @@ void InlineFlightCode(float dpsGyroArray[]) static uint32_t gyroStdDeviationLatch = 0; int32_t axis; -// inlineDigitalHi(ports[ENUM_PORTB], GPIO_PIN_0); +//inlineDigitalHi(ports[ENUM_PORTB], GPIO_PIN_0); +//inlineDigitalHi(ports[ENUM_PORTC], GPIO_PIN_9); //Gyro routine: //gyro interrupts @@ -991,6 +992,7 @@ void InlineFlightCode(float dpsGyroArray[]) } +//inlineDigitalLo(ports[ENUM_PORTC], GPIO_PIN_9); //inlineDigitalLo(ports[ACTUATOR1_GPIO], ACTUATOR1_PIN); if(usedSkunk == 2 || currentCommMode == GTBCM_GYRO_ACC_QUAT_FILTER_F ) return; @@ -1138,7 +1140,7 @@ int InitFlight(void) InitBoardUsarts(); //most important thing is activated last, the ability to control the craft. //needs to run before InitTelemtry and InitFlashChip - InitMaxOsd(); + //InitMaxOsd(); if (board.flash[0].enabled) { diff --git a/src/flight_controller/src/main.c b/src/flight_controller/src/main.c index de8a27c1..e917b8e2 100644 --- a/src/flight_controller/src/main.c +++ b/src/flight_controller/src/main.c @@ -10,15 +10,129 @@ int main(void) int count = 16; //TODO: Make automatic - retValChk = VectorIrqInit(THIS_ADDRESS); + retValChk = VectorIrqInit(THIS_ADDRESS); - //TODO Needs to pull parameters from flash here. For now we use defines - retValChk = GetBoardHardwareDefs(); + //TODO Needs to pull parameters from flash here. For now we use defines + retValChk = GetBoardHardwareDefs(); retValChk = InitializeMCUSettings(); retValChk = BoardInit(); + //SystemCoreClock = 240000000; + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct; + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + + __HAL_RCC_PWR_CLK_ENABLE(); + + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /**Initializes the CPU, AHB and APB busses clocks + */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = FC_PLLM; + RCC_OscInitStruct.PLL.PLLN = FC_PLLN; + RCC_OscInitStruct.PLL.PLLP = FC_PLLP; + RCC_OscInitStruct.PLL.PLLQ = FC_PLLQ; + + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) + { + while(1); + } + + if(HAL_PWREx_EnableOverDrive() != HAL_OK) + { + while(1); + } + + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK + |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7) != HAL_OK) + { + while(1); + } + + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_USART2|RCC_PERIPHCLK_USART3|RCC_PERIPHCLK_USART6|RCC_PERIPHCLK_UART4|RCC_PERIPHCLK_UART5|RCC_PERIPHCLK_UART7|RCC_PERIPHCLK_UART8|RCC_PERIPHCLK_I2C1|RCC_PERIPHCLK_I2C3|RCC_PERIPHCLK_I2C2|RCC_PERIPHCLK_I2C4|RCC_PERIPHCLK_CLK48; + PeriphClkInitStruct.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK2; + PeriphClkInitStruct.Usart2ClockSelection = RCC_USART2CLKSOURCE_PCLK1; + PeriphClkInitStruct.Usart3ClockSelection = RCC_USART3CLKSOURCE_PCLK1; + PeriphClkInitStruct.Uart4ClockSelection = RCC_UART4CLKSOURCE_PCLK1; + PeriphClkInitStruct.Uart5ClockSelection = RCC_UART5CLKSOURCE_PCLK1; + PeriphClkInitStruct.Usart6ClockSelection = RCC_USART6CLKSOURCE_PCLK2; + PeriphClkInitStruct.Uart7ClockSelection = RCC_UART7CLKSOURCE_PCLK1; + PeriphClkInitStruct.Uart8ClockSelection = RCC_UART8CLKSOURCE_PCLK1; + PeriphClkInitStruct.I2c1ClockSelection = RCC_I2C1CLKSOURCE_SYSCLK; + PeriphClkInitStruct.I2c2ClockSelection = RCC_I2C2CLKSOURCE_SYSCLK; + PeriphClkInitStruct.I2c3ClockSelection = RCC_I2C3CLKSOURCE_SYSCLK; + #ifdef RCC_DCKCFGR2_I2C4SEL_0 + PeriphClkInitStruct.I2c4ClockSelection = RCC_I2C4CLKSOURCE_SYSCLK; + #endif + PeriphClkInitStruct.PLLSAI.PLLSAIN = 384; + #if defined (STM32F745xx) || defined (STM32F746xx) || defined (STM32F756xx) || defined (STM32F765xx) || defined (STM32F767xx) || defined (STM32F769xx) || defined (STM32F777xx) || defined (STM32F779xx) + PeriphClkInitStruct.PLLSAI.PLLSAIR = 2; + PeriphClkInitStruct.PLLSAI.PLLSAIQ = 2; + #endif + #if defined (STM32F722xx) + PeriphClkInitStruct.PLLSAI.PLLSAIQ = 7; + #endif + + PeriphClkInitStruct.PLLSAI.PLLSAIP = RCC_PLLSAIP_DIV8; + PeriphClkInitStruct.PLLSAIDivQ = 1; + PeriphClkInitStruct.PLLSAIDivR = RCC_PLLSAIDIVR_2; + PeriphClkInitStruct.Clk48ClockSelection = RCC_CLK48SOURCE_PLLSAIP; + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_CLK48; + + if(HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) + { + while(1); + } + + systemUsTicks = (HAL_RCC_GetHCLKFreq()/1000000); + __HAL_RCC_GPIOA_CLK_ENABLE(); + __HAL_RCC_GPIOB_CLK_ENABLE(); + __HAL_RCC_GPIOC_CLK_ENABLE(); + __HAL_RCC_GPIOD_CLK_ENABLE(); + __HAL_RCC_GPIOE_CLK_ENABLE(); + __HAL_RCC_GPIOF_CLK_ENABLE(); + __HAL_RCC_GPIOG_CLK_ENABLE(); + __HAL_RCC_GPIOH_CLK_ENABLE(); + __HAL_RCC_GPIOI_CLK_ENABLE(); + + __HAL_RCC_ADC1_CLK_ENABLE(); + __HAL_RCC_ADC2_CLK_ENABLE(); + __HAL_RCC_ADC3_CLK_ENABLE(); + + __HAL_RCC_DMA1_CLK_ENABLE(); + __HAL_RCC_DMA2_CLK_ENABLE(); + + __HAL_RCC_TIM1_CLK_ENABLE(); + __HAL_RCC_TIM2_CLK_ENABLE(); + __HAL_RCC_TIM3_CLK_ENABLE(); + __HAL_RCC_TIM4_CLK_ENABLE(); + __HAL_RCC_TIM5_CLK_ENABLE(); + __HAL_RCC_TIM6_CLK_ENABLE(); + __HAL_RCC_TIM7_CLK_ENABLE(); + __HAL_RCC_TIM8_CLK_ENABLE(); + + __USART1_CLK_ENABLE(); + __USART2_CLK_ENABLE(); + __USART3_CLK_ENABLE(); + __UART4_CLK_ENABLE(); + __UART5_CLK_ENABLE(); + __USART6_CLK_ENABLE(); + + __HAL_RCC_CRC_CLK_ENABLE(); //DshotInit(1); retValChk = HandleRfbl(); @@ -45,8 +159,8 @@ int main(void) //DeInitActuators(); //DelayMs(10); - //InitializeGpio(ports[ACTUATOR1_GPIO], ACTUATOR1_PIN, 0); - //inlineDigitalLo(ports[ACTUATOR1_GPIO], ACTUATOR1_PIN); + //InitializeGpio(ports[ENUM_PORTC], GPIO_PIN_9, 0); + //inlineDigitalLo(ports[ENUM_PORTC], GPIO_PIN_9); //InitializeGpio(ports[ENUM_PORTB], GPIO_PIN_0, 0); while (1) diff --git a/src/flight_controller/src/usb/usbd_desc.c b/src/flight_controller/src/usb/usbd_desc.c index efe08f61..31455346 100644 --- a/src/flight_controller/src/usb/usbd_desc.c +++ b/src/flight_controller/src/usb/usbd_desc.c @@ -245,9 +245,9 @@ static void IntToUnicode(uint32_t value, uint8_t *pbuf, uint8_t len) */ static void Get_SerialNum(void) { - uint32_t deviceserial0 = *(uint32_t*)DEVICE_ID1; - uint32_t deviceserial1 = *(uint32_t*)DEVICE_ID2; - uint32_t deviceserial2 = *(uint32_t*)DEVICE_ID3; + uint32_t deviceserial0 = 111;//*(uint32_t*)DEVICE_ID1; + uint32_t deviceserial1 = 111;//*(uint32_t*)DEVICE_ID2; + uint32_t deviceserial2 = 111;//*(uint32_t*)DEVICE_ID3; deviceserial0 += deviceserial2; diff --git a/src/flight_controller/src/wizard.c b/src/flight_controller/src/wizard.c index 2066dc8d..552d6968 100644 --- a/src/flight_controller/src/wizard.c +++ b/src/flight_controller/src/wizard.c @@ -565,25 +565,6 @@ void HandleWizRx(void) for (y=0;yFLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM + + + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} \ No newline at end of file diff --git a/src/low_level_driver/stm32_flash_f722_recovery.ld b/src/low_level_driver/stm32_flash_f722_recovery.ld new file mode 100644 index 00000000..9595dc2a --- /dev/null +++ b/src/low_level_driver/stm32_flash_f722_recovery.ld @@ -0,0 +1,149 @@ +/* +***************************************************************************** +** + ** File : LinkerScript.ld +** +** Abstract : Linker script for STM32F746NGHx Device with +** 1024KByte FLASH, 320KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** +** Distribution: The file is distributed as is, without any warranty +** of any kind. +** +** (c)Copyright Ac6. +** You may use this file as-is or modify it according to the needs of your +** project. Distribution of this file (unmodified or modified) is not +** permitted. Ac6 permit registered System Workbench for MCU users the +** rights to distribute the assembled, compiled & linked contents of this +** file as part of an application binary file, provided that it is built +** using the System Workbench for MCU toolchain. +** +***************************************************************************** +*/ + /* Entry Point */ +ENTRY(Reset_Handler) + /* Highest address of the user mode stack */ +_estack = 0x20040000; /* end of RAM */ +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x460; /* required amount of stack */ + /* Specify the memory areas */ +MEMORY +{ +FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 0x8000 +/* TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K */ +RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 176K +MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + /* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + KEEP (*(.init)) + KEEP (*(.fini)) + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + /* Constant data goes into FLASH */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + .ARM.attributes 0 : { *(.ARM.attributes) } +} \ No newline at end of file diff --git a/src/low_level_driver/stm32_startup/startup_stm32f722xx.s b/src/low_level_driver/stm32_startup/startup_stm32f722xx.s new file mode 100644 index 00000000..a59ab6f5 --- /dev/null +++ b/src/low_level_driver/stm32_startup/startup_stm32f722xx.s @@ -0,0 +1,554 @@ +/** + ****************************************************************************** + * @file startup_stm32f722xx.s + * @author MCD Application Team + * @version V1.2.0 + * @date 30-December-2016 + * @brief STM32F722xx Devices vector table for GCC based toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M7 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2016 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m7 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + ldr sp, =_estack /* set stack pointer */ + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ +/* bl __libc_init_array */ +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M7. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + + /* External Interrupts */ + .word WWDG_IRQHandler /* Window WatchDog */ + .word PVD_IRQHandler /* PVD through EXTI Line detection */ + .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ + .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ + .word FLASH_IRQHandler /* FLASH */ + .word RCC_IRQHandler /* RCC */ + .word EXTI0_IRQHandler /* EXTI Line0 */ + .word EXTI1_IRQHandler /* EXTI Line1 */ + .word EXTI2_IRQHandler /* EXTI Line2 */ + .word EXTI3_IRQHandler /* EXTI Line3 */ + .word EXTI4_IRQHandler /* EXTI Line4 */ + .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ + .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ + .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ + .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ + .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ + .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ + .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ + .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ + .word CAN1_TX_IRQHandler /* CAN1 TX */ + .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ + .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ + .word CAN1_SCE_IRQHandler /* CAN1 SCE */ + .word EXTI9_5_IRQHandler /* External Line[9:5]s */ + .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ + .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ + .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ + .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ + .word TIM2_IRQHandler /* TIM2 */ + .word TIM3_IRQHandler /* TIM3 */ + .word TIM4_IRQHandler /* TIM4 */ + .word I2C1_EV_IRQHandler /* I2C1 Event */ + .word I2C1_ER_IRQHandler /* I2C1 Error */ + .word I2C2_EV_IRQHandler /* I2C2 Event */ + .word I2C2_ER_IRQHandler /* I2C2 Error */ + .word SPI1_IRQHandler /* SPI1 */ + .word SPI2_IRQHandler /* SPI2 */ + .word USART1_IRQHandler /* USART1 */ + .word USART2_IRQHandler /* USART2 */ + .word USART3_IRQHandler /* USART3 */ + .word EXTI15_10_IRQHandler /* External Line[15:10]s */ + .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ + .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ + .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ + .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ + .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ + .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ + .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ + .word FMC_IRQHandler /* FMC */ + .word SDMMC1_IRQHandler /* SDMMC1 */ + .word TIM5_IRQHandler /* TIM5 */ + .word SPI3_IRQHandler /* SPI3 */ + .word UART4_IRQHandler /* UART4 */ + .word UART5_IRQHandler /* UART5 */ + .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ + .word TIM7_IRQHandler /* TIM7 */ + .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ + .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ + .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ + .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ + .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word OTG_FS_IRQHandler /* USB OTG FS */ + .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ + .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ + .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ + .word USART6_IRQHandler /* USART6 */ + .word I2C3_EV_IRQHandler /* I2C3 event */ + .word I2C3_ER_IRQHandler /* I2C3 error */ + .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ + .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ + .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ + .word OTG_HS_IRQHandler /* USB OTG HS */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word RNG_IRQHandler /* RNG */ + .word FPU_IRQHandler /* FPU */ + .word UART7_IRQHandler /* UART7 */ + .word UART8_IRQHandler /* UART8 */ + .word SPI4_IRQHandler /* SPI4 */ + .word SPI5_IRQHandler /* SPI5 */ + .word 0 /* Reserved */ + .word SAI1_IRQHandler /* SAI1 */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word SAI2_IRQHandler /* SAI2 */ + .word QUADSPI_IRQHandler /* QUADSPI */ + .word LPTIM1_IRQHandler /* LPTIM1 */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word SDMMC2_IRQHandler /* SDMMC2 */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMP_STAMP_IRQHandler + .thumb_set TAMP_STAMP_IRQHandler,Default_Handler + + .weak RTC_WKUP_IRQHandler + .thumb_set RTC_WKUP_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Stream0_IRQHandler + .thumb_set DMA1_Stream0_IRQHandler,Default_Handler + + .weak DMA1_Stream1_IRQHandler + .thumb_set DMA1_Stream1_IRQHandler,Default_Handler + + .weak DMA1_Stream2_IRQHandler + .thumb_set DMA1_Stream2_IRQHandler,Default_Handler + + .weak DMA1_Stream3_IRQHandler + .thumb_set DMA1_Stream3_IRQHandler,Default_Handler + + .weak DMA1_Stream4_IRQHandler + .thumb_set DMA1_Stream4_IRQHandler,Default_Handler + + .weak DMA1_Stream5_IRQHandler + .thumb_set DMA1_Stream5_IRQHandler,Default_Handler + + .weak DMA1_Stream6_IRQHandler + .thumb_set DMA1_Stream6_IRQHandler,Default_Handler + + .weak ADC_IRQHandler + .thumb_set ADC_IRQHandler,Default_Handler + + .weak CAN1_TX_IRQHandler + .thumb_set CAN1_TX_IRQHandler,Default_Handler + + .weak CAN1_RX0_IRQHandler + .thumb_set CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM9_IRQHandler + .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM10_IRQHandler + .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM11_IRQHandler + .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTC_Alarm_IRQHandler + .thumb_set RTC_Alarm_IRQHandler,Default_Handler + + .weak OTG_FS_WKUP_IRQHandler + .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler + + .weak TIM8_BRK_TIM12_IRQHandler + .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler + + .weak TIM8_UP_TIM13_IRQHandler + .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_TIM14_IRQHandler + .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak DMA1_Stream7_IRQHandler + .thumb_set DMA1_Stream7_IRQHandler,Default_Handler + + .weak FMC_IRQHandler + .thumb_set FMC_IRQHandler,Default_Handler + + .weak SDMMC1_IRQHandler + .thumb_set SDMMC1_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Stream0_IRQHandler + .thumb_set DMA2_Stream0_IRQHandler,Default_Handler + + .weak DMA2_Stream1_IRQHandler + .thumb_set DMA2_Stream1_IRQHandler,Default_Handler + + .weak DMA2_Stream2_IRQHandler + .thumb_set DMA2_Stream2_IRQHandler,Default_Handler + + .weak DMA2_Stream3_IRQHandler + .thumb_set DMA2_Stream3_IRQHandler,Default_Handler + + .weak DMA2_Stream4_IRQHandler + .thumb_set DMA2_Stream4_IRQHandler,Default_Handler + + .weak DMA2_Stream4_IRQHandler + .thumb_set DMA2_Stream4_IRQHandler,Default_Handler + + .weak OTG_FS_IRQHandler + .thumb_set OTG_FS_IRQHandler,Default_Handler + + .weak DMA2_Stream5_IRQHandler + .thumb_set DMA2_Stream5_IRQHandler,Default_Handler + + .weak DMA2_Stream6_IRQHandler + .thumb_set DMA2_Stream6_IRQHandler,Default_Handler + + .weak DMA2_Stream7_IRQHandler + .thumb_set DMA2_Stream7_IRQHandler,Default_Handler + + .weak USART6_IRQHandler + .thumb_set USART6_IRQHandler,Default_Handler + + .weak I2C3_EV_IRQHandler + .thumb_set I2C3_EV_IRQHandler,Default_Handler + + .weak I2C3_ER_IRQHandler + .thumb_set I2C3_ER_IRQHandler,Default_Handler + + .weak OTG_HS_EP1_OUT_IRQHandler + .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler + + .weak OTG_HS_EP1_IN_IRQHandler + .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler + + .weak OTG_HS_WKUP_IRQHandler + .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler + + .weak OTG_HS_IRQHandler + .thumb_set OTG_HS_IRQHandler,Default_Handler + + .weak RNG_IRQHandler + .thumb_set RNG_IRQHandler,Default_Handler + + .weak FPU_IRQHandler + .thumb_set FPU_IRQHandler,Default_Handler + + .weak UART7_IRQHandler + .thumb_set UART7_IRQHandler,Default_Handler + + .weak UART8_IRQHandler + .thumb_set UART8_IRQHandler,Default_Handler + + .weak SPI4_IRQHandler + .thumb_set SPI4_IRQHandler,Default_Handler + + .weak SPI5_IRQHandler + .thumb_set SPI5_IRQHandler,Default_Handler + + .weak SAI1_IRQHandler + .thumb_set SAI1_IRQHandler,Default_Handler + + .weak SAI2_IRQHandler + .thumb_set SAI2_IRQHandler,Default_Handler + + .weak QUADSPI_IRQHandler + .thumb_set QUADSPI_IRQHandler,Default_Handler + + .weak LPTIM1_IRQHandler + .thumb_set LPTIM1_IRQHandler,Default_Handler + + .weak SDMMC2_IRQHandler + .thumb_set SDMMC2_IRQHandler,Default_Handler + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ \ No newline at end of file diff --git a/src/low_level_driver/stm32f0/stm32f0.c b/src/low_level_driver/stm32f0/stm32f0.c index b0bfabaa..6a2b57a8 100644 --- a/src/low_level_driver/stm32f0/stm32f0.c +++ b/src/low_level_driver/stm32f0/stm32f0.c @@ -47,7 +47,7 @@ void SystemClock_Config(void) systemUsTicks = (HAL_RCC_GetHCLKFreq()/1000000); } - void BoardInit(void) + int BoardInit(void) { SCB->VTOR = ADDRESS_FLASH_START; //set vector register to firmware start __enable_irq(); // enable interrupts @@ -61,6 +61,7 @@ void SystemClock_Config(void) __HAL_RCC_GPIOC_CLK_ENABLE(); __HAL_RCC_GPIOD_CLK_ENABLE(); + return(0); } inline void inlineDigitalHi(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) { diff --git a/src/low_level_driver/stm32f0/stm32f0xx_hal_conf.h b/src/low_level_driver/stm32f0/stm32f0xx_hal_conf.h index 0868f4fb..585d9e9b 100644 --- a/src/low_level_driver/stm32f0/stm32f0xx_hal_conf.h +++ b/src/low_level_driver/stm32f0/stm32f0xx_hal_conf.h @@ -297,7 +297,9 @@ /* Exported functions ------------------------------------------------------- */ void assert_failed(uint8_t* file, uint32_t line); #else - #define assert_param(expr) ((void)0U) +#ifndef assert_param +#define assert_param(expr) ((void)0U) +#endif #endif /* USE_FULL_ASSERT */ #ifdef __cplusplus diff --git a/src/low_level_driver/stm32f3/stm32f3.c b/src/low_level_driver/stm32f3/stm32f3.c index 7bbcd742..3c44a69a 100644 --- a/src/low_level_driver/stm32f3/stm32f3.c +++ b/src/low_level_driver/stm32f3/stm32f3.c @@ -49,7 +49,7 @@ void SystemClock_Config(void) systemUsTicks = (HAL_RCC_GetHCLKFreq()/1000000); } -void BoardInit(void) +int BoardInit(void) { SCB->VTOR = ADDRESS_FLASH_START; //set vector register to firmware start __enable_irq(); // enable interrupts @@ -79,6 +79,7 @@ void BoardInit(void) __HAL_RCC_TIM2_CLK_ENABLE(); __HAL_RCC_TIM6_CLK_ENABLE(); + return(0); } void VectorIrqInit(uint32_t address) diff --git a/src/low_level_driver/stm32f4/mcu_include.h b/src/low_level_driver/stm32f4/mcu_include.h index 16656c0c..80b51321 100644 --- a/src/low_level_driver/stm32f4/mcu_include.h +++ b/src/low_level_driver/stm32f4/mcu_include.h @@ -2,6 +2,11 @@ #include "stm32f4xx.h" #include "stm32f4xx_hal.h" +#include "stm32f4xx_ll_dma.h" +#include "stm32f4xx_ll_usart.h" +#include "stm32f4xx_ll_gpio.h" +#include "stm32f4xx_ll_rcc.h" +#include "stm32f4xx_ll_bus.h" #include "stm32f4xx_it.h" #include "stm32f4xx_hal_conf.h" #include "flash.h" diff --git a/src/low_level_driver/stm32f4/stm32f4xx_it.c b/src/low_level_driver/stm32f4/stm32f4xx_it.c index d93a2f68..08983a2e 100644 --- a/src/low_level_driver/stm32f4/stm32f4xx_it.c +++ b/src/low_level_driver/stm32f4/stm32f4xx_it.c @@ -411,3 +411,33 @@ void ADC_IRQHandler(void) //only need to use one ADC handle for now HAL_ADC_IRQHandler(&adcHandle[board.boardADC[1].adcHandle]); } + +void USART1_IRQHandler(void) +{ + UsartIrqCallback(0); +} + +void USART2_IRQHandler(void) +{ + UsartIrqCallback(1); +} + +void USART3_IRQHandler(void) +{ + UsartIrqCallback(2); +} + +void UART4_IRQHandler(void) +{ + UsartIrqCallback(3); +} + +void UART5_IRQHandler(void) +{ + UsartIrqCallback(4); +} + +void USART6_IRQHandler(void) +{ + UsartIrqCallback(5); +} \ No newline at end of file diff --git a/src/low_level_driver/stm32f7/flash.h b/src/low_level_driver/stm32f7/flash.h index 8fbf910b..8c5b07d1 100644 --- a/src/low_level_driver/stm32f7/flash.h +++ b/src/low_level_driver/stm32f7/flash.h @@ -2,6 +2,18 @@ #include +/* +Sector 0 0x08000000 - 0x08003FFF 16 Kbytes +Sector 1 0x08004000 - 0x08007FFF 16 Kbytes +Sector 2 0x08008000 - 0x0800BFFF 16 Kbytes +Sector 3 0x0800C000 - 0x0800FFFF 16 Kbytes +Sector 4 0x08010000 - 0x0801FFFF 64 Kbytes +Sector 5 0x08020000 - 0x0803FFFF 128 Kbytes +Sector 6 0x08040000 - 0x0805FFFF 128 Kbytes +Sector 7 0x08060000 - 0x0807FFFF 128 Kbytes +*/ + +#if defined(stm32f745xx) || defined(STM32F745xx) /* Base address of the Flash sectors */ #define ADDR_FLASH_SECTOR_0 ((uint32_t)0x08000000) /* Base @ of Sector 0, 32 Kbytes */ #define ADDR_FLASH_SECTOR_1 ((uint32_t)0x08008000) /* Base @ of Sector 1, 32 Kbytes */ @@ -12,8 +24,21 @@ #define ADDR_FLASH_SECTOR_6 ((uint32_t)0x08080000) /* Base @ of Sector 6, 256 Kbytes */ #define ADDR_FLASH_SECTOR_7 ((uint32_t)0x080C0000) /* Base @ of Sector 7, 256 Kbytes */ +#elif defined(stm32f722xx) +/* Base address of the Flash sectors */ +#define ADDR_FLASH_SECTOR_0 ((uint32_t)0x08000000) /* Base @ of Sector 0, 16 Kbytes */ +#define ADDR_FLASH_SECTOR_1 ((uint32_t)0x08004000) /* Base @ of Sector 1, 16 Kbytes */ +#define ADDR_FLASH_SECTOR_2 ((uint32_t)0x08008000) /* Base @ of Sector 2, 16 Kbytes */ +#define ADDR_FLASH_SECTOR_3 ((uint32_t)0x0800C000) /* Base @ of Sector 3, 16 Kbytes */ +#define ADDR_FLASH_SECTOR_4 ((uint32_t)0x08010000) /* Base @ of Sector 4, 64 Kbytes */ +#define ADDR_FLASH_SECTOR_5 ((uint32_t)0x08020000) /* Base @ of Sector 5, 128 Kbytes */ +#define ADDR_FLASH_SECTOR_6 ((uint32_t)0x08040000) /* Base @ of Sector 6, 128 Kbytes */ +#define ADDR_FLASH_SECTOR_7 ((uint32_t)0x08060000) /* Base @ of Sector 7, 128 Kbytes */ + +#endif + void PrepareFlash(void); void FinishFlash(void); int WriteFlash(uint32_t data32, uint32_t flashAddress ); int EraseFlash(uint32_t flashStart, uint32_t flashEnd); -uint32_t GetFlashSector(uint32_t flashAddress); +uint32_t GetFlashSector(uint32_t flashAddress); \ No newline at end of file diff --git a/src/low_level_driver/stm32f7/mcu_include.h b/src/low_level_driver/stm32f7/mcu_include.h index 8002ff62..2b31c93a 100644 --- a/src/low_level_driver/stm32f7/mcu_include.h +++ b/src/low_level_driver/stm32f7/mcu_include.h @@ -2,6 +2,11 @@ #include "stm32f7xx.h" #include "stm32f7xx_hal.h" +#include "stm32f7xx_ll_dma.h" +#include "stm32f7xx_ll_usart.h" +#include "stm32f7xx_ll_gpio.h" +#include "stm32f7xx_ll_rcc.h" +#include "stm32f7xx_ll_bus.h" #include "stm32f7xx_it.h" #include "stm32f7xx_hal_conf.h" #include "flash.h" @@ -57,8 +62,6 @@ extern int FULL_32; #define _GPIOG GPIOG #define _GPIOH GPIOH #define _GPIOI GPIOI -#define _GPIOJ GPIOJ -#define _GPIOK GPIOK #define _PORTA 0 #define _PORTB 1 @@ -82,15 +85,42 @@ extern int FULL_32; #define _USART5s 0 #define _USART6 USART6 #define _USART6s 1 -#define _USART7 USART7 -#define _USART7s 1 #define STM32_UUID ((uint32_t *)0x1FF0F420) #if defined(stm32f745xx) || defined(STM32F745xx) #include + +#define _USART7 USART7 +#define _USART7s 1 + +#define _GPIOJ GPIOJ +#define _GPIOK GPIOK + //STM32F4 UID address +#define DEVICE_ID1 0x1FF07A10 +#define DEVICE_ID2 0x1FF07A14 +#define DEVICE_ID3 0x1FF07A18 + +#define USE_RFBL +#define ADDRESS_FLASH_START (uint32_t)(0x08000000) +#define ADDRESS_RECOVERY_START (uint32_t)(0x08000000) +#define ADDRESS_RFBL_START (uint32_t)(0x08008000) +#define ADDRESS_CONFIG_START (uint32_t)(0x08010000) +#define ADDRESS_RFFW_START (uint32_t)(0x08020000) +#define ADDRESS_ESC_START (uint32_t)(0x08060000) +#define ADDRESS_FLASH_END (uint32_t)(0x0807FFF0) + + +#elif defined(stm32f722xx) + +#include +//STM32F4 UID address + +#define _GPIOJ NULL +#define _GPIOK NULL + #define DEVICE_ID1 0x1FF0F420 #define DEVICE_ID2 0x1FF0F424 #define DEVICE_ID3 0x1FF0F428 @@ -101,10 +131,9 @@ extern int FULL_32; #define ADDRESS_RFBL_START (uint32_t)(0x08008000) #define ADDRESS_CONFIG_START (uint32_t)(0x08010000) #define ADDRESS_RFFW_START (uint32_t)(0x08020000) -#define ADDRESS_ESC_START (uint32_t)(0x08060000) -#define ADDRESS_FLASH_END (uint32_t)(0x080FFFF0) - +#define ADDRESS_ESC_START (uint32_t)(0x08058000) +#define ADDRESS_FLASH_END (uint32_t)(0x0807FFF0) #endif -extern uint32_t TimerPrescalerDivisor(uint32_t timer); +extern uint32_t TimerPrescalerDivisor(uint32_t timer); \ No newline at end of file diff --git a/src/low_level_driver/stm32f7/stm32f7.c b/src/low_level_driver/stm32f7/stm32f7.c index 65b67647..a2859489 100644 --- a/src/low_level_driver/stm32f7/stm32f7.c +++ b/src/low_level_driver/stm32f7/stm32f7.c @@ -79,185 +79,55 @@ void SystemClock_Config(void) PeriphClkInitStruct.I2c1ClockSelection = RCC_I2C1CLKSOURCE_SYSCLK; PeriphClkInitStruct.I2c2ClockSelection = RCC_I2C2CLKSOURCE_SYSCLK; PeriphClkInitStruct.I2c3ClockSelection = RCC_I2C3CLKSOURCE_SYSCLK; + #ifdef RCC_DCKCFGR2_I2C4SEL_0 PeriphClkInitStruct.I2c4ClockSelection = RCC_I2C4CLKSOURCE_SYSCLK; + #endif PeriphClkInitStruct.PLLSAI.PLLSAIN = 384; + #if defined (STM32F745xx) || defined (STM32F746xx) || defined (STM32F756xx) || defined (STM32F765xx) || defined (STM32F767xx) || defined (STM32F769xx) || defined (STM32F777xx) || defined (STM32F779xx) PeriphClkInitStruct.PLLSAI.PLLSAIR = 2; - PeriphClkInitStruct.PLLSAI.PLLSAIQ = 2; + PeriphClkInitStruct.PLLSAI.PLLSAIQ = 2; + #endif + #if defined (STM32F722xx) + PeriphClkInitStruct.PLLSAI.PLLSAIQ = 7; + #endif + PeriphClkInitStruct.PLLSAI.PLLSAIP = RCC_PLLSAIP_DIV8; PeriphClkInitStruct.PLLSAIDivQ = 1; PeriphClkInitStruct.PLLSAIDivR = RCC_PLLSAIDIVR_2; PeriphClkInitStruct.Clk48ClockSelection = RCC_CLK48SOURCE_PLLSAIP; + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_CLK48; if(HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) { while(1); } - /* - #define FC_PLLM 8 -#define FC_PLLN 432 -#define FC_PLLP RCC_PLLP_DIV2 -#define FC_PLLQ 9 -#define FC_PLL_SAIN 384 -#define FC_PLL_SAIQ 7 -#define FC_PLL_SAIP RCC_PLLSAIP_DIV8 - - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.HSEState = RCC_HSE_ON; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; - RCC_OscInitStruct.PLL.PLLM = FC_PLLM; - RCC_OscInitStruct.PLL.PLLN = FC_PLLN; - RCC_OscInitStruct.PLL.PLLP = FC_PLLP; - RCC_OscInitStruct.PLL.PLLQ = FC_PLLQ; - - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.HSEState = RCC_HSE_ON; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; - RCC_OscInitStruct.PLL.PLLM = 8; - RCC_OscInitStruct.PLL.PLLN = 432; - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; - RCC_OscInitStruct.PLL.PLLQ = 9; - if(HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) - { - while(1); - } - */ - /* Activate the OverDrive to reach the 216 Mhz Frequency */ - /* - if(HAL_PWREx_EnableOverDrive() != HAL_OK) - { - while(1); - } - -#define RCC_CLK48CLKSOURCE_PLLQ ((uint32_t)0x00000000U) -*/ - /* Select PLLSAI output as USB clock source */ - /* - PeriphClkInitStruct.PLLSAI.PLLSAIN = 384; - PeriphClkInitStruct.PLLSAI.PLLSAIQ = 7; - PeriphClkInitStruct.PLLSAI.PLLSAIP = 8; - PeriphClkInitStruct.PeriphClockSelection = RCC_CLK48CLKSOURCE_PLLQ; - PeriphClkInitStruct.Clk48ClockSelection = RCC_CLK48SOURCE_PLLSAIP; -*/ - - /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 - clocks dividers */ - /* - RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); - RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; - if(HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7) != HAL_OK) - { - while(1); - } - - - PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_USART2|RCC_PERIPHCLK_USART3|RCC_PERIPHCLK_USART6|RCC_PERIPHCLK_UART4|RCC_PERIPHCLK_UART5|RCC_PERIPHCLK_UART7|RCC_PERIPHCLK_UART8|RCC_PERIPHCLK_I2C1|RCC_PERIPHCLK_I2C3|RCC_PERIPHCLK_I2C2|RCC_PERIPHCLK_I2C4; - PeriphClkInitStruct.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK2; - PeriphClkInitStruct.Usart2ClockSelection = RCC_USART2CLKSOURCE_PCLK1; - PeriphClkInitStruct.Usart3ClockSelection = RCC_USART3CLKSOURCE_PCLK1; - PeriphClkInitStruct.Uart4ClockSelection = RCC_UART4CLKSOURCE_PCLK1; - PeriphClkInitStruct.Uart5ClockSelection = RCC_UART5CLKSOURCE_PCLK1; - PeriphClkInitStruct.Usart6ClockSelection = RCC_USART6CLKSOURCE_PCLK2; - PeriphClkInitStruct.Uart7ClockSelection = RCC_UART7CLKSOURCE_PCLK1; - PeriphClkInitStruct.Uart8ClockSelection = RCC_UART8CLKSOURCE_PCLK1; - PeriphClkInitStruct.I2c1ClockSelection = RCC_I2C1CLKSOURCE_SYSCLK; - PeriphClkInitStruct.I2c2ClockSelection = RCC_I2C2CLKSOURCE_SYSCLK; - PeriphClkInitStruct.I2c3ClockSelection = RCC_I2C3CLKSOURCE_SYSCLK; - PeriphClkInitStruct.I2c4ClockSelection = RCC_I2C4CLKSOURCE_SYSCLK; - if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) - { - while(1); - } - - // Activating the timerprescalers while the APBx prescalers are 1/2/4 will connect the TIMxCLK to HCLK which has been configured to 216MHz - __HAL_RCC_TIMCLKPRESCALER(RCC_TIMPRES_ACTIVATED); -*/ - HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq()/1000); - - /**Configure the Systick - */ - HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK); - - /* SysTick_IRQn interrupt configuration */ - HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0); - -// SystemCoreClockUpdate(); - -// HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK); - -// HAL_InitTick(0); - -// SysTick_Config(HAL_RCC_GetHCLKFreq()/500); - - systemUsTicks = (HAL_RCC_GetHCLKFreq()/1000000); - + systemUsTicks = (HAL_RCC_GetHCLKFreq()/1000000); } -void VectorIrqInit(uint32_t address) +int VectorIrqInit(uint32_t address) { SCB->VTOR = address; //set vector register to firmware start __enable_irq(); // enable interrupts + //return(0); //#MD add to debug F722 CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk; - DWT->LAR = 0xC5ACCE55; + //DWT->LAR = 0xC5ACCE55; //commented out for debugging F722 #MD DWT->CYCCNT = 0; DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk; + return(0); } -void BoardInit(void) +int BoardInit(void) { - //SCB->VTOR = ADDRESS_FLASH_START; //set vector register to firmware start - //__enable_irq(); // enable interrupts - SCB_EnableICache(); - SCB_EnableDCache(); - HAL_Init(); + //SCB_EnableICache(); + //SCB_EnableDCache(); - SystemClock_Config(); + HAL_Init(); - //HAL_InitTick(TICK_INT_PRIORITY); - - __HAL_RCC_GPIOA_CLK_ENABLE(); - __HAL_RCC_GPIOB_CLK_ENABLE(); - __HAL_RCC_GPIOC_CLK_ENABLE(); - __HAL_RCC_GPIOD_CLK_ENABLE(); - __HAL_RCC_GPIOE_CLK_ENABLE(); - __HAL_RCC_GPIOF_CLK_ENABLE(); - __HAL_RCC_GPIOG_CLK_ENABLE(); - __HAL_RCC_GPIOH_CLK_ENABLE(); - __HAL_RCC_GPIOI_CLK_ENABLE(); - - __HAL_RCC_ADC1_CLK_ENABLE(); - __HAL_RCC_ADC2_CLK_ENABLE(); - __HAL_RCC_ADC3_CLK_ENABLE(); - - __HAL_RCC_DMA1_CLK_ENABLE(); - __HAL_RCC_DMA2_CLK_ENABLE(); - - __HAL_RCC_TIM1_CLK_ENABLE(); - __HAL_RCC_TIM2_CLK_ENABLE(); - __HAL_RCC_TIM3_CLK_ENABLE(); - __HAL_RCC_TIM4_CLK_ENABLE(); - __HAL_RCC_TIM5_CLK_ENABLE(); - __HAL_RCC_TIM6_CLK_ENABLE(); - __HAL_RCC_TIM7_CLK_ENABLE(); - __HAL_RCC_TIM8_CLK_ENABLE(); - - __USART1_CLK_ENABLE(); - __USART2_CLK_ENABLE(); - __USART3_CLK_ENABLE(); - __UART4_CLK_ENABLE(); - __UART5_CLK_ENABLE(); - __USART6_CLK_ENABLE(); - - __HAL_RCC_CRC_CLK_ENABLE(); - + return(1); } void USBInit(void) @@ -307,4 +177,4 @@ uint32_t TimerPrescalerDivisor(uint32_t timer) { (void)(timer); return(1); -} +} \ No newline at end of file diff --git a/src/low_level_driver/stm32f7/stm32f7xx_hal_msp.c b/src/low_level_driver/stm32f7/stm32f7xx_hal_msp.c new file mode 100644 index 00000000..77f7bdf4 --- /dev/null +++ b/src/low_level_driver/stm32f7/stm32f7xx_hal_msp.c @@ -0,0 +1,90 @@ +/** + ****************************************************************************** + * File Name : stm32f7xx_hal_msp.c + * Description : This file provides code for the MSP Initialization + * and de-Initialization codes. + ****************************************************************************** + ** This notice applies to any and all portions of this file + * that are not between comment pairs USER CODE BEGIN and + * USER CODE END. Other portions of this file, whether + * inserted by the user or by software development tools + * are owned by their respective copyright owners. + * + * COPYRIGHT(c) 2017 STMicroelectronics + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ +/* Includes ------------------------------------------------------------------*/ +#include "stm32f7xx_hal.h" + +extern void _Error_Handler(char *, int); +/* USER CODE BEGIN 0 */ + +/* USER CODE END 0 */ +/** + * Initializes the Global MSP. + */ +void HAL_MspInit(void) +{ + /* USER CODE BEGIN MspInit 0 */ + + /* USER CODE END MspInit 0 */ + + HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4); + + /* System interrupt init*/ + /* MemoryManagement_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(MemoryManagement_IRQn, 0, 0); + /* BusFault_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(BusFault_IRQn, 0, 0); + /* UsageFault_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(UsageFault_IRQn, 0, 0); + /* SVCall_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(SVCall_IRQn, 0, 0); + /* DebugMonitor_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(DebugMonitor_IRQn, 0, 0); + /* PendSV_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(PendSV_IRQn, 0, 0); + /* SysTick_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0); + + /* USER CODE BEGIN MspInit 1 */ + + /* USER CODE END MspInit 1 */ +} + +/* USER CODE BEGIN 1 */ + +/* USER CODE END 1 */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ \ No newline at end of file diff --git a/src/low_level_driver/stm32f7/stm32f7xx_it.c b/src/low_level_driver/stm32f7/stm32f7xx_it.c index 528e7d2e..304ecdb4 100644 --- a/src/low_level_driver/stm32f7/stm32f7xx_it.c +++ b/src/low_level_driver/stm32f7/stm32f7xx_it.c @@ -43,7 +43,11 @@ #include "stm32f7xx_hal.h" #include "stm32f7xx.h" #include "stm32f7xx_it.h" - +#include "stm32f7xx_ll_dma.h" +#include "stm32f7xx_ll_usart.h" +#include "stm32f7xx_ll_gpio.h" +#include "stm32f7xx_ll_rcc.h" +#include "stm32f7xx_ll_bus.h" extern PCD_HandleTypeDef hpcd_USB_OTG_FS; /* Private typedef -----------------------------------------------------------*/ @@ -155,7 +159,7 @@ void OTG_FS_IRQHandler(void) void OTG_HS_IRQHandler(void) #endif { -// HAL_PCD_IRQHandler(&hpcd); + HAL_PCD_IRQHandler(&hpcd_USB_OTG_FS); } /** @@ -369,24 +373,21 @@ void DMA2_Stream2_IRQHandler(void) { callbackFunctionArray[FP_DMA2_S2](FP_DMA2_S2); } -void DMA2_Stream3_IRQHandler(void) -{ +void DMA2_Stream3_IRQHandler(void){ HAL_NVIC_ClearPendingIRQ(DMA2_Stream3_IRQn); HAL_DMA_IRQHandler(&dmaHandles[ENUM_DMA2_STREAM_3]); if (callbackFunctionArray[FP_DMA2_S3]) callbackFunctionArray[FP_DMA2_S3](FP_DMA2_S3); } -void DMA2_Stream4_IRQHandler(void) -{ +void DMA2_Stream4_IRQHandler(void){ HAL_NVIC_ClearPendingIRQ(DMA2_Stream4_IRQn); HAL_DMA_IRQHandler(&dmaHandles[ENUM_DMA2_STREAM_4]); if (callbackFunctionArray[FP_DMA2_S4]) callbackFunctionArray[FP_DMA2_S4](FP_DMA2_S4); } -void DMA2_Stream5_IRQHandler(void) -{ +void DMA2_Stream5_IRQHandler(void){ HAL_NVIC_ClearPendingIRQ(DMA2_Stream5_IRQn); HAL_DMA_IRQHandler(&dmaHandles[ENUM_DMA2_STREAM_5]); if (callbackFunctionArray[FP_DMA2_S5]) @@ -455,5 +456,42 @@ void EXTI15_10_IRQHandler(void) void ADC_IRQHandler(void) { - //HAL_ADC_IRQHandler(&adcHandleT); + //only need to use one ADC handle for now + HAL_ADC_IRQHandler(&adcHandle[board.boardADC[1].adcHandle]); } + +void USART1_IRQHandler(void) +{ + UsartIrqCallback(0); + HAL_NVIC_ClearPendingIRQ(USART1_IRQn); +} + +void USART2_IRQHandler(void) +{ + UsartIrqCallback(1); + //HAL_NVIC_ClearPendingIRQ(USART2_IRQn); +} + +void USART3_IRQHandler(void) +{ + UsartIrqCallback(2); + HAL_NVIC_ClearPendingIRQ(USART3_IRQn); +} + +void UART4_IRQHandler(void) +{ + UsartIrqCallback(3); + HAL_NVIC_ClearPendingIRQ(UART4_IRQn); +} + +void UART5_IRQHandler(void) +{ + UsartIrqCallback(4); + HAL_NVIC_ClearPendingIRQ(UART5_IRQn); +} + +void USART6_IRQHandler(void) +{ + UsartIrqCallback(5); + HAL_NVIC_ClearPendingIRQ(USART6_IRQn); +} \ No newline at end of file diff --git a/src/new_bootloader/src/scheduler.c b/src/new_bootloader/src/scheduler.c index a36a7d17..690ed4bd 100644 --- a/src/new_bootloader/src/scheduler.c +++ b/src/new_bootloader/src/scheduler.c @@ -21,7 +21,8 @@ inline void Scheduler(int32_t count) void ErrorHandler(uint32_t error) { - (void)(error); + static volatile uint32_t superError = 0; + superError = error; while (1) { DoLed(1, 1); diff --git a/src/new_bootloader/src/usb/usbd_desc.c b/src/new_bootloader/src/usb/usbd_desc.c index 1be3d525..3fadffd7 100644 --- a/src/new_bootloader/src/usb/usbd_desc.c +++ b/src/new_bootloader/src/usb/usbd_desc.c @@ -245,9 +245,9 @@ static void IntToUnicode(uint32_t value, uint8_t *pbuf, uint8_t len) */ static void Get_SerialNum(void) { - uint32_t deviceserial0 = *(uint32_t*)DEVICE_ID1; - uint32_t deviceserial1 = *(uint32_t*)DEVICE_ID2; - uint32_t deviceserial2 = *(uint32_t*)DEVICE_ID3; + uint32_t deviceserial0 = 111;//*(uint32_t*)DEVICE_ID1; + uint32_t deviceserial1 = 111;//*(uint32_t*)DEVICE_ID2; + uint32_t deviceserial2 = 111;//*(uint32_t*)DEVICE_ID3; deviceserial0 += deviceserial2; diff --git a/src/passthru/inc/includes.h b/src/passthru/inc/includes.h index b23fa465..66256732 100644 --- a/src/passthru/inc/includes.h +++ b/src/passthru/inc/includes.h @@ -1,4 +1,4 @@ -#pragma once +b #pragma once #include #include