Browse Source

boards: add UAVCAN timer override mechanism and CUAV X7 add CAN (#15348)

* X7Pro adds CAN driver
* UAVCAN timer selection moved to default.cmake
* Modify some details about @CUAVcaijie UAVCAN timer selection moved to default.cmake
* Put some timer parameters to micro_hal.h from board_config.h. Fix all h7 boards

Co-authored-by: honglang <honglang@cuav.net>
sbg
CUAVcaijie 5 years ago committed by GitHub
parent
commit
536877cf0a
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 3
      boards/cuav/nora/src/board_config.h
  2. 5
      boards/cuav/x7pro/default.cmake
  3. 3
      boards/cuav/x7pro/nuttx-config/include/board.h
  4. 3
      boards/cuav/x7pro/src/board_config.h
  5. 5
      boards/cubepilot/cubeorange/src/board_config.h
  6. 3
      boards/spracing/h7extreme/src/board_config.h
  7. 5
      cmake/px4_add_board.cmake
  8. 13
      platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/micro_hal.h
  9. 3
      src/drivers/uavcan/CMakeLists.txt

3
boards/cuav/nora/src/board_config.h

@ -153,8 +153,7 @@ @@ -153,8 +153,7 @@
/* High-resolution timer */
#define HRT_TIMER 3 /* use timer3 for the HRT */
#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */
#define STM32_RCC_APB1ENR STM32_RCC_APB1LENR
#define RCC_APB1ENR_TIM3EN RCC_APB1LENR_TIM3EN
#define HRT_PPM_CHANNEL /* T3C1 */ 1 /* use capture/compare channel 1 */
#define GPIO_PPM_IN /* PB4 T3C1 */ GPIO_TIM3_CH1IN_2

5
boards/cuav/x7pro/default.cmake

@ -9,7 +9,8 @@ px4_add_board( @@ -9,7 +9,8 @@ px4_add_board(
ROMFSROOT px4fmu_common
BUILD_BOOTLOADER
TESTING
# UAVCAN_INTERFACES 2 - No H7 or FD can support in UAVCAN
UAVCAN_INTERFACES 2
UAVCAN_TIMER_OVERRIDE 2
SERIAL_PORTS
GPS1:/dev/ttyS0
TEL1:/dev/ttyS1
@ -56,7 +57,7 @@ px4_add_board( @@ -56,7 +57,7 @@ px4_add_board(
telemetry # all available telemetry drivers
test_ppm
tone_alarm
# uavcan - No H7 or FD can support in UAVCAN yet
uavcan
MODULES
airspeed_selector
attitude_estimator_q

3
boards/cuav/x7pro/nuttx-config/include/board.h

@ -193,6 +193,9 @@ @@ -193,6 +193,9 @@
#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 /* SPI6 clock source */
#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 /* USB 1 and 2 clock source */
#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2 /* ADC 1 2 3 clock source */
#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */
#define STM32_FDCANCLK STM32_HSE_FREQUENCY
/* FLASH wait states */
#define BOARD_FLASH_WAITSTATES 2

3
boards/cuav/x7pro/src/board_config.h

@ -153,8 +153,7 @@ @@ -153,8 +153,7 @@
/* High-resolution timer */
#define HRT_TIMER 3 /* use timer3 for the HRT */
#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */
#define STM32_RCC_APB1ENR STM32_RCC_APB1LENR
#define RCC_APB1ENR_TIM3EN RCC_APB1LENR_TIM3EN
#define HRT_PPM_CHANNEL /* T3C1 */ 1 /* use capture/compare channel 1 */
#define GPIO_PPM_IN /* PB4 T3C1 */ GPIO_TIM3_CH1IN_2

5
boards/cubepilot/cubeorange/src/board_config.h

@ -107,11 +107,6 @@ @@ -107,11 +107,6 @@
#define GPIO_nVDD_5V_HIPOWER_OC /* PE10 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN10) // VDD_5V_HIPOWER_OC
/* Tone alarm output */
#define STM32_RCC_APB1ENR STM32_RCC_APB1LENR /* This is stupid and only applies for H7 */
#define STM32_RCC_APB1RSTR STM32_RCC_APB1LRSTR /* This is stupid and only applies for H7 */
#define RCC_APB1ENR_TIM2EN RCC_APB1LENR_TIM2EN /* This is stupid and only applies for H7 */
#define RCC_APB1ENR_TIM5EN RCC_APB1LENR_TIM5EN /* This is stupid and only applies for H7 */
#define RCC_APB1RSTR_TIM5RST RCC_APB1LRSTR_TIM5RST /* This is stupid and only applies for H7 */
#define TONE_ALARM_TIMER 2 /* timer 2 */
#define TONE_ALARM_CHANNEL 1 /* PA15 TIM2_CH1 */

3
boards/spracing/h7extreme/src/board_config.h

@ -111,8 +111,7 @@ @@ -111,8 +111,7 @@
/* High-resolution timer */
#define HRT_TIMER 2 /* use timer2 for the HRT */
#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */
#define STM32_RCC_APB1ENR STM32_RCC_APB1LENR
#define RCC_APB1ENR_TIM2EN RCC_APB1LENR_TIM2EN /* This is stupid and only applies for H7 */
/* RC Serial port */

5
cmake/px4_add_board.cmake

@ -142,6 +142,7 @@ function(px4_add_board) @@ -142,6 +142,7 @@ function(px4_add_board)
IO
BOOTLOADER
UAVCAN_INTERFACES
UAVCAN_TIMER_OVERRIDE
LINKER_PREFIX
MULTI_VALUE
DRIVERS
@ -221,6 +222,10 @@ function(px4_add_board) @@ -221,6 +222,10 @@ function(px4_add_board)
set(config_uavcan_num_ifaces ${UAVCAN_INTERFACES} CACHE INTERNAL "UAVCAN interfaces" FORCE)
endif()
if(UAVCAN_TIMER_OVERRIDE)
set(config_uavcan_timer_override ${UAVCAN_TIMER_OVERRIDE} CACHE INTERNAL "UAVCAN TIMER OVERRIDE" FORCE)
endif()
# OPTIONS
if(CONSTRAINED_FLASH)

13
platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/micro_hal.h

@ -38,6 +38,19 @@ @@ -38,6 +38,19 @@
__BEGIN_DECLS
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_STM32H7
#define STM32_RCC_APB1ENR STM32_RCC_APB1LENR
#define STM32_RCC_APB1RSTR STM32_RCC_APB1LRSTR
#define RCC_APB1ENR_TIM2EN RCC_APB1LENR_TIM2EN
#define RCC_APB1ENR_TIM3EN RCC_APB1LENR_TIM3EN
#define RCC_APB1ENR_TIM5EN RCC_APB1LENR_TIM5EN
#define RCC_APB1ENR_TIM14EN RCC_APB1LENR_TIM14EN
#define RCC_APB1RSTR_TIM2RST RCC_APB1LRSTR_TIM2RST
#define RCC_APB1RSTR_TIM5RST RCC_APB1LRSTR_TIM5RST
#include <chip.h>
#include <hardware/stm32_flash.h>
#include <up_internal.h> //include up_systemreset() which is included on stm32.h

3
src/drivers/uavcan/CMakeLists.txt

@ -46,6 +46,9 @@ if(CONFIG_ARCH_CHIP) @@ -46,6 +46,9 @@ if(CONFIG_ARCH_CHIP)
elseif(${CONFIG_ARCH_CHIP} MATCHES "stm32h7")
set(UAVCAN_DRIVER "stm32h7")
set(UAVCAN_TIMER 5) # The default timer is TIM5
if (DEFINED config_uavcan_timer_override)
set (UAVCAN_TIMER ${config_uavcan_timer_override})
endif()
elseif(${CONFIG_ARCH_CHIP} MATCHES "stm32")
set(UAVCAN_DRIVER "stm32")
set(UAVCAN_TIMER 5) # The default timer is TIM5

Loading…
Cancel
Save