Compare commits

...

1 Commits

Author SHA1 Message Date
Daniel Agar 77ac41f123 boards: stm32h7 enable SPI and serial DMA everywhere
- try to keep board support packages in sync
2022-01-10 10:42:13 -05:00
82 changed files with 753 additions and 1818 deletions
+4 -2
View File
@@ -46,6 +46,7 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
@@ -69,7 +70,6 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
@@ -78,8 +78,8 @@ CONFIG_MODULES_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VMOUNT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
@@ -95,6 +95,8 @@ CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PWM=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -33,17 +33,29 @@
#pragma once
// DMAMUX1
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_0 /* DMA1:81 */
#define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_0 /* DMA1:82 */
#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_0 /* DMA1:83 */
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_0 /* DMA1:84 */
// DMAMAP_TIM1UP DMAMAP_DMA12_TIM1UP_0 /* DMA1:15 */ // DSHOT 9,10,11,12
// DMAMAP_TIM4UP DMAMAP_DMA12_TIM4UP_0 /* DMA1:32 */ // DSHOT 5, 6, 7, 8
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */
#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 */ // GPS1 (RX only)
// DMAMAP_TIM5UP DMAMAP_DMA12_TIM5UP_0 /* DMA1:59 */ // DSHOT 1, 2, 3, 4
// DMAMUX2 (BDMA)
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */
// DMAMUX2
#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* DMA2:43 */ // TELEM1 RX
#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_1 /* DMA2:44 */ // TELEM1 TX
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_1 /* DMA2:71 */ // TELEM2 RX
#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_1 /* DMA2:72 */ // TELEM2 TX
#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* DMA2:79 */ // CONSOLE (RX only)
#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_1 /* DMA2:81 */ // RC (RX only)
#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_1 /* DMA2:83 */
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* DMA2:84 */
// BDMA
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */
+10 -5
View File
@@ -53,7 +53,6 @@ CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x3163
CONFIG_CDCACM_VENDORSTR="CUAV"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_SYMBOLS=y
@@ -61,6 +60,7 @@ CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_EXAMPLES_CALIB_UDELAY=y
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
@@ -83,7 +83,6 @@ CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
@@ -103,9 +102,6 @@ CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_DISABLE_IFCONFIG=y
CONFIG_NSH_DISABLE_IFUPDOWN=y
CONFIG_NSH_DISABLE_TELNETD=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
@@ -181,6 +177,8 @@ CONFIG_STM32H7_SPI1=y
CONFIG_STM32H7_SPI1_DMA=y
CONFIG_STM32H7_SPI1_DMA_BUFFER=1024
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI2_DMA=y
CONFIG_STM32H7_SPI2_DMA_BUFFER=1024
CONFIG_STM32H7_SPI4=y
CONFIG_STM32H7_SPI4_DMA=y
CONFIG_STM32H7_SPI4_DMA_BUFFER=1024
@@ -216,24 +214,31 @@ CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_RXDMA=y
CONFIG_UART7_SERIAL_CONSOLE=y
CONFIG_UART7_TXBUFSIZE=1500
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_RXDMA=y
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_RXDMA=y
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_RXDMA=y
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART2_TXDMA=y
CONFIG_USART6_BAUD=57600
CONFIG_USART6_IFLOWCONTROL=y
CONFIG_USART6_OFLOWCONTROL=y
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_RXDMA=y
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USART6_TXDMA=y
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
+1 -1
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
+1 -1
View File
@@ -94,7 +94,7 @@
//#define USE_VBUS_PULL_DOWN
#define INTERFACE_USART 1
#define INTERFACE_USART_CONFIG "/dev/ttyS4,57600"
#define INTERFACE_USART_CONFIG "/dev/ttyS4,115200"
#define BOOT_DELAY_ADDRESS 0x000001a0
#define BOARD_TYPE 1009
#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880)
+12 -11
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,11 +34,11 @@
/**
* @file init.c
*
* FMU-specific early startup code. This file implements the
* board-specific early startup code. This file implements the
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialisation.
* subsystems and perform board-specific initialization.
*/
#include "board_config.h"
@@ -60,8 +60,6 @@
#include <px4_platform/gpio.h>
#include <px4_platform/board_dma_alloc.h>
#include <mpu.h>
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
@@ -78,7 +76,6 @@ __EXPORT void board_peripheral_reset(int ms)
{
/* set the peripheral rails off */
VDD_5V_PERIPH_EN(false);
board_control_spi_sensors_power(false, 0xffff);
bool last = READ_SPEKTRUM_POWER();
/* Keep Spektum on to discharge rail*/
@@ -92,7 +89,6 @@ __EXPORT void board_peripheral_reset(int ms)
/* switch the peripheral rail back on */
SPEKTRUM_POWER(last);
board_control_spi_sensors_power(true, 0xffff);
VDD_5V_PERIPH_EN(true);
}
@@ -132,14 +128,14 @@ __EXPORT void stm32_boardinitialize(void)
/* Reset PWM first thing */
board_on_reset(-1);
/* configure LEDs */
board_autoled_initialize();
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
board_control_spi_sensors_power_configgpio();
/* configure LEDs */
board_autoled_initialize();
}
/****************************************************************************
@@ -179,6 +175,12 @@ __EXPORT int board_app_initialize(uintptr_t arg)
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
#if defined(SERIAL_HAVE_RXDMA)
// set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
static struct hrt_call serial_dma_call;
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
#endif
/* initial LED state */
drv_led_start();
led_off(LED_RED);
@@ -212,7 +214,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
#endif /* CONFIG_MMCSD */
/* Configure the HW based on the manifest */
px4_platform_configure();
return OK;
+3 -2
View File
@@ -47,6 +47,7 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
@@ -70,7 +71,6 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
@@ -79,8 +79,8 @@ CONFIG_MODULES_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VMOUNT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
@@ -98,6 +98,7 @@ CONFIG_SYSTEMCMDS_PWM=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
-1
View File
@@ -20,6 +20,5 @@ param set-default SENS_TEMP_ID 6946850
# Set Camera trigger pins to 13/14
param set-default TRIG_PINS_EX 12288
rgbled_pwm start
safety_button start
@@ -220,6 +220,7 @@
#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE
/* UART/USART */
#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */
#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */
@@ -243,12 +244,14 @@
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
/* CAN */
#define GPIO_CAN1_RX GPIO_CAN1_RX_5 /* PI9 */
#define GPIO_CAN1_TX GPIO_CAN1_TX_4 /* PH13 */
#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */
#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */
/* SPI */
#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz))
@@ -272,6 +275,7 @@
#define GPIO_SPI6_MISO GPIO_SPI6_MISO_1 /* PG12 */
#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_2 /* PA7 */
/* I2C */
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -33,17 +33,29 @@
#pragma once
// DMAMUX1
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_0 /* DMA1:81 */
#define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_0 /* DMA1:82 */
#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_0 /* DMA1:83 */
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_0 /* DMA1:84 */
// DMAMAP_TIM1UP DMAMAP_DMA12_TIM1UP_0 /* DMA1:15 */ // DSHOT 9,10,11,12
// DMAMAP_TIM4UP DMAMAP_DMA12_TIM4UP_0 /* DMA1:32 */ // DSHOT 5, 6, 7, 8
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */
#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 */ // GPS1 (RX only)
// DMAMAP_TIM5UP DMAMAP_DMA12_TIM5UP_0 /* DMA1:59 */ // DSHOT 1, 2, 3, 4
// DMAMUX2 (BDMA)
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */
// DMAMUX2
#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* DMA2:43 */ // TELEM1 RX
#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_1 /* DMA2:44 */ // TELEM1 TX
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_1 /* DMA2:71 */ // TELEM2 RX
#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_1 /* DMA2:72 */ // TELEM2 TX
#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* DMA2:79 */ // CONSOLE (RX only)
#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_1 /* DMA2:81 */ // RC (RX only)
#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_1 /* DMA2:83 */
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* DMA2:84 */
// BDMA
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */
+9 -3
View File
@@ -102,9 +102,6 @@ CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_DISABLE_IFCONFIG=y
CONFIG_NSH_DISABLE_IFUPDOWN=y
CONFIG_NSH_DISABLE_TELNETD=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
@@ -180,6 +177,8 @@ CONFIG_STM32H7_SPI1=y
CONFIG_STM32H7_SPI1_DMA=y
CONFIG_STM32H7_SPI1_DMA_BUFFER=1024
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI2_DMA=y
CONFIG_STM32H7_SPI2_DMA_BUFFER=1024
CONFIG_STM32H7_SPI4=y
CONFIG_STM32H7_SPI4_DMA=y
CONFIG_STM32H7_SPI4_DMA_BUFFER=1024
@@ -215,24 +214,31 @@ CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_RXDMA=y
CONFIG_UART7_SERIAL_CONSOLE=y
CONFIG_UART7_TXBUFSIZE=1500
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_RXDMA=y
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_RXDMA=y
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_RXDMA=y
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART2_TXDMA=y
CONFIG_USART6_BAUD=57600
CONFIG_USART6_IFLOWCONTROL=y
CONFIG_USART6_OFLOWCONTROL=y
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_RXDMA=y
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USART6_TXDMA=y
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
+2 -8
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -109,7 +109,6 @@
/* PWM */
#define DIRECT_PWM_OUTPUT_CHANNELS 14
#define BOARD_NUM_IO_TIMERS 4
/* Power supply control and monitoring GPIOs */
#define BOARD_NUMBER_BRICKS 2
@@ -192,14 +191,9 @@
#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_nVDD_5V_PERIPH_OC))
#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_OC))
/* This board provides a DMA pool and APIs */
#define BOARD_NUM_IO_TIMERS 4
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
/* This board provides the board_on_reset interface */
#define BOARD_HAS_ON_RESET 1
#define BOARD_ENABLE_CONSOLE_BUFFER
#define PX4_GPIO_INIT_LIST { \
+1 -1
View File
@@ -94,7 +94,7 @@
//#define USE_VBUS_PULL_DOWN
#define INTERFACE_USART 1
#define INTERFACE_USART_CONFIG "/dev/ttyS4,57600"
#define INTERFACE_USART_CONFIG "/dev/ttyS4,115200"
#define BOOT_DELAY_ADDRESS 0x000001a0
#define BOARD_TYPE 1010
#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880)
+12 -11
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,11 +34,11 @@
/**
* @file init.c
*
* FMU-specific early startup code. This file implements the
* board-specific early startup code. This file implements the
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialisation.
* subsystems and perform board-specific initialization.
*/
#include "board_config.h"
@@ -60,8 +60,6 @@
#include <px4_platform/gpio.h>
#include <px4_platform/board_dma_alloc.h>
#include <mpu.h>
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
@@ -78,7 +76,6 @@ __EXPORT void board_peripheral_reset(int ms)
{
/* set the peripheral rails off */
VDD_5V_PERIPH_EN(false);
board_control_spi_sensors_power(false, 0xffff);
bool last = READ_SPEKTRUM_POWER();
/* Keep Spektum on to discharge rail*/
@@ -92,7 +89,6 @@ __EXPORT void board_peripheral_reset(int ms)
/* switch the peripheral rail back on */
SPEKTRUM_POWER(last);
board_control_spi_sensors_power(true, 0xffff);
VDD_5V_PERIPH_EN(true);
}
@@ -132,14 +128,14 @@ __EXPORT void stm32_boardinitialize(void)
/* Reset PWM first thing */
board_on_reset(-1);
/* configure LEDs */
board_autoled_initialize();
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
board_control_spi_sensors_power_configgpio();
/* configure LEDs */
board_autoled_initialize();
}
/****************************************************************************
@@ -179,6 +175,12 @@ __EXPORT int board_app_initialize(uintptr_t arg)
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
#if defined(SERIAL_HAVE_RXDMA)
// set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
static struct hrt_call serial_dma_call;
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
#endif
/* initial LED state */
drv_led_start();
led_off(LED_RED);
@@ -212,7 +214,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
#endif /* CONFIG_MMCSD */
/* Configure the HW based on the manifest */
px4_platform_configure();
return OK;
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -33,12 +33,23 @@
#pragma once
// DMAMUX1
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
// DMAMAP_TIM1UP DMAMAP_DMA12_TIM1UP_0 /* DMA1:15 */ // DSHOT 1, 2, 3, 4
// DMAMAP_TIM4UP DMAMAP_DMA12_TIM4UP_0 /* DMA1:32 */ // DSHOT 5, 6
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_0 /* DMA1:43 */ // TELEM1 RX
#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_0 /* DMA1:44 */ // TELEM1 TX
#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 */ // TELEM2 RX
#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 */ // TELEM2 TX
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_1 /* DMA1:71 */
#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_1 /* DMA1:72 */
#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_0 /* DMA1:83 */
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_0 /* DMA1:84 */
// DMAMUX2
#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_1 /* DMA2:63 */ // GPS1 RX
#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_1 /* DMA2:64 */ // GPS1 TX
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_1 /* DMA2:71 */ // PX4IO RX
#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_1 /* DMA2:72 */ // PX4IO TX
#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* DMA2:79 */ // console (RX only)
#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_1 /* DMA2:83 */
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* DMA2:84 */
@@ -54,7 +54,6 @@ CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x2DAE
CONFIG_CDCACM_VENDORSTR="CubePilot"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_SYMBOLS=y
@@ -62,6 +61,7 @@ CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_EXAMPLES_CALIB_UDELAY=y
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
@@ -84,7 +84,6 @@ CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
@@ -204,9 +203,12 @@ CONFIG_TTY_SIGINT_CHAR=0x03
CONFIG_TTY_SIGTSTP=y
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_RXDMA=y
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART4_TXDMA=y
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_RXDMA=y
CONFIG_UART7_TXBUFSIZE=1500
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
@@ -215,15 +217,21 @@ CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART2_RXDMA=y
CONFIG_USART2_TXBUFSIZE=3000
CONFIG_USART2_TXDMA=y
CONFIG_USART3_BAUD=57600
CONFIG_USART3_IFLOWCONTROL=y
CONFIG_USART3_OFLOWCONTROL=y
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_RXDMA=y
CONFIG_USART3_TXBUFSIZE=3000
CONFIG_USART3_TXDMA=y
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_RXDMA=y
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USART6_TXDMA=y
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
@@ -201,9 +201,12 @@ CONFIG_TTY_SIGINT=y
CONFIG_TTY_SIGTSTP=y
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_RXDMA=y
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART4_TXDMA=y
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_RXDMA=y
CONFIG_UART7_SERIAL_CONSOLE=y
CONFIG_UART7_TXBUFSIZE=1500
CONFIG_UART8_BAUD=57600
@@ -213,15 +216,21 @@ CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART2_RXDMA=y
CONFIG_USART2_TXBUFSIZE=3000
CONFIG_USART2_TXDMA=y
CONFIG_USART3_BAUD=57600
CONFIG_USART3_IFLOWCONTROL=y
CONFIG_USART3_OFLOWCONTROL=y
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_RXDMA=y
CONFIG_USART3_TXBUFSIZE=3000
CONFIG_USART3_TXDMA=y
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_RXDMA=y
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USART6_TXDMA=y
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
+9 -5
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -38,7 +38,7 @@
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialisation.
* subsystems and perform board-specific initialization.
*/
#include "board_config.h"
@@ -60,8 +60,6 @@
#include <px4_platform/gpio.h>
#include <px4_platform/board_dma_alloc.h>
#include <mpu.h>
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
@@ -126,6 +124,7 @@ __EXPORT void stm32_boardinitialize(void)
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
board_control_spi_sensors_power_configgpio();
/* configure LEDs */
@@ -166,6 +165,12 @@ __EXPORT int board_app_initialize(uintptr_t arg)
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
#if defined(SERIAL_HAVE_RXDMA)
// set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
static struct hrt_call serial_dma_call;
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
#endif
/* initial LED state */
drv_led_start();
led_off(LED_AMBER);
@@ -192,7 +197,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
#endif /* CONFIG_MMCSD */
/* Configure the HW based on the manifest */
px4_platform_configure();
return OK;
-1
View File
@@ -42,7 +42,6 @@
#include <nuttx/usb/usbdev_trace.h>
#include <stm32_otg.h>
#include <debug.h>
#include <syslog.h>
/************************************************************************************
* Name: stm32_usbsuspend
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -33,13 +33,28 @@
#pragma once
// DMAMUX1
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_0 /* DMA1:81 */
#define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_0 /* DMA1:82 */
// DMAMUX1
// DMAMAP_TIM1UP DMAMAP_DMA12_TIM1UP_0 /* DMA1:15 */ // DSHOT 1, 2, 3, 4
// DMAMAP_TIM4UP DMAMAP_DMA12_TIM4UP_0 /* DMA1:32 */ // DSHOT 5, 6
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 */ // GPS1 RX
#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 */ // GPS2 RX
#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_0 /* DMA1:43 */ // TELEM1 RX
#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_0 /* DMA1:44 */ // TELEM1 TX
// DMAMUX2
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */
#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* DMA2:45 */ // TELEM2 RX
#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* DMA2:46 */ // TELEM2 TX
#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_1 /* DMA2:63 */ // TELEM4 RX
#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_1 /* DMA2:64 */ // TELEM4 TX
#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* DMA2:79 */ // console (RX only)
#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_1 /* DMA2:81 */ // PX4IO RX
#define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_1 /* DMA2:82 */ // PX4IO TX
// BDMA
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */
@@ -209,27 +209,38 @@ CONFIG_TTY_SIGINT=y
CONFIG_TTY_SIGTSTP=y
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_RXDMA=y
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART4_TXDMA=y
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_RXDMA=y
CONFIG_UART7_SERIAL_CONSOLE=y
CONFIG_UART7_TXBUFSIZE=1500
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_RXDMA=y
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_UART8_TXDMA=y
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_RXDMA=y
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART1_TXDMA=y
CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_RXDMA=y
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART2_TXDMA=y
CONFIG_USART3_BAUD=57600
CONFIG_USART3_IFLOWCONTROL=y
CONFIG_USART3_OFLOWCONTROL=y
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_RXDMA=y
CONFIG_USART3_TXBUFSIZE=3000
CONFIG_USART3_TXDMA=y
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_TXBUFSIZE=1500
+10 -62
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012-2019 PX4 Development Team. All rights reserved.
* Copyright (c) 2019-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,35 +34,21 @@
/**
* @file init.c
*
* PX4FMU-specific early startup code. This file implements the
* board-specific early startup code. This file implements the
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialisation.
* subsystems and perform board-specific initialization.
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include "board_config.h"
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
#include <debug.h>
#include <errno.h>
#include <syslog.h>
#include <nuttx/config.h>
#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include <nuttx/analog/adc.h>
#include <nuttx/mm/gran.h>
#include <chip.h>
#include <stm32_uart.h>
#include <arch/board/board.h>
#include "arm_internal.h"
@@ -75,28 +61,12 @@
#include <px4_platform/board_determine_hw_info.h>
#include <px4_platform/board_dma_alloc.h>
#include <mpu.h>
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/*
* Ideally we'd be able to get these from arm_internal.h,
* but since we want to be able to disable the NuttX use
* of leds for system indication at will and there is no
* separate switch, we need to build independent of the
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
__END_DECLS
/************************************************************************************
* Name: board_peripheral_reset
*
@@ -106,9 +76,7 @@ __END_DECLS
__EXPORT void board_peripheral_reset(int ms)
{
/* set the peripheral rails off */
VDD_5V_PERIPH_EN(false);
board_control_spi_sensors_power(false, 0xffff);
bool last = READ_VDD_3V3_SPEKTRUM_POWER_EN();
/* Keep Spektum on to discharge rail*/
@@ -122,9 +90,7 @@ __EXPORT void board_peripheral_reset(int ms)
/* switch the peripheral rail back on */
VDD_3V3_SPEKTRUM_POWER_EN(last);
board_control_spi_sensors_power(true, 0xffff);
VDD_5V_PERIPH_EN(true);
}
/************************************************************************************
@@ -158,27 +124,22 @@ __EXPORT void board_on_reset(int status)
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void
stm32_boardinitialize(void)
__EXPORT void stm32_boardinitialize(void)
{
board_on_reset(-1); /* Reset PWM first thing */
/* configure LEDs */
board_autoled_initialize();
/* Reset PWM first thing */
board_on_reset(-1);
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
board_control_spi_sensors_power_configgpio();
/* configure USB interfaces */
stm32_usbinitialize();
/* configure LEDs */
board_autoled_initialize();
}
/****************************************************************************
@@ -192,21 +153,13 @@ stm32_boardinitialize(void)
* Input Parameters:
* arg - The boardctl() argument is passed to the board_app_initialize()
* implementation without modification. The argument has no
* meaning to NuttX; the meaning of the argument is a contract
* between the board-specific initalization logic and the the
* matching application logic. The value cold be such things as a
* mode enumeration value, a set of DIP switch switch settings, a
* pointer to configuration data read from a file or serial FLASH,
* or whatever you would like to do with it. Every implementation
* should accept zero/NULL as a default configuration.
* meaning to NuttX;
*
* Returned Value:
* Zero (OK) is returned on success; a negated errno value is returned on
* any failure to indicate the nature of the failure.
*
****************************************************************************/
__EXPORT int board_app_initialize(uintptr_t arg)
{
/* Power on Interfaces */
@@ -216,10 +169,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
VDD_3V3_SPEKTRUM_POWER_EN(true);
/* Need hrt running before using the ADC */
px4_platform_init();
if (OK == board_determine_hw_info()) {
syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(),
board_get_hw_type_name());
@@ -229,11 +180,9 @@ __EXPORT int board_app_initialize(uintptr_t arg)
}
/* configure SPI interfaces (after we determined the HW version) */
stm32_spiinitialize();
/* configure the DMA allocator */
if (board_dma_alloc_init() < 0) {
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
@@ -254,12 +203,12 @@ __EXPORT int board_app_initialize(uintptr_t arg)
led_on(LED_RED);
}
#ifdef CONFIG_MMCSD
// Ensure Power is off for > 10 mS
usleep(15 * 1000);
VDD_3V3_SD_CARD_EN(true);
usleep(500 * 1000);
#ifdef CONFIG_MMCSD
int ret = stm32_sdio_initialize();
if (ret != OK) {
@@ -269,7 +218,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
#endif /* CONFIG_MMCSD */
/* Configure the HW based on the manifest */
px4_platform_configure();
return OK;
+3 -3
View File
@@ -12,8 +12,8 @@ CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
@@ -28,6 +28,7 @@ CONFIG_DRIVERS_UAVCAN=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_EVENTS=y
@@ -47,14 +48,13 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VMOUNT=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
@@ -1,17 +0,0 @@
#
# For a description of the syntax of this configuration file,
# see misc/tools/kconfig-language.txt.
#
config BOARD_HAS_PROBES
bool "Board provides GPIO or other Hardware for signaling to timing analyze."
default y
---help---
This board provides GPIO FMU-CH1-5, CAP1-6 as PROBE_1-11 to provide timing signals from selected drivers.
config BOARD_USE_PROBES
bool "Enable the use the board provided FMU-CH1-5, CAP1-6 as PROBE_1-11"
default n
depends on BOARD_HAS_PROBES
---help---
Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers.
@@ -52,7 +52,6 @@ CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_LIB_BOARDCTL=y
CONFIG_FS_PROCFS_MAX_TASKS=8
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_PREALLOC_TIMERS=50
@@ -1,7 +1,7 @@
/************************************************************************************
* nuttx-configs/px4_fmu-v6u/include/board.h
* nuttx-config/include/board.h
*
* Copyright (C) 2016-2019 Gregory Nutt. All rights reserved.
* Copyright (C) 2020 Gregory Nutt. All rights reserved.
* Authors: David Sidrane <david.sidrane@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
@@ -32,12 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H
#define __NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H
/************************************************************************************
* Included Files
************************************************************************************/
#pragma once
#include "board_dma_map.h"
@@ -50,12 +45,8 @@
#include "stm32_rcc.h"
#include "stm32_sdmmc.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Clocking *************************************************************************/
/* The MatekH743-Slim board provides the following clock sources:
/* The board provides the following clock sources:
*
* X1: 8 MHz crystal for HSE
*
@@ -64,13 +55,12 @@
* HSI: 64 MHz RC factory-trimmed
* HSE: 8 MHz crystal for HSE
*/
#define STM32_BOARD_XTAL 8000000ul
#define STM32_HSI_FREQUENCY 16000000ul
#define STM32_LSI_FREQUENCY 32000
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
#define STM32_LSE_FREQUENCY 32768
#define STM32_LSE_FREQUENCY 0
/* Main PLL Configuration.
*
@@ -105,12 +95,7 @@
* PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz
* PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz
*/
#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \
RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \
RCC_PLLCFGR_DIVP1EN | \
RCC_PLLCFGR_DIVQ1EN | \
RCC_PLLCFGR_DIVR1EN)
#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE|RCC_PLLCFGR_PLL1RGE_4_8_MHZ|RCC_PLLCFGR_DIVP1EN|RCC_PLLCFGR_DIVQ1EN|RCC_PLLCFGR_DIVR1EN)
#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1)
#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(120)
#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2)
@@ -123,12 +108,7 @@
#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8)
/* PLL2 */
#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \
RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \
RCC_PLLCFGR_DIVP2EN | \
RCC_PLLCFGR_DIVQ2EN | \
RCC_PLLCFGR_DIVR2EN)
#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE|RCC_PLLCFGR_PLL2RGE_4_8_MHZ|RCC_PLLCFGR_DIVP2EN|RCC_PLLCFGR_DIVQ2EN|RCC_PLLCFGR_DIVR2EN)
#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(2)
#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48)
#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2)
@@ -141,10 +121,7 @@
#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
/* PLL3 */
#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \
RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \
RCC_PLLCFGR_DIVQ3EN)
#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE|RCC_PLLCFGR_PLL3RGE_4_8_MHZ|RCC_PLLCFGR_DIVQ3EN)
#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(2)
#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48)
#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2)
@@ -159,7 +136,6 @@
/* SYSCLK = PLL1P = 480MHz
* CPUCLK = SYSCLK / 1 = 480 MHz
*/
#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK)
#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY)
#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1)
@@ -169,36 +145,30 @@
/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max)
* HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240
*/
#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */
#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */
#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */
#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */
#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */
#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */
#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */
#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */
#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* Timer clock frequencies */
/* Timers driven from APB1 will be twice PCLK1 */
#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
@@ -210,7 +180,6 @@
#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
/* Timers driven from APB2 will be twice PCLK2 */
#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY)
@@ -218,76 +187,29 @@
#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY)
/* Kernel Clock Configuration
*
* Note: look at Table 54 in ST Manual
* Note: look at Table 54 in ST Manual
*/
/* I2C123 clock source */
#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI
/* I2C4 clock source */
#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI
/* SPI123 clock source */
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2
/* SPI45 clock source */
#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2
/* SPI6 clock source */
#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2
/* USB 1 and 2 clock source */
#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3
/* ADC 1 2 3 clock source */
#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2
/* FDCAN 1 clock source */
#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI /* I2C123 clock source */
#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI /* I2C4 clock source */
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 /* SPI123 clock source */
#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 /* SPI45 clock source */
#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
*
* ------------ ---------- -----------
* Vcore MAX ACLK WAIT STATES
* ------------ ---------- -----------
* 1.15-1.26 V 70 MHz 0
* (VOS1 level) 140 MHz 1
* 210 MHz 2
* 1.05-1.15 V 55 MHz 0
* (VOS2 level) 110 MHz 1
* 165 MHz 2
* 220 MHz 3
* 0.95-1.05 V 45 MHz 0
* (VOS3 level) 90 MHz 1
* 135 MHz 2
* 180 MHz 3
* 225 MHz 4
* ------------ ---------- -----------
*/
/* FLASH wait states */
#define BOARD_FLASH_WAITSTATES 2
/* SDMMC definitions ********************************************************/
/* Init 480kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */
#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq)
* div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s
*/
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#else
@@ -301,55 +223,8 @@
#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE
/* LED definitions ******************************************************************/
/* The board has two, LED_GREEN a Green LED and LED_BLUE a Blue LED,
* that can be controlled by software.
*
* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way.
* The following definitions are used to access individual LEDs.
*/
/* LED index values for use with board_userled() */
#define BOARD_LED1 0
#define BOARD_LED2 1
#define BOARD_NLEDS 2
#define BOARD_LED_BLUE BOARD_LED1
#define BOARD_LED_GREEN BOARD_LED2
/* LED bits for use with board_userled_all() */
#define BOARD_LED1_BIT (1 << BOARD_LED1)
#define BOARD_LED2_BIT (1 << BOARD_LED2)
/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in
* include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related
* events as follows:
*
*
* SYMBOL Meaning LED state
* Red Green Blue
* ---------------------- -------------------------- ------ ------ ----*/
#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */
#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */
#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */
#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */
#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */
#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */
#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */
#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */
#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */
/* Thus if the Green LED is statically on, NuttX has successfully booted and
* is, apparently, running normally. If the Red LED is flashing at
* approximately 2Hz, then a fatal error has been detected and the system
* has halted.
*/
/* Alternate function pin selections ************************************************/
/* UART/USART */
#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PA10 */
#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PA9 */
@@ -374,59 +249,38 @@
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
/* CAN
*
* CAN1 is routed to transceiver.
*/
/* CAN */
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
/* SPI
*
* SPI1 is MPU6000
* SPI2 is MAX7456
* SPI3 is extern with PD4 and PE2 as CS
* SPI4 is ICM20602
*/
/* SPI */
#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz))
#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */
#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */
#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_4) /* PB13 */
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 /* PB15 */
#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_4) /* PB13 */
#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_1) /* PB3 */
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_1 /* PB4 */
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_4 /* PB5 */
#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_1) /* PB3 */
#define GPIO_SPI4_SCK ADJ_SLEW_RATE(GPIO_SPI4_SCK_1) /* PE12 */
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 /* PE13 */
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1 /* PE14 */
#define GPIO_SPI4_SCK ADJ_SLEW_RATE(GPIO_SPI4_SCK_1) /* PE12 */
/* I2C
*
* The optional _GPIO configurations allow the I2C driver to manually
* reset the bus to clear stuck slaves. They match the pin configuration,
* but are normally-high GPIOs.
*
*/
/* I2C */
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1 /* PB6 */
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 /* PB7 */
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN6)
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7)
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 /* PB10 */
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 /* PB11 */
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10)
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN11)
/* SDMMC1
*
@@ -444,50 +298,3 @@
// #define GPIO_SDMMC1_D3 GPIO_SDMMC1_D3 /* PC11 */
// #define GPIO_SDMMC1_CK GPIO_SDMMC1_CK /* PC12 */
// #define GPIO_SDMMC1_CMD GPIO_SDMMC1_CMD /* PD2 */
/* USB
*
* OTG_FS_DM PA11
* OTG_FS_DP PA12
* VBUS PA9
*/
/* Board provides GPIO or other Hardware for signaling to timing analyzer */
#if defined(CONFIG_BOARD_USE_PROBES)
# include "stm32_gpio.h"
# define PROBE_N(n) (1<<((n)-1))
# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 AUX1 */
# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */
# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */
# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 AUX4 */
# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */
# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */
# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 AUX7 */
# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */
# define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 CAP1 */
# define PROBE_INIT(mask) \
do { \
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \
if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \
if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \
if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \
if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \
if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \
} while(0)
# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)
#else
# define PROBE_INIT(mask)
# define PROBE(n,s)
# define PROBE_MARK(n)
#endif
#endif /*__NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H */
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
* Copyright (c) 2021-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -33,11 +33,15 @@
#pragma once
// DMAMUX1
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
// DMAMAP_TIM3UP DMAMAP_DMA12_TIM3UP_0 /* DMA1:27 */ // DSHOT 1, 2
// DMAMAP_TIM4UP DMAMAP_DMA12_TIM4UP_0 /* DMA1:32 */ // DSHOT 7, 8
// DMAMAP_TIM5UP DMAMAP_DMA12_TIM5UP_0 /* DMA1:59 */ // DSHOT 3, 4, 5, 6
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
// DMAMUX2
#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_1 /* DMA2:83 */
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* DMA2:84 */
#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_1 /* DMA2:83 */
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* DMA2:84 */
@@ -48,7 +48,6 @@ else()
i2c.cpp
init.c
led.c
sdio.c
spi.cpp
timer_config.cpp
usb.c
@@ -58,7 +57,6 @@ else()
target_link_libraries(drivers_board
PRIVATE
arch_spi
arch_board_hw_info
drivers__led
nuttx_arch
nuttx_drivers
+41 -112
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
* Copyright (c) 2021-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -39,25 +39,15 @@
#pragma once
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
#include <stm32_gpio.h>
/****************************************************************************************************
* Definitions
****************************************************************************************************/
// #define FLASH_BASED_PARAMS
/* LEDs */
/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */
#define GPIO_nLED_BLUE /* PE3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
#define GPIO_nLED_GREEN /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
@@ -65,57 +55,39 @@
#define BOARD_ARMED_STATE_LED 1 // Green LED
#define BOARD_OVERLOAD_LED 0 // Blue LED
/*
* ADC channels
*
* These are the channel numbers of the ADCs of the microcontroller that
* can be used by the Px4 Firmware in the adc driver
*/
/* ADC defines to be used in sensors.cpp to read from a particular channel */
#define ADC1_CH(n) (n)
/* Define GPIO pins used as ADC N.B. Channel numbers must match below */
/* ADC channels */
#define PX4_ADC_GPIO \
/* PC0 */ GPIO_ADC123_INP10, \
/* PC1 */ GPIO_ADC123_INP11, \
/* PA4 */ GPIO_ADC12_INP18, \
/* PA7 */ GPIO_ADC12_INP7, \
/* PC4 */ GPIO_ADC12_INP4, \
/* PA4 */ GPIO_ADC12_INP18, \
/* PA7 */ GPIO_ADC12_INP7, \
/* PC4 */ GPIO_ADC12_INP4, \
/* PC5 */ GPIO_ADC12_INP8
/* Define Channel numbers must match above GPIO pin IN(n)*/
#define ADC_BATTERY_VOLTAGE_CHANNEL /* PC0 */ ADC1_CH(10)
#define ADC_BATTERY_CURRENT_CHANNEL /* PC1 */ ADC1_CH(11)
#define ADC_BATTERY2_VOLTAGE_CHANNEL /* PA4 */ ADC1_CH(18)
#define ADC_BATTERY2_CURRENT_CHANNEL /* PA7 */ ADC1_CH(7)
#define ADC_AIRSPEED_IN_CHANNEL /* PC4 */ ADC1_CH(4)
#define ADC_RSSI_IN_CHANNEL /* PC5 */ ADC1_CH(8)
/* Define Channel numbers must match above GPIO pins */
#define ADC_BATTERY1_VOLTAGE_CHANNEL 10 /* PC0 */
#define ADC_BATTERY1_CURRENT_CHANNEL 11 /* PC1 */
#define ADC_BATTERY2_VOLTAGE_CHANNEL 18 /* PA4 */
#define ADC_BATTERY2_CURRENT_CHANNEL 7 /* PA7 */
#define ADC_AIRSPEED_IN_CHANNEL 4 /* PC4 */
#define ADC_RSSI_IN_CHANNEL 8 /* PC5 */
#define ADC_CHANNELS \
((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \
(1 << ADC_BATTERY_CURRENT_CHANNEL) | \
(1 << ADC_BATTERY2_VOLTAGE_CHANNEL) | \
(1 << ADC_BATTERY2_CURRENT_CHANNEL) | \
((1 << ADC_BATTERY1_VOLTAGE_CHANNEL) | \
(1 << ADC_BATTERY1_CURRENT_CHANNEL) | \
(1 << ADC_BATTERY2_VOLTAGE_CHANNEL) | \
(1 << ADC_BATTERY2_CURRENT_CHANNEL) | \
(1 << ADC_AIRSPEED_IN_CHANNEL) | \
(1 << ADC_RSSI_IN_CHANNEL))
/* CAN Silence
*
* Silent mode control \ ESC Mux select
*/
/* CAN Silence Silent mode control */
#define GPIO_CAN1_SILENT_S0 /* PD3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN3)
/* PWM
*/
/* PWM */
#define DIRECT_PWM_OUTPUT_CHANNELS 8
#define DIRECT_INPUT_TIMER_CHANNELS 8
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
/* Power supply control and monitoring GPIOs */
#define BOARD_NUMBER_BRICKS 2
/* Spare GPIO */
@@ -125,7 +97,6 @@
/* Tone alarm output */
#define GPIO_TONE_ALARM_IDLE /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
#define GPIO_TONE_ALARM_GPIO /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
@@ -136,13 +107,10 @@
/* USB OTG FS
*
* PE2 OTG_FS_VBUS VBUS sensing
*/
#define GPIO_OTGFS_VBUS /* PE2 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN2)
/* High-resolution timer */
#define HRT_TIMER 2 /* use timer8 for the HRT */
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 3 */
@@ -154,75 +122,36 @@
// #define GPIO_RSSI_IN /* PC5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN5)
/* SD Card */
#define SDIO_SLOTNO 0 /* Only one slot */
#define SDIO_MINOR 0
/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
/* This board provides the board_on_reset interface */
#define BOARD_HAS_ON_RESET 1
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \
GPIO_CAN1_TX, \
GPIO_CAN1_RX, \
GPIO_CAN1_SILENT_S0, \
GPIO_nLED_BLUE, \
GPIO_nLED_GREEN, \
GPIO_TONE_ALARM_IDLE, \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
#define BOARD_ADC_BRICK1_VALID (1)
#define BOARD_ADC_BRICK2_VALID (1)
#define BOARD_NUM_IO_TIMERS 4
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
#define BOARD_HAS_ON_RESET 1
#define BOARD_ENABLE_CONSOLE_BUFFER
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \
GPIO_CAN1_TX, \
GPIO_CAN1_RX, \
GPIO_CAN1_SILENT_S0, \
GPIO_nLED_BLUE, \
GPIO_nLED_GREEN, \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D0), \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D1), \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D2), \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D3), \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_CMD),\
GPIO_TONE_ALARM_IDLE, \
GPIO_OTGFS_VBUS, \
}
__BEGIN_DECLS
/****************************************************************************************************
* Public Types
****************************************************************************************************/
/****************************************************************************************************
* Public data
****************************************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************************************
* Public Functions
****************************************************************************************************/
/****************************************************************************
* Name: stm32_sdio_initialize
*
* Description:
* Initialize SDIO-based MMC/SD card support
*
****************************************************************************/
int stm32_sdio_initialize(void);
/****************************************************************************************************
* Name: stm32_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the board.
*
****************************************************************************************************/
extern void stm32_spiinitialize(void);
extern void stm32_usbinitialize(void);
extern void board_peripheral_reset(int ms);
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */
__END_DECLS
+23 -13
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
* Copyright (c) 2021-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,11 +34,11 @@
/**
* @file init.c
*
* FMU-specific early startup code. This file implements the
* board-specific early startup code. This file implements the
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialisation.
* subsystems and perform board-specific initialization.
*/
#include "board_config.h"
@@ -113,9 +113,6 @@ __EXPORT void stm32_boardinitialize(void)
/* Reset PWM first thing */
board_on_reset(-1);
/* configure LEDs */
board_autoled_initialize();
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
@@ -123,9 +120,8 @@ __EXPORT void stm32_boardinitialize(void)
/* configure SPI interfaces */
stm32_spiinitialize();
/* configure USB interfaces */
stm32_usbinitialize();
/* configure LEDs */
board_autoled_initialize();
}
/****************************************************************************
@@ -156,6 +152,12 @@ __EXPORT int board_app_initialize(uintptr_t arg)
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
#if defined(SERIAL_HAVE_RXDMA)
// set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
static struct hrt_call serial_dma_call;
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
#endif
/* initial LED state */
drv_led_start();
led_off(LED_RED);
@@ -166,13 +168,21 @@ __EXPORT int board_app_initialize(uintptr_t arg)
}
#ifdef CONFIG_MMCSD
int ret = stm32_sdio_initialize();
/* Mount the SDIO-based MMC/SD block driver */
/* First, get an instance of the SDIO interface */
struct sdio_dev_s *sdio_dev = sdio_initialize(0); // SDIO_SLOTNO 0 Only one slot
if (ret != OK) {
led_on(LED_BLUE);
if (!sdio_dev) {
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", 0);
}
#endif
if (mmcsd_slotinitialize(0, sdio_dev) != OK) {
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver\n");
}
/* Assume that the SD card is inserted. What choice do we have? */
sdio_mediachange(sdio_dev, true);
#endif /* CONFIG_MMCSD */
/* Configure the HW based on the manifest */
px4_platform_configure();
-177
View File
@@ -1,177 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <board_config.h>
#include <stdbool.h>
#include <stdio.h>
#include <debug.h>
#include <errno.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include "chip.h"
#include "board_config.h"
#include "stm32_gpio.h"
#include "stm32_sdmmc.h"
#ifdef CONFIG_MMCSD
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Card detections requires card support and a card detection GPIO */
#define HAVE_NCD 1
#if !defined(GPIO_SDMMC1_NCD)
# undef HAVE_NCD
#endif
/****************************************************************************
* Private Data
****************************************************************************/
static FAR struct sdio_dev_s *sdio_dev;
#ifdef HAVE_NCD
static bool g_sd_inserted = 0xff; /* Impossible value */
#endif
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_ncd_interrupt
*
* Description:
* Card detect interrupt handler.
*
****************************************************************************/
#ifdef HAVE_NCD
static int stm32_ncd_interrupt(int irq, FAR void *context)
{
bool present;
present = !stm32_gpioread(GPIO_SDMMC1_NCD);
if (sdio_dev && present != g_sd_inserted) {
sdio_mediachange(sdio_dev, present);
g_sd_inserted = present;
}
return OK;
}
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_sdio_initialize
*
* Description:
* Initialize SDIO-based MMC/SD card support
*
****************************************************************************/
int stm32_sdio_initialize(void)
{
int ret;
#ifdef HAVE_NCD
/* Card detect */
bool cd_status;
/* Configure the card detect GPIO */
stm32_configgpio(GPIO_SDMMC1_NCD);
/* Register an interrupt handler for the card detect pin */
stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt);
#endif
/* Mount the SDIO-based MMC/SD block driver */
/* First, get an instance of the SDIO interface */
finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO);
sdio_dev = sdio_initialize(SDIO_SLOTNO);
if (!sdio_dev) {
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO);
return -ENODEV;
}
/* Now bind the SDIO interface to the MMC/SD driver */
finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR);
ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev);
if (ret != OK) {
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
return ret;
}
finfo("Successfully bound SDIO to the MMC/SD driver\n");
#ifdef HAVE_NCD
/* Use SD card detect pin to check if a card is g_sd_inserted */
cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD);
finfo("Card detect : %d\n", cd_status);
sdio_mediachange(sdio_dev, cd_status);
#else
/* Assume that the SD card is inserted. What choice do we have? */
sdio_mediachange(sdio_dev, true);
#endif
return OK;
}
#endif /* CONFIG_MMCSD */
-1
View File
@@ -35,7 +35,6 @@
#include <drivers/drv_sensor.h>
#include <nuttx/spi/spi.h>
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_MPU6000, SPI::CS{GPIO::PortC, GPIO::Pin15}, SPI::DRDY{GPIO::PortB, GPIO::Pin2}),
+3 -3
View File
@@ -34,9 +34,9 @@
#include <px4_arch/io_timer_hw_description.h>
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOTimer(Timer::Timer3, DMA{DMA::Index1, DMA::Stream2, DMA::Channel5}),
initIOTimer(Timer::Timer5, DMA{DMA::Index1, DMA::Stream0, DMA::Channel6}),
initIOTimer(Timer::Timer4, DMA{DMA::Index1, DMA::Stream6, DMA::Channel2}),
initIOTimer(Timer::Timer3, DMA{DMA::Index1}),
initIOTimer(Timer::Timer5, DMA{DMA::Index1}),
initIOTimer(Timer::Timer4, DMA{DMA::Index1}),
// initIOTimer(Timer::Timer15),
};
-19
View File
@@ -43,25 +43,6 @@
#include <stm32_otg.h>
#include <debug.h>
/************************************************************************************
* Name: stm32_usbinitialize
*
* Description:
* Called to setup USB-related GPIO pins for the board.
*
************************************************************************************/
__EXPORT void stm32_usbinitialize(void)
{
/* The OTG FS has an internal soft pull-up */
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
#ifdef CONFIG_STM32F7_OTGFS
stm32_configgpio(GPIO_OTGFS_VBUS);
#endif
}
/************************************************************************************
* Name: stm32_usbsuspend
*
+2 -2
View File
@@ -40,6 +40,7 @@ CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
@@ -63,7 +64,6 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
@@ -72,8 +72,8 @@ CONFIG_MODULES_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VMOUNT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -33,19 +33,27 @@
#pragma once
// DMAMUX1
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
// DMAMAP_TIM4UP DMAMAP_DMA12_TIM4UP_0 /* DMA1:32 */ // DSHOT 5, 6
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */
#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 */ // GPS1 RX
#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 */ // GPS1 TX
// DMAMAP_TIM5UP DMAMAP_DMA12_TIM5UP_0 /* DMA1:59 */ // DSHOT 1, 2, 3, 4
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* DMA1:71 */
#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* DMA1:72 */
// DMAMUX2
#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_1 /* DMA2:61 */
#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_1 /* DMA2:62 */
#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 /* DMA2:65 */ // TELEM2 RX
#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 /* DMA2:66 */ // TELEM2 TX
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_1 /* DMA2:71 */ // RC RX
#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_1 /* DMA2:72 */ // RC TX
#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* DMA2:79 */ // TELEM1 RX
#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 /* DMA2:80 */ // TELEM1 TX
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */
// BDMA
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */
@@ -53,7 +53,6 @@ CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x0483
CONFIG_CDCACM_VENDORSTR="ModalAI"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_MEMFAULT=y
@@ -62,6 +61,7 @@ CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_EXAMPLES_CALIB_UDELAY=y
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
@@ -86,7 +86,6 @@ CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_IOB_NBUFFERS=24
CONFIG_IOB_NCHAINS=24
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
@@ -181,13 +180,15 @@ CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_SPI1=y
CONFIG_STM32H7_SPI1_DMA=y
CONFIG_STM32H7_SPI1_DMA_BUFFER=1024
CONFIG_STM32H7_SPI1_DMA_BUFFER=4096
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI2_DMA=y
CONFIG_STM32H7_SPI2_DMA_BUFFER=4096
CONFIG_STM32H7_SPI4=y
CONFIG_STM32H7_SPI5=y
CONFIG_STM32H7_SPI6=y
CONFIG_STM32H7_SPI6_DMA=y
CONFIG_STM32H7_SPI6_DMA_BUFFER=1024
CONFIG_STM32H7_SPI_DMA=y
CONFIG_STM32H7_TIM12=y
CONFIG_STM32H7_TIM1=y
@@ -211,19 +212,28 @@ CONFIG_TASK_NAME_SIZE=24
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART5_BAUD=57600
CONFIG_UART5_IFLOWCONTROL=y
CONFIG_UART5_OFLOWCONTROL=y
CONFIG_UART5_RXBUFSIZE=600
CONFIG_UART5_RXDMA=y
CONFIG_UART5_TXBUFSIZE=3000
CONFIG_UART5_TXDMA=y
CONFIG_UART7_BAUD=57600
CONFIG_UART7_IFLOWCONTROL=y
CONFIG_UART7_OFLOWCONTROL=y
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_RXDMA=y
CONFIG_UART7_TXBUFSIZE=3000
CONFIG_UART7_TXDMA=y
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_RXDMA=y
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART1_TXDMA=y
CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
@@ -235,7 +245,9 @@ CONFIG_USART3_SERIAL_CONSOLE=y
CONFIG_USART3_TXBUFSIZE=1500
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_RXDMA=y
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USART6_TXDMA=y
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
-20
View File
@@ -53,26 +53,6 @@
* Definitions
****************************************************************************************************/
/* PX4IO connection configuration */
#define BOARD_USES_PX4IO_VERSION 2
#define PX4IO_SERIAL_DEVICE "/dev/ttyS5"
#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX
#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX
#define PX4IO_SERIAL_BASE STM32_USART6_BASE
#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6
#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX
#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX
#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB2ENR
#define PX4IO_SERIAL_RCC_EN RCC_APB2ENR_USART6EN
#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY
#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */
/* Configuration ************************************************************************************/
/* PX4FMU GPIOs ***********************************************************************************/
/* Trace Clock and D0-D3 are available on the trace connector
*
* TRACECLK PE2 - Dedicated - Trace Connector Pin 1
+7 -52
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012-2021 PX4 Development Team. All rights reserved.
* Copyright (c) 2021-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,35 +34,21 @@
/**
* @file init.c
*
* PX4FMU-specific early startup code. This file implements the
* board-specific early startup code. This file implements the
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialization.
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include "board_config.h"
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
#include <debug.h>
#include <errno.h>
#include <syslog.h>
#include <nuttx/config.h>
#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include <nuttx/analog/adc.h>
#include <nuttx/mm/gran.h>
#include <chip.h>
#include <stm32_uart.h>
#include <arch/board/board.h>
#include "arm_internal.h"
@@ -75,26 +61,12 @@
#include <px4_platform/board_determine_hw_info.h>
#include <px4_platform/board_dma_alloc.h>
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/*
* Ideally we'd be able to get these from arm_internal.h,
* but since we want to be able to disable the NuttX use
* of leds for system indication at will and there is no
* separate switch, we need to build independent of the
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
__END_DECLS
/************************************************************************************
* Name: board_peripheral_reset
*
@@ -103,9 +75,6 @@ __END_DECLS
************************************************************************************/
__EXPORT void board_peripheral_reset(int ms)
{
/* set the peripheral rails off */
board_control_spi_sensors_power(false, 0xffff);
bool last = READ_VDD_3V3_SPEKTRUM_POWER_EN();
/* Keep Spektum on to discharge rail*/
VDD_3V3_SPEKTRUM_POWER_EN(false);
@@ -118,8 +87,6 @@ __EXPORT void board_peripheral_reset(int ms)
/* switch the peripheral rail back on */
VDD_3V3_SPEKTRUM_POWER_EN(last);
board_control_spi_sensors_power(true, 0xffff);
}
/************************************************************************************
@@ -153,15 +120,11 @@ __EXPORT void board_on_reset(int status)
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void
stm32_boardinitialize(void)
__EXPORT void stm32_boardinitialize(void)
{
board_on_reset(-1); /* Reset PWM first thing */
/* configure LEDs */
board_autoled_initialize();
/* configure pins */
@@ -174,10 +137,11 @@ stm32_boardinitialize(void)
stm32_spiinitialize();
/* configure LEDs */
board_autoled_initialize();
/* configure USB interfaces */
stm32_usbinitialize();
}
/****************************************************************************
@@ -191,13 +155,7 @@ stm32_boardinitialize(void)
* Input Parameters:
* arg - The boardctl() argument is passed to the board_app_initialize()
* implementation without modification. The argument has no
* meaning to NuttX; the meaning of the argument is a contract
* between the board-specific initalization logic and the the
* matching application logic. The value cold be such things as a
* mode enumeration value, a set of DIP switch switch settings, a
* pointer to configuration data read from a file or serial FLASH,
* or whatever you would like to do with it. Every implementation
* should accept zero/NULL as a default configuration.
* meaning to NuttX;
*
* Returned Value:
* Zero (OK) is returned on success; a negated errno value is returned on
@@ -213,10 +171,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
VDD_3V3_SPEKTRUM_POWER_EN(true);
/* Need hrt running before using the ADC */
px4_platform_init();
if (OK == board_determine_hw_info()) {
syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(),
board_get_hw_type_name());
@@ -226,7 +182,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
}
/* configure the DMA allocator */
if (board_dma_alloc_init() < 0) {
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
@@ -268,6 +268,10 @@
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF9 */
#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_1) /* PG13 */
#define GPIO_SPI6_MISO GPIO_SPI6_MISO_1 /* PG12 */
#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_1 /* PG14 */
/* I2C */
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
* Copyright (c) 2021-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,11 +34,23 @@
#pragma once
// DMAMUX1
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
// DMAMAP_TIM1UP DMAMAP_DMA12_TIM1UP_0 /* DMA1:15 */ // DSHOT 1, 2, 3, 4
// DMAMAP_TIM4UP DMAMAP_DMA12_TIM4UP_0 /* DMA1:32 */ // DSHOT 5, 6
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_0 /* DMA1:43 */ // TELEM1 RX
#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_0 /* DMA1:44 */ // TELEM1 TX
#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 */ // TELEM2 RX
#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 */ // TELEM2 TX
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_1 /* DMA1:71 */
#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_1 /* DMA1:72 */
// DMAMUX2
// DMAMAP_TIM8UP DMAMAP_DMA12_TIM8UP_1 /* DMA2:61 */ // DSHOT 7, 8
#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_1 /* DMA2:63 */ // GPS1 RX
#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_1 /* DMA2:64 */ // GPS1 TX
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_1 /* DMA2:71 */ // RC (RX only)
#define DMAMAP_SPI5_RX DMAMAP_DMA12_SPI5RX_1 /* DMA2:85 */
#define DMAMAP_SPI5_TX DMAMAP_DMA12_SPI5TX_1 /* DMA2:86 */
#define DMAMAP_SPI5_RX DMAMAP_DMA12_SPI5RX_0 /* DMA1:83 */
#define DMAMAP_SPI5_TX DMAMAP_DMA12_SPI5TX_0 /* DMA1:84 */
// BDMA
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */
@@ -56,13 +56,11 @@ CONFIG_CDCACM_VENDORSTR="mRo"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_MEMFAULT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_DISABLE_MQUEUE=y
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
@@ -185,6 +183,9 @@ CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI5=y
CONFIG_STM32H7_SPI5_DMA=y
CONFIG_STM32H7_SPI5_DMA_BUFFER=1024
CONFIG_STM32H7_SPI6=y
CONFIG_STM32H7_SPI6_DMA=y
CONFIG_STM32H7_SPI6_DMA_BUFFER=1024
CONFIG_STM32H7_SPI_DMA=y
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_TIM2=y
@@ -208,30 +209,37 @@ CONFIG_TTY_SIGINT=y
CONFIG_TTY_SIGTSTP=y
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_RXDMA=y
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART4_TXDMA=y
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_SERIAL_CONSOLE=y
CONFIG_UART7_TXBUFSIZE=1500
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_SERIAL_CONSOLE=y
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART2_RXDMA=y
CONFIG_USART2_TXBUFSIZE=3000
CONFIG_USART2_TXDMA=y
CONFIG_USART3_BAUD=57600
CONFIG_USART3_IFLOWCONTROL=y
CONFIG_USART3_OFLOWCONTROL=y
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_RXDMA=y
CONFIG_USART3_TXBUFSIZE=3000
CONFIG_USART3_TXDMA=y
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USART6_RXDMA=y
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_USERMAIN_STACKSIZE=2944
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_WATCHDOG=y
+11 -15
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
* Copyright (c) 2021-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -97,17 +97,17 @@
#define TONE_ALARM_TIMER 2 /* timer 2 */
#define TONE_ALARM_CHANNEL 1 /* PA15 TIM2_CH1 */
#define GPIO_BUZZER_1 /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
#define GPIO_BUZZER_1 /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) // ALARM
#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1
#define GPIO_TONE_ALARM GPIO_TIM2_CH1OUT_2
/* USB OTG FS */
#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9)
#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_OPENDRAIN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9)
/* High-resolution timer */
#define HRT_TIMER 3 /* use timer3 for the HRT */
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */
#define HRT_PPM_CHANNEL /* T3C3 */ 3 /* use capture/compare channel 3 */
#define GPIO_PPM_IN /* PB0 T3C3 */ GPIO_TIM3_CH3IN_1
@@ -146,19 +146,10 @@
#define BOARD_ADC_SERVO_VALID (1) /* never powers off the Servo rail */
#define BOARD_ADC_BRICK_VALID (px4_arch_gpioread(GPIO_VDD_BRICK1_VALID))
/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
/* This board provides the board_on_reset interface */
#define BOARD_HAS_ON_RESET 1
#define BOARD_HAS_STATIC_MANIFEST 1
#define BOARD_NUM_IO_TIMERS 3
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5, 6, 7};
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
#define BOARD_HAS_ON_RESET 1
#define BOARD_ENABLE_CONSOLE_BUFFER
#define PX4_GPIO_INIT_LIST { \
@@ -170,6 +161,11 @@
GPIO_CAN1_SILENT_S0, \
GPIO_nPOWER_IN_A, \
GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D0), \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D1), \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D2), \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D3), \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_CMD),\
GPIO_TONE_ALARM_IDLE, \
GPIO_SAFETY_SWITCH_IN, \
GPIO_OTGFS_VBUS, \
+8 -5
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
* Copyright (c) 2021-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -38,7 +38,7 @@
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialisation.
* subsystems and perform board-specific initialization.
*/
#include "board_config.h"
@@ -60,8 +60,6 @@
#include <px4_platform/gpio.h>
#include <px4_platform/board_dma_alloc.h>
#include <mpu.h>
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
@@ -129,6 +127,7 @@ __EXPORT void stm32_boardinitialize(void)
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
board_control_spi_sensors_power_configgpio();
/* configure LEDs */
@@ -168,6 +167,11 @@ __EXPORT int board_app_initialize(uintptr_t arg)
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
#if defined(SERIAL_HAVE_RXDMA)
// set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
static struct hrt_call serial_dma_call;
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
#endif
/* initial LED state */
drv_led_start();
@@ -197,7 +201,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
#endif /* CONFIG_MMCSD */
/* Configure the HW based on the manifest */
px4_platform_configure();
return OK;
+3
View File
@@ -48,6 +48,9 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin10}, SPI::DRDY{GPIO::PortF, GPIO::Pin3}),
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin6}, SPI::DRDY{GPIO::PortF, GPIO::Pin1}),
}),
initSPIBusExternal(SPI::Bus::SPI6, {
initSPIConfigExternal(SPI::CS{GPIO::PortG, GPIO::Pin9}),
}),
};
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
@@ -36,7 +36,7 @@
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOTimer(Timer::Timer1, DMA{DMA::Index1}),
initIOTimer(Timer::Timer4, DMA{DMA::Index1}),
initIOTimer(Timer::Timer8, DMA{DMA::Index1}),
initIOTimer(Timer::Timer8, DMA{DMA::Index2}),
};
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
@@ -264,6 +264,10 @@
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF9 */
#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_1) /* PG13 */
#define GPIO_SPI6_MISO GPIO_SPI6_MISO_1 /* PG12 */
#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_1 /* PG14 */
/* I2C */
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
* Copyright (c) 2021-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,11 +34,23 @@
#pragma once
// DMAMUX1
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
// DMAMAP_TIM1UP DMAMAP_DMA12_TIM1UP_0 /* DMA1:15 */ // DSHOT 1, 2, 3, 4
// DMAMAP_TIM4UP DMAMAP_DMA12_TIM4UP_0 /* DMA1:32 */ // DSHOT 5, 6
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_0 /* DMA1:43 */ // TELEM1 RX
#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_0 /* DMA1:44 */ // TELEM1 TX
#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 */ // TELEM2 RX
#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 */ // TELEM2 TX
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_1 /* DMA1:71 */
#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_1 /* DMA1:72 */
// DMAMUX2
// DMAMAP_TIM8UP DMAMAP_DMA12_TIM8UP_1 /* DMA2:61 */ // DSHOT 7, 8
#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_1 /* DMA2:63 */ // GPS1 RX
#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_1 /* DMA2:64 */ // GPS1 TX
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_1 /* DMA2:71 */ // RC (RX only)
#define DMAMAP_SPI5_RX DMAMAP_DMA12_SPI5RX_1 /* DMA2:85 */
#define DMAMAP_SPI5_TX DMAMAP_DMA12_SPI5TX_1 /* DMA2:86 */
#define DMAMAP_SPI5_RX DMAMAP_DMA12_SPI5RX_0 /* DMA1:83 */
#define DMAMAP_SPI5_TX DMAMAP_DMA12_SPI5TX_0 /* DMA1:84 */
// BDMA
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */
@@ -56,13 +56,11 @@ CONFIG_CDCACM_VENDORSTR="mRo"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_MEMFAULT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_DISABLE_MQUEUE=y
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
@@ -158,6 +156,7 @@ CONFIG_STM32H7_ADC1=y
CONFIG_STM32H7_ADC3=y
CONFIG_STM32H7_BBSRAM=y
CONFIG_STM32H7_BBSRAM_FILES=5
CONFIG_STM32H7_BDMA=y
CONFIG_STM32H7_BKPSRAM=y
CONFIG_STM32H7_DMA1=y
CONFIG_STM32H7_DMA2=y
@@ -182,6 +181,9 @@ CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI5=y
CONFIG_STM32H7_SPI5_DMA=y
CONFIG_STM32H7_SPI5_DMA_BUFFER=1024
CONFIG_STM32H7_SPI6=y
CONFIG_STM32H7_SPI6_DMA=y
CONFIG_STM32H7_SPI6_DMA_BUFFER=1024
CONFIG_STM32H7_SPI_DMA=y
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_TIM2=y
@@ -205,30 +207,37 @@ CONFIG_TTY_SIGINT=y
CONFIG_TTY_SIGTSTP=y
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_RXDMA=y
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART4_TXDMA=y
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_SERIAL_CONSOLE=y
CONFIG_UART7_TXBUFSIZE=1500
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_SERIAL_CONSOLE=y
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART2_RXDMA=y
CONFIG_USART2_TXBUFSIZE=3000
CONFIG_USART2_TXDMA=y
CONFIG_USART3_BAUD=57600
CONFIG_USART3_IFLOWCONTROL=y
CONFIG_USART3_OFLOWCONTROL=y
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_RXDMA=y
CONFIG_USART3_TXBUFSIZE=3000
CONFIG_USART3_TXDMA=y
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USART6_RXDMA=y
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_USERMAIN_STACKSIZE=2944
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_WATCHDOG=y
+11 -15
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
* Copyright (c) 2021-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -97,17 +97,17 @@
#define TONE_ALARM_TIMER 2 /* timer 2 */
#define TONE_ALARM_CHANNEL 1 /* PA15 TIM2_CH1 */
#define GPIO_BUZZER_1 /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
#define GPIO_BUZZER_1 /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) // ALARM
#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1
#define GPIO_TONE_ALARM GPIO_TIM2_CH1OUT_2
/* USB OTG FS */
#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9)
#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_OPENDRAIN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9)
/* High-resolution timer */
#define HRT_TIMER 3 /* use timer3 for the HRT */
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */
#define HRT_PPM_CHANNEL /* T3C3 */ 3 /* use capture/compare channel 3 */
#define GPIO_PPM_IN /* PB0 T3C3 */ GPIO_TIM3_CH3IN_1
@@ -146,19 +146,10 @@
#define BOARD_ADC_SERVO_VALID (1) /* never powers off the Servo rail */
#define BOARD_ADC_BRICK_VALID (px4_arch_gpioread(GPIO_VDD_BRICK1_VALID))
/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
/* This board provides the board_on_reset interface */
#define BOARD_HAS_ON_RESET 1
#define BOARD_HAS_STATIC_MANIFEST 1
#define BOARD_NUM_IO_TIMERS 3
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5, 6, 7};
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
#define BOARD_HAS_ON_RESET 1
#define BOARD_ENABLE_CONSOLE_BUFFER
#define PX4_GPIO_INIT_LIST { \
@@ -168,6 +159,11 @@
GPIO_CAN1_SILENT_S0, \
GPIO_nPOWER_IN_A, \
GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D0), \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D1), \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D2), \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D3), \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_CMD),\
GPIO_TONE_ALARM_IDLE, \
GPIO_SAFETY_SWITCH_IN, \
GPIO_OTGFS_VBUS, \
+8 -5
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
* Copyright (c) 2021-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -38,7 +38,7 @@
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialisation.
* subsystems and perform board-specific initialization.
*/
#include "board_config.h"
@@ -60,8 +60,6 @@
#include <px4_platform/gpio.h>
#include <px4_platform/board_dma_alloc.h>
#include <mpu.h>
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
@@ -129,6 +127,7 @@ __EXPORT void stm32_boardinitialize(void)
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
board_control_spi_sensors_power_configgpio();
/* configure LEDs */
@@ -168,6 +167,11 @@ __EXPORT int board_app_initialize(uintptr_t arg)
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
#if defined(SERIAL_HAVE_RXDMA)
// set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
static struct hrt_call serial_dma_call;
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
#endif
/* initial LED state */
drv_led_start();
@@ -197,7 +201,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
#endif /* CONFIG_MMCSD */
/* Configure the HW based on the manifest */
px4_platform_configure();
return OK;
+3
View File
@@ -48,6 +48,9 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin10}, SPI::DRDY{GPIO::PortF, GPIO::Pin3}),
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin6}, SPI::DRDY{GPIO::PortF, GPIO::Pin1}),
}),
initSPIBusExternal(SPI::Bus::SPI6, {
initSPIConfigExternal(SPI::CS{GPIO::PortG, GPIO::Pin9}),
}),
};
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
+1 -1
View File
@@ -36,7 +36,7 @@
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOTimer(Timer::Timer1, DMA{DMA::Index1}),
initIOTimer(Timer::Timer4, DMA{DMA::Index1}),
initIOTimer(Timer::Timer8, DMA{DMA::Index1}),
initIOTimer(Timer::Timer8, DMA{DMA::Index2}),
};
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
+2 -2
View File
@@ -38,6 +38,7 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
@@ -61,7 +62,6 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
@@ -72,8 +72,8 @@ CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VMOUNT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -33,16 +33,27 @@
#pragma once
// DMAMUX1
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
// DMAMAP_TIM1UP DMAMAP_DMA12_TIM1UP_0 /* DMA1:15 */ // DSHOT 1, 2, 3, 4
// DMAMAP_TIM4UP DMAMAP_DMA12_TIM4UP_0 /* DMA1:32 */ // DSHOT 5, 6
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_0 /* DMA1:43 */ // TELEM1 RX
#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_0 /* DMA1:44 */ // TELEM1 TX
#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 */ // TELEM2 RX
#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 */ // TELEM2 TX
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */
#define DMAMAP_SPI5_RX DMAMAP_DMA12_SPI5RX_0 /* DMA1:85 */
#define DMAMAP_SPI5_TX DMAMAP_DMA12_SPI5TX_0 /* DMA1:86 */
// DMAMUX2
// DMAMAP_TIM8UP DMAMAP_DMA12_TIM8UP_1 /* DMA2:61 */ // DSHOT 7, 8
#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_1 /* DMA2:63 */ // GPS1 RX
#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_1 /* DMA2:64 */ // GPS1 TX
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_1 /* DMA2:71 */ // RC (RX only)
#define DMAMAP_SPI5_RX DMAMAP_DMA12_SPI5RX_1 /* DMA2:85 */
#define DMAMAP_SPI5_TX DMAMAP_DMA12_SPI5TX_1 /* DMA2:86 */
// BDMA
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */
@@ -103,9 +103,6 @@ CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_DISABLE_IFCONFIG=y
CONFIG_NSH_DISABLE_IFUPDOWN=y
CONFIG_NSH_DISABLE_TELNETD=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
@@ -206,7 +203,9 @@ CONFIG_TTY_SIGINT=y
CONFIG_TTY_SIGTSTP=y
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_RXDMA=y
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART4_TXDMA=y
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_SERIAL_CONSOLE=y
@@ -218,14 +217,19 @@ CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART2_RXDMA=y
CONFIG_USART2_TXBUFSIZE=3000
CONFIG_USART2_TXDMA=y
CONFIG_USART3_BAUD=57600
CONFIG_USART3_IFLOWCONTROL=y
CONFIG_USART3_OFLOWCONTROL=y
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_RXDMA=y
CONFIG_USART3_TXBUFSIZE=3000
CONFIG_USART3_TXDMA=y
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_RXDMA=y
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
@@ -111,6 +111,7 @@ MEMORY
{
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1920K
DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */
+3 -4
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2020-2021 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -118,7 +118,6 @@
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS4"
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
#define GPIO_RSSI_IN /* PC1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1)
@@ -147,8 +146,8 @@
#define BOARD_NUM_IO_TIMERS 3
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5, 6, 7};
#define BOARD_DMA_ALLOC_POOL_SIZE 5120 /* This board provides a DMA pool and APIs */
#define BOARD_HAS_ON_RESET 1 /* This board provides the board_on_reset interface */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
#define BOARD_HAS_ON_RESET 1
#define BOARD_ENABLE_CONSOLE_BUFFER
#define PX4_GPIO_INIT_LIST { \
+12 -4
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -38,7 +38,7 @@
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialisation.
* subsystems and perform board-specific initialization.
*/
#include "board_config.h"
@@ -60,8 +60,6 @@
#include <px4_platform/gpio.h>
#include <px4_platform/board_dma_alloc.h>
#include <mpu.h>
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
@@ -129,6 +127,7 @@ __EXPORT void stm32_boardinitialize(void)
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
board_control_spi_sensors_power_configgpio();
/* configure LEDs */
@@ -168,6 +167,12 @@ __EXPORT int board_app_initialize(uintptr_t arg)
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
#if defined(SERIAL_HAVE_RXDMA)
// set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
static struct hrt_call serial_dma_call;
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
#endif
/* initial LED state */
drv_led_start();
led_off(LED_RED);
@@ -195,5 +200,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
sdio_mediachange(sdio_dev, true);
#endif /* CONFIG_MMCSD */
/* Configure the HW based on the manifest */
px4_platform_configure();
return OK;
}
+1 -1
View File
@@ -36,7 +36,7 @@
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOTimer(Timer::Timer1, DMA{DMA::Index1}),
initIOTimer(Timer::Timer4, DMA{DMA::Index1}),
initIOTimer(Timer::Timer8, DMA{DMA::Index1}),
initIOTimer(Timer::Timer8, DMA{DMA::Index2}),
};
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
+2 -2
View File
@@ -43,6 +43,7 @@ CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
@@ -65,7 +66,6 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
@@ -74,8 +74,8 @@ CONFIG_MODULES_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VMOUNT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -33,16 +33,29 @@
#pragma once
// DMAMUX1
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */
// DMAMUX1
// DMAMAP_TIM4UP DMAMAP_DMA12_TIM4UP_0 /* DMA1:32 */ // DSHOT 5, 6
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */
#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 */ // GPS1 RX
#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 */ // GPS1 TX
// DMAMAP_TIM5UP DMAMAP_DMA12_TIM5UP_0 /* DMA1:59 */ // DSHOT 1, 2, 3, 4
// DMAMUX2
#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_1 /* DMA2:61 */
#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_1 /* DMA2:62 */
#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_1 /* DMA2:61 */
#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_1 /* DMA2:62 */
#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 /* DMA2:65 */ // TELEM2 RX
#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 /* DMA2:66 */ // TELEM2 TX
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_1 /* DMA2:71 */ // RC RX
#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_1 /* DMA2:72 */ // RC TX
#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* DMA2:79 */ // TELEM1 RX
#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 /* DMA2:80 */ // TELEM1 TX
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */
// BDMA
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */
+12 -1
View File
@@ -181,7 +181,7 @@ CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_SPI1=y
CONFIG_STM32H7_SPI1_DMA=y
CONFIG_STM32H7_SPI1_DMA_BUFFER=1024
CONFIG_STM32H7_SPI1_DMA_BUFFER=4096
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI2_DMA=y
CONFIG_STM32H7_SPI2_DMA_BUFFER=4096
@@ -215,19 +215,28 @@ CONFIG_TASK_NAME_SIZE=24
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART5_BAUD=57600
CONFIG_UART5_IFLOWCONTROL=y
CONFIG_UART5_OFLOWCONTROL=y
CONFIG_UART5_RXBUFSIZE=600
CONFIG_UART5_RXDMA=y
CONFIG_UART5_TXBUFSIZE=3000
CONFIG_UART5_TXDMA=y
CONFIG_UART7_BAUD=57600
CONFIG_UART7_IFLOWCONTROL=y
CONFIG_UART7_OFLOWCONTROL=y
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_RXDMA=y
CONFIG_UART7_TXBUFSIZE=3000
CONFIG_UART7_TXDMA=y
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_RXDMA=y
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART1_TXDMA=y
CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
@@ -239,7 +248,9 @@ CONFIG_USART3_SERIAL_CONSOLE=y
CONFIG_USART3_TXBUFSIZE=1500
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_RXDMA=y
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USART6_TXDMA=y
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
+9 -58
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012-2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,35 +34,21 @@
/**
* @file init.c
*
* PX4FMU-specific early startup code. This file implements the
* board-specific early startup code. This file implements the
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialization.
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include "board_config.h"
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
#include <debug.h>
#include <errno.h>
#include <syslog.h>
#include <nuttx/config.h>
#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include <nuttx/analog/adc.h>
#include <nuttx/mm/gran.h>
#include <chip.h>
#include <stm32_uart.h>
#include <arch/board/board.h>
#include "arm_internal.h"
@@ -75,26 +61,12 @@
#include <px4_platform/board_determine_hw_info.h>
#include <px4_platform/board_dma_alloc.h>
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/*
* Ideally we'd be able to get these from arm_internal.h,
* but since we want to be able to disable the NuttX use
* of leds for system indication at will and there is no
* separate switch, we need to build independent of the
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
__END_DECLS
/************************************************************************************
* Name: board_peripheral_reset
*
@@ -104,9 +76,7 @@ __END_DECLS
__EXPORT void board_peripheral_reset(int ms)
{
/* set the peripheral rails off */
VDD_5V_PERIPH_EN(false);
board_control_spi_sensors_power(false, 0xffff);
VDD_3V3_SENSORS_EN(false);
bool last = READ_VDD_3V3_SPEKTRUM_POWER_EN();
@@ -121,10 +91,8 @@ __EXPORT void board_peripheral_reset(int ms)
/* switch the peripheral rail back on */
VDD_3V3_SPEKTRUM_POWER_EN(last);
board_control_spi_sensors_power(true, 0xffff);
VDD_3V3_SENSORS_EN(true);
VDD_5V_PERIPH_EN(true);
}
/************************************************************************************
@@ -158,18 +126,12 @@ __EXPORT void board_on_reset(int status)
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void
stm32_boardinitialize(void)
__EXPORT void stm32_boardinitialize(void)
{
board_on_reset(-1); /* Reset PWM first thing */
/* configure LEDs */
board_autoled_initialize();
/* Reset PWM first thing */
board_on_reset(-1);
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
@@ -180,9 +142,10 @@ stm32_boardinitialize(void)
stm32_spiinitialize();
/* configure USB interfaces */
stm32_usbinitialize();
/* configure LEDs */
board_autoled_initialize();
}
/****************************************************************************
@@ -196,21 +159,13 @@ stm32_boardinitialize(void)
* Input Parameters:
* arg - The boardctl() argument is passed to the board_app_initialize()
* implementation without modification. The argument has no
* meaning to NuttX; the meaning of the argument is a contract
* between the board-specific initalization logic and the the
* matching application logic. The value cold be such things as a
* mode enumeration value, a set of DIP switch switch settings, a
* pointer to configuration data read from a file or serial FLASH,
* or whatever you would like to do with it. Every implementation
* should accept zero/NULL as a default configuration.
* meaning to NuttX;
*
* Returned Value:
* Zero (OK) is returned on success; a negated errno value is returned on
* any failure to indicate the nature of the failure.
*
****************************************************************************/
__EXPORT int board_app_initialize(uintptr_t arg)
{
/* Power on Interfaces */
@@ -222,10 +177,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
VDD_3V3_SPEKTRUM_POWER_EN(true);
/* Need hrt running before using the ADC */
px4_platform_init();
if (OK == board_determine_hw_info()) {
syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(),
board_get_hw_type_name());
@@ -235,7 +188,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
}
/* configure the DMA allocator */
if (board_dma_alloc_init() < 0) {
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
@@ -256,12 +208,12 @@ __EXPORT int board_app_initialize(uintptr_t arg)
led_on(LED_RED);
}
#ifdef CONFIG_MMCSD
// Ensure Power is off for > 10 mS
usleep(15 * 1000);
VDD_3V3_SD_CARD_EN(true);
usleep(500 * 1000);
#ifdef CONFIG_MMCSD
int ret = stm32_sdio_initialize();
if (ret != OK) {
@@ -271,7 +223,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
#endif /* CONFIG_MMCSD */
/* Configure the HW based on the manifest */
px4_platform_configure();
return OK;
+2 -2
View File
@@ -39,6 +39,7 @@ CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
@@ -61,7 +62,6 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
@@ -70,8 +70,8 @@ CONFIG_MODULES_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VMOUNT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -33,19 +33,29 @@
#pragma once
// DMAMUX1
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
// DMAMAP_TIM4UP DMAMAP_DMA12_TIM4UP_0 /* DMA1:32 */ // DSHOT 5, 6
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */
#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 */ // GPS1 RX
#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 */ // GPS1 TX
// DMAMAP_TIM5UP DMAMAP_DMA12_TIM5UP_0 /* DMA1:59 */ // DSHOT 1, 2, 3, 4
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* DMA1:71 */
#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* DMA1:72 */
// DMAMUX2
#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_1 /* DMA2:61 */
#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_1 /* DMA2:62 */
#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_1 /* DMA2:61 */
#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_1 /* DMA2:62 */
#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 /* DMA2:65 */ // TELEM2 RX
#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 /* DMA2:66 */ // TELEM2 TX
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_1 /* DMA2:71 */ // PX4IO RX
#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_1 /* DMA2:72 */ // PX4IO TX
#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* DMA2:79 */ // TELEM1 RX
#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 /* DMA2:80 */ // TELEM1 TX
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */
// BDMA
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */
+12 -1
View File
@@ -219,7 +219,7 @@ CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_SPI1=y
CONFIG_STM32H7_SPI1_DMA=y
CONFIG_STM32H7_SPI1_DMA_BUFFER=1024
CONFIG_STM32H7_SPI1_DMA_BUFFER=4096
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI2_DMA=y
CONFIG_STM32H7_SPI2_DMA_BUFFER=4096
@@ -255,19 +255,28 @@ CONFIG_TASK_NAME_SIZE=24
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART5_BAUD=57600
CONFIG_UART5_IFLOWCONTROL=y
CONFIG_UART5_OFLOWCONTROL=y
CONFIG_UART5_RXBUFSIZE=600
CONFIG_UART5_RXDMA=y
CONFIG_UART5_TXBUFSIZE=3000
CONFIG_UART5_TXDMA=y
CONFIG_UART7_BAUD=57600
CONFIG_UART7_IFLOWCONTROL=y
CONFIG_UART7_OFLOWCONTROL=y
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_RXDMA=y
CONFIG_UART7_TXBUFSIZE=3000
CONFIG_UART7_TXDMA=y
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_RXDMA=y
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART1_TXDMA=y
CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
@@ -279,7 +288,9 @@ CONFIG_USART3_SERIAL_CONSOLE=y
CONFIG_USART3_TXBUFSIZE=1500
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_RXDMA=y
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USART6_TXDMA=y
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
+2 -8
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2016, 2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,20 +34,14 @@
/**
* @file board_config.h
*
* PX4FMU-v6x internal definitions
* Board internal definitions
*/
#pragma once
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
#include <stm32_gpio.h>
/****************************************************************************************************
+32 -7
View File
@@ -1,12 +1,37 @@
/*
* hw_config.h
/****************************************************************************
*
* Created on: May 17, 2015
* Author: david_s5
*/
* Copyright (C) 2020 PX4 Development Team. All rights reserved.
*
* 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 PX4 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 OWNER 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.
*
****************************************************************************/
#ifndef HW_CONFIG_H_
#define HW_CONFIG_H_
#pragma once
/****************************************************************************
* 10-8--2016:
+10 -59
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012-2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,35 +34,21 @@
/**
* @file init.c
*
* PX4FMU-specific early startup code. This file implements the
* board-specific early startup code. This file implements the
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialization.
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include "board_config.h"
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
#include <debug.h>
#include <errno.h>
#include <syslog.h>
#include <nuttx/config.h>
#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include <nuttx/analog/adc.h>
#include <nuttx/mm/gran.h>
#include <chip.h>
#include <stm32_uart.h>
#include <arch/board/board.h>
#include "arm_internal.h"
@@ -75,26 +61,12 @@
#include <px4_platform/board_determine_hw_info.h>
#include <px4_platform/board_dma_alloc.h>
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/*
* Ideally we'd be able to get these from arm_internal.h,
* but since we want to be able to disable the NuttX use
* of leds for system indication at will and there is no
* separate switch, we need to build independent of the
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
__END_DECLS
/************************************************************************************
* Name: board_peripheral_reset
*
@@ -104,9 +76,7 @@ __END_DECLS
__EXPORT void board_peripheral_reset(int ms)
{
/* set the peripheral rails off */
VDD_5V_PERIPH_EN(false);
board_control_spi_sensors_power(false, 0xffff);
VDD_3V3_SENSORS4_EN(false);
bool last = READ_VDD_3V3_SPEKTRUM_POWER_EN();
@@ -121,10 +91,8 @@ __EXPORT void board_peripheral_reset(int ms)
/* switch the peripheral rail back on */
VDD_3V3_SPEKTRUM_POWER_EN(last);
board_control_spi_sensors_power(true, 0xffff);
VDD_3V3_SENSORS4_EN(true);
VDD_5V_PERIPH_EN(true);
}
/************************************************************************************
@@ -158,18 +126,12 @@ __EXPORT void board_on_reset(int status)
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void
stm32_boardinitialize(void)
__EXPORT void stm32_boardinitialize(void)
{
board_on_reset(-1); /* Reset PWM first thing */
/* configure LEDs */
board_autoled_initialize();
/* Reset PWM first thing */
board_on_reset(-1);
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
@@ -180,11 +142,12 @@ stm32_boardinitialize(void)
stm32_spiinitialize();
/* configure USB interfaces */
stm32_usbinitialize();
VDD_3V3_ETH_POWER_EN(true);
/* configure LEDs */
board_autoled_initialize();
VDD_3V3_ETH_POWER_EN(true);
}
/****************************************************************************
@@ -198,21 +161,13 @@ stm32_boardinitialize(void)
* Input Parameters:
* arg - The boardctl() argument is passed to the board_app_initialize()
* implementation without modification. The argument has no
* meaning to NuttX; the meaning of the argument is a contract
* between the board-specific initalization logic and the the
* matching application logic. The value cold be such things as a
* mode enumeration value, a set of DIP switch switch settings, a
* pointer to configuration data read from a file or serial FLASH,
* or whatever you would like to do with it. Every implementation
* should accept zero/NULL as a default configuration.
* meaning to NuttX;
*
* Returned Value:
* Zero (OK) is returned on success; a negated errno value is returned on
* any failure to indicate the nature of the failure.
*
****************************************************************************/
__EXPORT int board_app_initialize(uintptr_t arg)
{
/* Power on Interfaces */
@@ -224,10 +179,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
VDD_3V3_SPEKTRUM_POWER_EN(true);
/* Need hrt running before using the ADC */
px4_platform_init();
if (OK == board_determine_hw_info()) {
syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(),
board_get_hw_type_name());
@@ -237,7 +190,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
}
/* configure the DMA allocator */
if (board_dma_alloc_init() < 0) {
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
@@ -258,12 +210,12 @@ __EXPORT int board_app_initialize(uintptr_t arg)
led_on(LED_RED);
}
#ifdef CONFIG_MMCSD
// Ensure Power is off for > 10 mS
usleep(15 * 1000);
VDD_3V3_SD_CARD_EN(true);
usleep(500 * 1000);
#ifdef CONFIG_MMCSD
int ret = stm32_sdio_initialize();
if (ret != OK) {
@@ -273,7 +225,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
#endif /* CONFIG_MMCSD */
/* Configure the HW based on the manifest */
px4_platform_configure();
return OK;
@@ -91,9 +91,6 @@
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 4
// Has pwm outputs
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
/*
* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
* this board support the ADC system_power interface, and therefore
+1 -1
View File
@@ -21,6 +21,7 @@ CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
@@ -35,7 +36,6 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
@@ -1,7 +1,8 @@
#!/bin/sh
#
# SP Racing H7 EXTREME specific board sensors init
# board specific sensors init
#------------------------------------------------------------------------------
board_adc start
# Internal SPI bus ICM-20602
@@ -13,5 +14,3 @@ icm20602 -s -b 3 -R 4 start # SPI 3
# Internal I2C bus
bmp388 -I start
@@ -1,5 +1,5 @@
/************************************************************************************
* nuttx-configs/spracing/h7extreme/include/board.h
* nuttx-config/include/board.h
*
* Copyright (C) 2016-2020 Gregory Nutt. All rights reserved.
* Authors: Igor Misic <igy1000mb@gmail.com>
@@ -32,12 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __NUTTX_CONFIG_SPRACING_H7EXTREME_INCLUDE_BOARD_H
#define __NUTTX_CONFIG_SPRACING_H7EXTREME_INCLUDE_BOARD_H
#pragma once
/************************************************************************************
* Included Files
************************************************************************************/
#include "board_dma_map.h"
#include <nuttx/config.h>
@@ -49,12 +45,8 @@
#include "stm32_rcc.h"
#include "stm32_sdmmc.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Clocking *************************************************************************/
/* The sp racing h7 extreme board provides the following clock sources:
/* The board provides the following clock sources:
*
* X1: 8 MHz crystal for HSE
*
@@ -63,13 +55,12 @@
* HSI: 64 MHz RC factory-trimmed
* HSE: 8 MHz crystal for HSE
*/
#define STM32_BOARD_XTAL 8000000ul
#define STM32_HSI_FREQUENCY 16000000ul
#define STM32_LSI_FREQUENCY 32000
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
#define STM32_LSE_FREQUENCY 32768
#define STM32_LSE_FREQUENCY 0
/* Main PLL Configuration.
*
@@ -104,12 +95,7 @@
* PLL1Q = PLL1_VCO/4 = 800 MHz / 4 = 200 MHz
* PLL1R = PLL1_VCO/2 = 800 MHz / 2 = 400 MHz - locked for H750
*/
#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \
RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \
RCC_PLLCFGR_DIVP1EN | \
RCC_PLLCFGR_DIVQ1EN | \
RCC_PLLCFGR_DIVR1EN)
#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE|RCC_PLLCFGR_PLL1RGE_4_8_MHZ|RCC_PLLCFGR_DIVP1EN|RCC_PLLCFGR_DIVQ1EN|RCC_PLLCFGR_DIVR1EN)
#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(2)
#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(200)
#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2)
@@ -122,12 +108,7 @@
#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 2)
/* PLL2 */
#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \
RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \
RCC_PLLCFGR_DIVP2EN | \
RCC_PLLCFGR_DIVQ2EN | \
RCC_PLLCFGR_DIVR2EN)
#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE|RCC_PLLCFGR_PLL2RGE_4_8_MHZ|RCC_PLLCFGR_DIVP2EN|RCC_PLLCFGR_DIVQ2EN|RCC_PLLCFGR_DIVR2EN)
#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4)
#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(260)
#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2)
@@ -140,12 +121,7 @@
#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
/* PLL3 */
#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \
RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \
RCC_PLLCFGR_DIVP3EN | \
RCC_PLLCFGR_DIVQ3EN | \
RCC_PLLCFGR_DIVR3EN)
#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE|RCC_PLLCFGR_PLL3RGE_4_8_MHZ|RCC_PLLCFGR_DIVP3EN|RCC_PLLCFGR_DIVQ3EN|RCC_PLLCFGR_DIVR3EN)
#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(2)
#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(50)
#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2)
@@ -160,7 +136,6 @@
/* SYSCLK = PLL1P = 400MHz
* CPUCLK = SYSCLK / 1 = 400 MHz
*/
#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK)
#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY)
#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1)
@@ -170,36 +145,30 @@
/* AHB clock (HCLK) is SYSCLK/2 (200 MHz max)
* HCLK1 = HCLK2 = HCLK3 = HCLK4 = 200
*/
#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */
#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */
#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
/* APB1 clock (PCLK1) is HCLK/2 (100 MHz) */
#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB2 clock (PCLK2) is HCLK/2 (50 MHz) */
#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB3 clock (PCLK3) is HCLK/2 (50 MHz) */
#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */
#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB4 clock (PCLK4) is HCLK/4 (50 MHz) */
#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */
#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* Timer clock frequencies */
/* Timers driven from APB1 will be twice PCLK1 */
#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
@@ -211,7 +180,6 @@
#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
/* Timers driven from APB2 will be twice PCLK2 */
#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY)
@@ -219,65 +187,25 @@
#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY)
/* Kernel Clock Configuration
*
* Note: look at Table 54 in ST Manual
*/
/* I2C123 clock source */
#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI
/* SPI123 clock source */
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL1
/* SPI45 clock source */
#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_APB
/* USB 1 and 2 clock source */
#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_HSI48
/* ADC 1 2 3 clock source */
#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2
/* QSPI clock source */
#define STM32_RCC_D1CCIPR_QSPISEL RCC_D1CCIPR_QSPISEL_PLL2
/* FLASH wait states
*
* ------------ ---------- -----------
* Vcore MAX ACLK WAIT STATES
* ------------ ---------- -----------
* 1.15-1.26 V 70 MHz 0
* (VOS1 level) 140 MHz 1
* 210 MHz 2
* 1.05-1.15 V 55 MHz 0
* (VOS2 level) 110 MHz 1
* 165 MHz 2
* 220 MHz 3
* 0.95-1.05 V 45 MHz 0
* (VOS3 level) 90 MHz 1
* 135 MHz 2
* 180 MHz 3
* 225 MHz 4
* ------------ ---------- -----------
* Note: look at Table 54 in ST Manual
*/
#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI /* I2C123 clock source */
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL1 /* SPI123 clock source */
#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_APB /* SPI45 clock source */
#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_HSI48 /* USB 1 and 2 clock source */
#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2 /* ADC 1 2 3 clock source */
#define STM32_RCC_D1CCIPR_QSPISEL RCC_D1CCIPR_QSPISEL_PLL2 /* QSPI clock source */
/* FLASH wait states */
#define BOARD_FLASH_WAITSTATES 2
/* SDMMC definitions ********************************************************/
/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */
#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq)
* div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s
*/
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#else
@@ -291,118 +219,64 @@
#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE
/* LED definitions ******************************************************************/
/* The sp racing h7 extreme board has three, LED_GREEN a Green LED, LED_BLUE
* Red LED can be controlled by software.
*
* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way.
* The following definitions are used to access individual LEDs.
*/
/* LED index values for use with board_userled() */
/* UART/USART */
#define GPIO_USART1_RX GPIO_USART1_RX_1 /* PB15 */
#define GPIO_USART1_TX GPIO_USART1_TX_1 /* PB14 */
#define BOARD_LED1 0
#define BOARD_NLEDS 1
#define GPIO_USART2_RX 0 /* Not in use */
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
#define BOARD_LED_RED BOARD_LED1
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
/* LED bits for use with board_userled_all() */
#define GPIO_UART4_RX GPIO_UART4_RX_5 /* PD0 */
#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PD1 */
#define BOARD_LED1_BIT (1 << BOARD_LED1)
#define GPIO_UART5_RX GPIO_UART5_RX_2 /* PB5 */
#define GPIO_UART5_TX GPIO_UART5_TX_1 /* PB13 */
/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in
* include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related
* events as follows:
*
*
* SYMBOL Meaning LED state
* Red Green Blue
* ---------------------- -------------------------- ------ ------ ----*/
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */
#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */
#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */
#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */
#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */
#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */
#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */
#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */
#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */
#define LED_IDLE 8 /* MCU is in sleep mode ON OFF OFF */
/* Alternate function pin selections ************************************************/
#define GPIO_USART1_RX GPIO_USART1_RX_1 /* PB15 */
#define GPIO_USART1_TX GPIO_USART1_TX_1 /* PB14 */
#define GPIO_USART2_RX 0 /* Not in use */
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
#define GPIO_UART4_RX GPIO_UART4_RX_5 /* PD0 */
#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PD1 */
#define GPIO_UART5_RX GPIO_UART5_RX_2 /* PB5 */
#define GPIO_UART5_TX GPIO_UART5_TX_1 /* PB13 */
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
/* SPI
* SPI2 is gyro 1
* SPI3 is gyro 2
* SPI4 is BARO
*/
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
//#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
//#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */
//#define GPIO_SPI1_SCK GPIO_SPI1_SCK_3 /* PG11 */
/* SPI */
#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz))
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_2 /* PC2 */
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_3 /* PC3 */
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_5 /* PD3 */
//#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_3) /* PG11 */
//#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
//#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_1 /* PB4 */
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_1 /* PD6 */
#define GPIO_SPI3_SCK GPIO_SPI3_SCK_1 /* PB3 */
#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_5) /* PD3 */
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_2 /* PC2 */
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_3 /* PC3 */
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 /* PE13 */
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1 /* PE14 */
#define GPIO_SPI4_SCK GPIO_SPI4_SCK_1 /* PE12 */
#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_1) /* PB3 */
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_1 /* PB4 */
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_1 /* PD6 */
/* I2C
*
* Each I2C is associated with a U[S]ART
* hence the naming I2C2_SDA_UART4 in FMU USAGE spreadsheet
*
* The optional _GPIO configurations allow the I2C driver to manually
* reset the bus to clear stuck slaves. They match the pin configuration,
* but are normally-high GPIOs.
*
*/
#define GPIO_SPI4_SCK ADJ_SLEW_RATE(GPIO_SPI4_SCK_1) /* PE12 */
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 /* PE13 */
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1 /* PE14 */
/* I2C */
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8)
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9)
/* SDMMC1
*
* VDD 3.3
* GND
* SDMMC1_CK PC12
* SDMMC1_CMD PD2
* SDMMC1_D0 PC8
* SDMMC1_D1 PC9
* SDMMC1_D2 PC10
* SDMMC1_D3 PC11
* GPIO_SDMMC1_NCD PG0
* SDMMC1_D0 PC8
* SDMMC1_D1 PC9
* SDMMC1_D2 PC10
* SDMMC1_D3 PC11
* SDMMC1_CK PC12
* SDMMC1_CMD PD2
* GPIO_SDMMC1_NCD PG0
*/
/* USB
@@ -412,47 +286,6 @@
* VBUS PA9
*/
/* Board provides GPIO or other Hardware for signaling to timing analyzer */
#if defined(CONFIG_BOARD_USE_PROBES)
# include "stm32_gpio.h"
# define PROBE_N(n) (1<<((n)-1))
# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN14) /* PE14 AUX1 */
# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN10) /* PA10 AUX2 */
# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 AUX3 */
# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9) /* PE9 AUX4 */
# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */
# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 FMU_CAP6 */
# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 FMU_CAP5 */
# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 FMU_CAP4 */
# define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN5) /* PA5 FMU_CAP3 */
# define PROBE_10 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN3) /* PB3 FMU_CAP2 */
# define PROBE_11 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN11) /* PB11 FMU_CAP1 */
# define PROBE_INIT(mask) \
do { \
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \
if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \
if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \
if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \
if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \
if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \
if ((mask)& PROBE_N(10)) { stm32_configgpio(PROBE_10); } \
if ((mask)& PROBE_N(11)) { stm32_configgpio(PROBE_11); } \
} while(0)
# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)
#else
# define PROBE_INIT(mask)
# define PROBE(n,s)
# define PROBE_MARK(n)
#endif
/* QSPI configuration */
#define CONFIG_STM32H7_QUADSPI
@@ -466,41 +299,3 @@
#define GPIO_QSPI_IO2 GPIO_QUADSPI_BK1_IO2_1 /* PE2 */
#define GPIO_QSPI_IO3 GPIO_QUADSPI_BK1_IO3_2 /* PD13 */
#define GPIO_QSPI_SCK GPIO_QUADSPI_CLK_1 /* PB2 */
/************************************************************************************
* Public Data
************************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
void stm32_boardinitialize(void);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /*__NUTTX_CONFIG_SPRACING_H7EXTREME_INCLUDE_BOARD_H */
@@ -35,7 +35,6 @@ add_library(drivers_board
i2c.cpp
init.c
led.c
sdio.c
spi.cpp
timer_config.cpp
usb.c
+27 -84
View File
@@ -35,61 +35,44 @@
/**
* @file board_config.h
*
* sp racing h7 extreme internal definitions
* Board internal definitions
*/
#pragma once
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
#include <stm32_gpio.h>
/****************************************************************************************************
* Definitions
****************************************************************************************************/
#define FLASH_BASED_PARAMS
#define BOARD_USE_EXTERNAL_FLASH //Configuration and firmware are in external flash
#define BOARD_HAS_USB_VALID 1 // LTC Has No USB valid
/* LEDs */
/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */
#define GPIO_nLED_RED /* PE3 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
#define BOARD_HAS_CONTROL_STATUS_LEDS 1
#define BOARD_HAS_CONTROL_STATUS_LEDS 1
#define BOARD_ARMED_STATE_LED LED_RED
#define BOARD_OVERLOAD_LED LED_RED
/*
* ADC channels
*
* These are the channel numbers of the ADCs of the microcontroller that
* can be used by the Px4 Firmware in the adc driver
*/
/* Define GPIO pins used as ADC N.B. Channel numbers must match below */
/* ADC channels */
#define PX4_ADC_GPIO \
/* PC4 */ GPIO_ADC12_INP4, \
/* PC1 */ GPIO_ADC123_INP11, \
/* PC0 */ GPIO_ADC123_INP10
/* PC4 */ GPIO_ADC12_INP4, \
/* PC1 */ GPIO_ADC123_INP11, \
/* PC0 */ GPIO_ADC123_INP10
/* Define Channel numbers must match above GPIO pins */
#define ADC_RSSI_IN_CHANNEL 4 /* PC4 */
#define ADC_BATTERY_VOLTAGE_CHANNEL 11 /* PC1 */
#define ADC_BATTERY_CURRENT_CHANNEL 10 /* PC0 */
/* Define Channel numbers must match above GPIO pin IN(n)*/
#define ADC_RSSI_IN_CHANNEL /* PC4 */ 4
#define ADC_BATTERY_VOLTAGE_CHANNEL /* PC1 */ 11
#define ADC_BATTERY_CURRENT_CHANNEL /* PC0 */ 10
#define ADC_CHANNELS \
((1 << ADC_RSSI_IN_CHANNEL) | \
(1 << ADC_BATTERY_CURRENT_CHANNEL) | \
(1 << ADC_BATTERY_VOLTAGE_CHANNEL))
#define ADC_CHANNELS (1 << 4) | (1 << 10) | (1 << 11)
/* PWM
*/
/* PWM */
#define DIRECT_PWM_OUTPUT_CHANNELS 8
/* Tone alarm output */
@@ -97,8 +80,7 @@
#define GPIO_TONE_ALARM_GPIO /* PE5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN5)
/* USB OTG FS
*
* PA8 OTG_FS_VBUS VBUS sensing
* PA9 OTG_FS_VBUS VBUS sensing
*/
#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9)
@@ -108,71 +90,32 @@
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS0"
#define GPIO_RSSI_IN /* PC5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN5)
#define SDIO_SLOTNO 0 /* Only one slot */
#define SDIO_MINOR 0
/* This board provides a DMA pool and APIs */
#define BOARD_NUM_IO_TIMERS 3
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {1, 2, 3, 0, 4, 5, 6, 7};
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
/* This board provides the board_on_reset interface */
#define BOARD_HAS_ON_RESET 1
#define BOARD_ENABLE_CONSOLE_BUFFER
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \
GPIO_RSSI_IN, \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D0), \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D1), \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D2), \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D3), \
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_CMD),\
GPIO_TONE_ALARM_IDLE, \
GPIO_RSSI_IN, \
GPIO_OTGFS_VBUS, \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
#define BOARD_NUM_IO_TIMERS 3
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {1, 2, 3, 0, 4, 5, 6, 7};
__BEGIN_DECLS
/****************************************************************************************************
* Public Types
****************************************************************************************************/
/****************************************************************************************************
* Public data
****************************************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************************************
* Public Functions
****************************************************************************************************/
/****************************************************************************
* Name: stm32_sdio_initialize
*
* Description:
* Initialize SDIO-based MMC/SD card support
*
****************************************************************************/
int stm32_sdio_initialize(void);
/****************************************************************************************************
* Name: stm32_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the board.
*
****************************************************************************************************/
extern void stm32_spiinitialize(void);
extern void stm32_usbinitialize(void);
extern void board_peripheral_reset(int ms);
#include <px4_platform_common/board_common.h>
+23 -62
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012-2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,42 +34,28 @@
/**
* @file init.c
*
* Board-specific early startup code. This file implements the
* board-specific early startup code. This file implements the
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialisation.
* subsystems and perform board-specific initialization.
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include "board_config.h"
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
#include <debug.h>
#include <errno.h>
#include <syslog.h>
#include <nuttx/config.h>
#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include <nuttx/analog/adc.h>
#include <nuttx/mm/gran.h>
#include <chip.h>
#include <stm32_uart.h>
#include <arch/board/board.h>
#include "arm_internal.h"
#include <px4_arch/io_timer.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_board_led.h>
#include <systemlib/px4_macros.h>
#include <px4_arch/io_timer.h>
#include <px4_platform_common/init.h>
#include <px4_platform/gpio.h>
#include <px4_platform/board_dma_alloc.h>
@@ -78,19 +64,6 @@
# include <parameters/flashparams/flashfs.h>
#endif
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/*
* Ideally we'd be able to get these from arm_internal.h,
* but since we want to be able to disable the NuttX use
* of leds for system indication at will and there is no
* separate switch, we need to build independent of the
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
@@ -139,32 +112,23 @@ __EXPORT void board_on_reset(int status)
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void
stm32_boardinitialize(void)
__EXPORT void stm32_boardinitialize(void)
{
board_on_reset(-1); /* Reset PWM first thing */
/* configure LEDs */
board_autoled_initialize();
/* Reset PWM first thing */
board_on_reset(-1);
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
/* configure SPI interfaces */
stm32_spiinitialize();
/* configure USB interfaces */
stm32_usbinitialize();
/* configure external memory*/
flash_w25q128_init();
/* configure LEDs */
board_autoled_initialize();
}
/****************************************************************************
@@ -178,29 +142,19 @@ stm32_boardinitialize(void)
* Input Parameters:
* arg - The boardctl() argument is passed to the board_app_initialize()
* implementation without modification. The argument has no
* meaning to NuttX; the meaning of the argument is a contract
* between the board-specific initalization logic and the the
* matching application logic. The value cold be such things as a
* mode enumeration value, a set of DIP switch switch settings, a
* pointer to configuration data read from a file or serial FLASH,
* or whatever you would like to do with it. Every implementation
* should accept zero/NULL as a default configuration.
* meaning to NuttX;
*
* Returned Value:
* Zero (OK) is returned on success; a negated errno value is returned on
* any failure to indicate the nature of the failure.
*
****************************************************************************/
__EXPORT int board_app_initialize(uintptr_t arg)
{
/* Need hrt running before using the ADC */
px4_platform_init();
/* configure the DMA allocator */
if (board_dma_alloc_init() < 0) {
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
@@ -219,15 +173,23 @@ __EXPORT int board_app_initialize(uintptr_t arg)
led_on(LED_RED);
}
#ifdef CONFIG_MMCSD
int ret = stm32_sdio_initialize();
/* Mount the SDIO-based MMC/SD block driver */
/* First, get an instance of the SDIO interface */
struct sdio_dev_s *sdio_dev = sdio_initialize(0); // SDIO_SLOTNO 0 Only one slot
if (ret != OK) {
led_on(LED_RED);
if (!sdio_dev) {
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", 0);
}
#endif
if (mmcsd_slotinitialize(0, sdio_dev) != OK) {
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver\n");
}
/* Assume that the SD card is inserted. What choice do we have? */
sdio_mediachange(sdio_dev, true);
#endif /* CONFIG_MMCSD */
up_udelay(20);
@@ -277,7 +239,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
#endif
/* Configure the HW based on the manifest */
px4_platform_configure();
return OK;
+3 -110
View File
@@ -32,9 +32,9 @@
****************************************************************************/
/**
* @file px4fmu2_led.c
* @file led.c
*
* PX4FMU LED backend.
* LED backend.
*/
#include <px4_platform_common/px4_config.h>
@@ -62,27 +62,14 @@ extern void led_off(int led);
extern void led_toggle(int led);
__END_DECLS
#ifdef CONFIG_ARCH_LEDS
static bool nuttx_owns_leds = true;
// B R S G
// 0 1 2 3
static const uint8_t xlatpx4[] = {1, 2, 4, 0};
# define xlat(p) xlatpx4[(p)]
static uint32_t g_ledmap[] = {
GPIO_nLED_RED, // Indexed by BOARD_LED_RED
};
#else
# define xlat(p) (p)
static uint32_t g_ledmap[] = {
GPIO_nLED_RED // Indexed by LED_RED
};
#endif
__EXPORT void led_init(void)
{
/* Configure LED GPIOs for output */
for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) {
if (g_ledmap[l] != 0) {
stm32_configgpio(g_ledmap[l]);
@@ -93,7 +80,6 @@ __EXPORT void led_init(void)
static void phy_set_led(int led, bool state)
{
/* Drive Low to switch on */
if (g_ledmap[led] != 0) {
stm32_gpiowrite(g_ledmap[led], !state);
}
@@ -123,96 +109,3 @@ __EXPORT void led_toggle(int led)
{
phy_set_led(xlat(led), !phy_get_led(xlat(led)));
}
#ifdef CONFIG_ARCH_LEDS
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: board_autoled_initialize
****************************************************************************/
void board_autoled_initialize(void)
{
led_init();
}
/****************************************************************************
* Name: board_autoled_on
****************************************************************************/
void board_autoled_on(int led)
{
if (!nuttx_owns_leds) {
return;
}
switch (led) {
default:
break;
case LED_HEAPALLOCATE:
break;
case LED_IRQSENABLED:
break;
case LED_STACKCREATED:
break;
case LED_INIRQ:
break;
case LED_SIGNAL:
break;
case LED_ASSERTION:
phy_set_led(BOARD_LED_RED, true);
break;
case LED_PANIC:
phy_set_led(BOARD_LED_RED, true);
break;
case LED_IDLE : /* IDLE */
phy_set_led(BOARD_LED_RED, true);
break;
}
}
/****************************************************************************
* Name: board_autoled_off
****************************************************************************/
void board_autoled_off(int led)
{
if (!nuttx_owns_leds) {
return;
}
switch (led) {
default:
break;
case LED_SIGNAL:
break;
case LED_INIRQ:
break;
case LED_ASSERTION:
phy_set_led(BOARD_LED_RED, false);
break;
case LED_PANIC:
phy_set_led(BOARD_LED_RED, false);
break;
case LED_IDLE : /* IDLE */
phy_set_led(BOARD_LED_RED, false);
break;
}
}
#endif /* CONFIG_ARCH_LEDS */
-177
View File
@@ -1,177 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <board_config.h>
#include <stdbool.h>
#include <stdio.h>
#include <debug.h>
#include <errno.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include "chip.h"
#include "board_config.h"
#include "stm32_gpio.h"
#include "stm32_sdmmc.h"
#ifdef CONFIG_MMCSD
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Card detections requires card support and a card detection GPIO */
#define HAVE_NCD 1
#if !defined(GPIO_SDMMC1_NCD)
# undef HAVE_NCD
#endif
/****************************************************************************
* Private Data
****************************************************************************/
static FAR struct sdio_dev_s *sdio_dev;
#ifdef HAVE_NCD
static bool g_sd_inserted = 0xff; /* Impossible value */
#endif
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_ncd_interrupt
*
* Description:
* Card detect interrupt handler.
*
****************************************************************************/
#ifdef HAVE_NCD
static int stm32_ncd_interrupt(int irq, FAR void *context)
{
bool present;
present = !stm32_gpioread(GPIO_SDMMC1_NCD);
if (sdio_dev && present != g_sd_inserted) {
sdio_mediachange(sdio_dev, present);
g_sd_inserted = present;
}
return OK;
}
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_sdio_initialize
*
* Description:
* Initialize SDIO-based MMC/SD card support
*
****************************************************************************/
int stm32_sdio_initialize(void)
{
int ret;
#ifdef HAVE_NCD
/* Card detect */
bool cd_status;
/* Configure the card detect GPIO */
stm32_configgpio(GPIO_SDMMC1_NCD);
/* Register an interrupt handler for the card detect pin */
stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt);
#endif
/* Mount the SDIO-based MMC/SD block driver */
/* First, get an instance of the SDIO interface */
finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO);
sdio_dev = sdio_initialize(SDIO_SLOTNO);
if (!sdio_dev) {
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO);
return -ENODEV;
}
/* Now bind the SDIO interface to the MMC/SD driver */
finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR);
ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev);
if (ret != OK) {
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
return ret;
}
finfo("Successfully bound SDIO to the MMC/SD driver\n");
#ifdef HAVE_NCD
/* Use SD card detect pin to check if a card is g_sd_inserted */
cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD);
finfo("Card detect : %d\n", cd_status);
sdio_mediachange(sdio_dev, cd_status);
#else
/* Assume that the SD card is inserted. What choice do we have? */
sdio_mediachange(sdio_dev, true);
#endif
return OK;
}
#endif /* CONFIG_MMCSD */
-1
View File
@@ -45,7 +45,6 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(SPI::Bus::SPI4, {
initSPIDevice(DRV_OSD_DEVTYPE_ATXXXX, SPI::CS{GPIO::PortE, GPIO::Pin11}),
}),
};
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
+4 -50
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2016 PX4 Development Team. All rights reserved.
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -32,61 +32,16 @@
****************************************************************************/
/**
* @file px4fmu_usb.c
* @file usb.c
*
* Board-specific USB functions.
*/
/************************************************************************************
* Included Files
************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
#include "board_config.h"
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
#include <arm_arch.h>
#include <chip.h>
#include <stm32_gpio.h>
#include <stm32_otg.h>
#include "board_config.h"
/************************************************************************************
* Definitions
************************************************************************************/
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: stm32_usbinitialize
*
* Description:
* Called to setup USB-related GPIO pins for the PX4FMU board.
*
************************************************************************************/
__EXPORT void stm32_usbinitialize(void)
{
/* The OTG FS has an internal soft pull-up */
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
#ifdef CONFIG_STM32H7_OTGFS
stm32_configgpio(GPIO_OTGFS_VBUS);
#endif
}
#include <debug.h>
/************************************************************************************
* Name: stm32_usbsuspend
@@ -98,7 +53,6 @@ __EXPORT void stm32_usbinitialize(void)
* while the USB is suspended.
*
************************************************************************************/
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
uinfo("resume: %d\n", resume);