forked from Archive/PX4-Autopilot
boards: mRo X2.1-777 fixes
- ardupilot bootloader compatibility (first 3 sectors) - clock tree fixes - start mavlink - start mpu9250 magnetometer (only onboard mag) - fixes https://github.com/PX4/Firmware/issues/15466
This commit is contained in:
parent
e16c8fa345
commit
fbc8e1b09e
|
@ -96,6 +96,11 @@ CONFIG:
|
|||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: mro_ctrl-zero-f7_default
|
||||
mro_x21-777_default:
|
||||
short: mro_x2.1-777
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: mro_x21-777_default
|
||||
nxp_fmuk66-v3_default:
|
||||
short: nxp_fmuk66-v3
|
||||
buildType: MinSizeRel
|
||||
|
|
|
@ -11,9 +11,13 @@ px4_add_board(
|
|||
TESTING
|
||||
UAVCAN_INTERFACES 1
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS3
|
||||
# IO DEBUG:/dev/ttyS0
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
GPS1:/dev/ttyS3
|
||||
# PX4IO:/dev/ttyS4
|
||||
# CONSOLE:/dev/tty5
|
||||
# OSD:/dev/tty6
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
|
@ -22,7 +26,7 @@ px4_add_board(
|
|||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
#dshot
|
||||
dshot
|
||||
gps
|
||||
#imu # all available imu drivers
|
||||
imu/invensense/icm20602
|
||||
|
@ -44,6 +48,7 @@ px4_add_board(
|
|||
pwm_out
|
||||
px4io
|
||||
roboclaw
|
||||
rpm
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
@ -57,6 +62,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
|
@ -84,6 +90,7 @@ px4_add_board(
|
|||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -106,6 +113,7 @@ px4_add_board(
|
|||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# mRo x21-777 specific board defaults
|
||||
# Board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
|
||||
|
|
|
@ -0,0 +1,7 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# Board specific MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Start MAVLink on the USB port
|
||||
mavlink start -d /dev/ttyACM0
|
|
@ -1,15 +1,11 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# mRo x21-777 specific board sensors init
|
||||
# Board specific sensors init
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
adc start
|
||||
|
||||
# Internal SPI bus ICM-20608-G
|
||||
icm20608g -s -R 8 start
|
||||
|
||||
# Internal SPI bus ICM-20602
|
||||
icm20602 -s -R 8 start
|
||||
|
||||
# Internal SPI bus mpu9250
|
||||
mpu9250 -s -R 8 start
|
||||
# SPI1
|
||||
ms5611 -s -b 1 start
|
||||
icm20608g -s -b 1 -R 8 start
|
||||
icm20602 -s -b 1 -R 8 start
|
||||
mpu9250 -s -b 1 -R 8 -M start
|
||||
|
|
|
@ -32,12 +32,8 @@
|
|||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
#include "board_dma_map.h"
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
@ -49,21 +45,16 @@
|
|||
#include "stm32_rcc.h"
|
||||
#include "stm32_sdmmc.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Clocking *************************************************************************/
|
||||
/* The mRo x2.1 777 board provides the following clock sources:
|
||||
/* The board provides the following clock sources:
|
||||
*
|
||||
* X301: 16 MHz crystal for HSE
|
||||
* X1: 24 MHz crystal for HSE
|
||||
*
|
||||
* So we have these clock source available within the STM32
|
||||
*
|
||||
* HSI: 16 MHz RC factory-trimmed
|
||||
* HSE: 16 MHz crystal for HSE
|
||||
* HSI: 16 MHz RC factory-trimmed internal oscillator
|
||||
* HSE: 24 MHz crystal for HSE
|
||||
*/
|
||||
|
||||
#define STM32_BOARD_XTAL 24000000ul
|
||||
|
||||
#define STM32_HSI_FREQUENCY 16000000ul
|
||||
|
@ -99,22 +90,21 @@
|
|||
|
||||
/* Highest SYSCLK with USB OTG FS clock = 48 MHz
|
||||
*
|
||||
* PLL_VCO = (16,000,000 / 8) * 216 = 432 MHz
|
||||
* PLL_VCO = (24,000,000 / 12) * 216 = 432 MHz
|
||||
* SYSCLK = 432 MHz / 2 = 216 MHz
|
||||
* USB OTG FS, SDMMC and RNG Clock = 432 MHz / 9 = 48 MHz
|
||||
*/
|
||||
|
||||
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(24)
|
||||
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(432)
|
||||
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(12)
|
||||
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(216)
|
||||
#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
|
||||
#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(9)
|
||||
|
||||
#define STM32_VCO_FREQUENCY ((STM32_HSE_FREQUENCY / 8) * 216)
|
||||
#define STM32_VCO_FREQUENCY ((STM32_HSE_FREQUENCY / 12) * 216)
|
||||
#define STM32_SYSCLK_FREQUENCY (STM32_VCO_FREQUENCY / 2)
|
||||
#define STM32_OTGFS_FREQUENCY (STM32_VCO_FREQUENCY / 9)
|
||||
|
||||
/* Configure factors for PLLSAI clock */
|
||||
|
||||
#define CONFIG_STM32F7_PLLSAI 1
|
||||
#define STM32_RCC_PLLSAICFGR_PLLSAIN RCC_PLLSAICFGR_PLLSAIN(192)
|
||||
#define STM32_RCC_PLLSAICFGR_PLLSAIP RCC_PLLSAICFGR_PLLSAIP(8)
|
||||
|
@ -122,7 +112,6 @@
|
|||
#define STM32_RCC_PLLSAICFGR_PLLSAIR RCC_PLLSAICFGR_PLLSAIR(2)
|
||||
|
||||
/* Configure Dedicated Clock Configuration Register */
|
||||
|
||||
#define STM32_RCC_DCKCFGR1_PLLI2SDIVQ RCC_DCKCFGR1_PLLI2SDIVQ(1)
|
||||
#define STM32_RCC_DCKCFGR1_PLLSAIDIVQ RCC_DCKCFGR1_PLLSAIDIVQ(1)
|
||||
#define STM32_RCC_DCKCFGR1_PLLSAIDIVR RCC_DCKCFGR1_PLLSAIDIVR(0)
|
||||
|
@ -132,10 +121,7 @@
|
|||
#define STM32_RCC_DCKCFGR1_DFSDM1SRC 0
|
||||
#define STM32_RCC_DCKCFGR1_ADFSDM1SRC 0
|
||||
|
||||
|
||||
|
||||
/* Configure factors for PLLI2S clock */
|
||||
|
||||
#define CONFIG_STM32F7_PLLI2S 1
|
||||
#define STM32_RCC_PLLI2SCFGR_PLLI2SN RCC_PLLI2SCFGR_PLLI2SN(192)
|
||||
#define STM32_RCC_PLLI2SCFGR_PLLI2SP RCC_PLLI2SCFGR_PLLI2SP(2)
|
||||
|
@ -143,7 +129,6 @@
|
|||
#define STM32_RCC_PLLI2SCFGR_PLLI2SR RCC_PLLI2SCFGR_PLLI2SR(2)
|
||||
|
||||
/* Configure Dedicated Clock Configuration Register 2 */
|
||||
|
||||
#define STM32_RCC_DCKCFGR2_USART1SRC RCC_DCKCFGR2_USART1SEL_APB
|
||||
#define STM32_RCC_DCKCFGR2_USART2SRC RCC_DCKCFGR2_USART2SEL_APB
|
||||
#define STM32_RCC_DCKCFGR2_UART4SRC RCC_DCKCFGR2_UART4SEL_APB
|
||||
|
@ -171,18 +156,15 @@
|
|||
*/
|
||||
|
||||
/* AHB clock (HCLK) is SYSCLK (216 MHz) */
|
||||
|
||||
#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */
|
||||
#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
|
||||
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
|
||||
|
||||
/* APB1 clock (PCLK1) is HCLK/4 (54 MHz) */
|
||||
|
||||
#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */
|
||||
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4)
|
||||
|
||||
/* 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)
|
||||
|
@ -194,12 +176,10 @@
|
|||
#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
|
||||
/* APB2 clock (PCLK2) is HCLK/2 (108MHz) */
|
||||
|
||||
#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
|
||||
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
|
||||
|
||||
/* 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_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
|
@ -283,31 +263,18 @@
|
|||
|
||||
/* UART8 has no alternate pin config */
|
||||
|
||||
/*
|
||||
* CAN
|
||||
*
|
||||
* CAN1 is routed to the onboard transceiver.
|
||||
*/
|
||||
|
||||
/* CAN */
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_3
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_3
|
||||
|
||||
/*
|
||||
* 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_2
|
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2
|
||||
#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)
|
||||
|
||||
/*
|
||||
* SPI
|
||||
*
|
||||
* There are sensors on SPI1, and SPI2 is connected to the FRAM.
|
||||
*/
|
||||
|
||||
/* SPI */
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1
|
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
|
||||
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
|
||||
|
@ -316,6 +283,3 @@
|
|||
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1
|
||||
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2
|
||||
|
||||
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1
|
||||
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1
|
||||
#define GPIO_SPI4_SCK GPIO_SPI4_SCK_1
|
||||
|
|
|
@ -74,7 +74,7 @@
|
|||
| Channel 10 | SAI1_B | SAI2_B | SAI2_A | - | - | - | SAI1_A | - |
|
||||
| Channel 11 | SDMMC2 | - | QUADSPI | - | - | SDMMC2 | - | - |
|
||||
| | | | | | | | | |
|
||||
| Usage | SPI1_RX_1 | | USART6_RX_2 | SPI1_TX_1 | | USART1_RX_2 | SDMMC1_2 | USART6_TX_2 |
|
||||
| Usage | SPI1_RX_1 | | USART6_RX_2 | SPI1_TX_1 | | TIM1_UP | SDMMC1_2 | USART6_TX_2 |
|
||||
*/
|
||||
|
||||
// DMA1 Channel/Stream Selections
|
||||
|
@ -91,9 +91,9 @@
|
|||
//--------------------------------------------//---------------------------//----------------
|
||||
#define DMAMAP_SPI1_RX DMAMAP_SPI1_RX_1 // DMA2, Stream 0, Channel 3 (SPI sensors RX)
|
||||
// AVAILABLE // DMA2, Stream 1
|
||||
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2 // DMA2, Stream 2, Channel 5
|
||||
#define DMAMAP_SPI1_TX DMAMAP_SPI1_TX_1 // DMA2, Stream 3, Channel 3 (SPI sensors TX)
|
||||
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2 // DMA2, Stream 2, Channel 5 (PX4_IO RX)
|
||||
// AVAILABLE // DMA2, Stream 3, Channel 3
|
||||
// AVAILABLE // DMA2, Stream 4
|
||||
#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2 // DMA2, Stream 5, Channel 4
|
||||
#define DMAMAP_SDMMC1 DMAMAP_SDMMC1_2 // DMA2, Stream 6, Channel 4
|
||||
#define DMAMAP_USART6_TX DMAMAP_USART6_TX_2 // DMA2, Stream 7, Channel 5
|
||||
#define DMAMAP_SPI1_TX DMAMAP_SPI1_TX_2 // DMA2, Stream 5, Channel 3 (SPI sensors TX)
|
||||
#define DMAMAP_SDMMC1 DMAMAP_SDMMC1_2 // DMA2, Stream 6, Channel 4 (SDMMC)
|
||||
#define DMAMAP_USART6_TX DMAMAP_USART6_TX_2 // DMA2, Stream 7, Channel 5 (PX4_IO TX)
|
||||
|
|
|
@ -214,7 +214,6 @@ 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
|
||||
|
@ -232,6 +231,7 @@ 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
|
||||
|
|
|
@ -65,19 +65,19 @@
|
|||
* where the code expects to begin execution by jumping to the entry point in
|
||||
* the 0x0800:0000 address range.
|
||||
*
|
||||
* Bootloader reserves the first 32K bank (2 Mbytes Flash memory single bank)
|
||||
* Bootloader reserves three 32K banks (2 Mbytes Flash memory single bank)
|
||||
* organization (256 bits read width)
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
FLASH_ITCM (rx) : ORIGIN = 0x00208000, LENGTH = 2016K
|
||||
FLASH_AXIM (rx) : ORIGIN = 0x08008000, LENGTH = 2016K
|
||||
FLASH_ITCM (rx) : ORIGIN = 0x00218000, LENGTH = 1952K
|
||||
FLASH_AXIM (rx) : ORIGIN = 0x08018000, LENGTH = 1952K
|
||||
|
||||
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 16K
|
||||
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K
|
||||
SRAM2 (rwx) : ORIGIN = 0x2007c000, LENGTH = 16K
|
||||
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 16K
|
||||
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K
|
||||
SRAM2 (rwx) : ORIGIN = 0x2007c000, LENGTH = 16K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
|
|
|
@ -32,20 +32,18 @@
|
|||
############################################################################
|
||||
|
||||
add_library(drivers_board
|
||||
init.c
|
||||
i2c.cpp
|
||||
init.c
|
||||
led.c
|
||||
sdio.c
|
||||
spi.cpp
|
||||
timer_config.cpp
|
||||
usb.c
|
||||
)
|
||||
add_dependencies(drivers_board arch_board_hw_info)
|
||||
|
||||
target_link_libraries(drivers_board
|
||||
PRIVATE
|
||||
arch_spi
|
||||
arch_board_hw_info
|
||||
drivers__led # drv_led_start
|
||||
nuttx_arch # sdio
|
||||
nuttx_drivers # sdio
|
||||
|
|
|
@ -34,27 +34,17 @@
|
|||
/**
|
||||
* @file board_config.h
|
||||
*
|
||||
* mRo x2.1 777 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
|
||||
****************************************************************************************************/
|
||||
|
||||
/* PX4IO connection configuration */
|
||||
|
||||
#define BOARD_USES_PX4IO_VERSION 2
|
||||
#define PX4IO_SERIAL_DEVICE "/dev/ttyS4"
|
||||
#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX
|
||||
|
@ -68,8 +58,6 @@
|
|||
#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY
|
||||
#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */
|
||||
|
||||
|
||||
/* PX4FMU GPIOs ***********************************************************************************/
|
||||
/* LEDs */
|
||||
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN12)
|
||||
|
@ -90,7 +78,7 @@
|
|||
|
||||
/* Power supply control and monitoring GPIOs */
|
||||
// Signal is not connected
|
||||
#define GPIO_VDD_5V_PERIPH_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8)
|
||||
#define GPIO_nVDD_5V_PERIPH_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8)
|
||||
#define GPIO_VDD_BRICK_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_VDD_3V3_SENSORS_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
|
||||
#define GPIO_VDD_5V_PERIPH_OC (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN15)
|
||||
|
@ -101,8 +89,7 @@
|
|||
#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
|
||||
#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN15)
|
||||
|
||||
/* PWM
|
||||
*/
|
||||
/* PWM */
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 6
|
||||
#define DIRECT_INPUT_TIMER_CHANNELS 6
|
||||
|
||||
|
@ -113,8 +100,8 @@
|
|||
#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9)
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 8 /* use timer8 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
|
||||
#define HRT_TIMER 8 /* use timer8 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */
|
||||
|
||||
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
|
||||
#define PWMIN_TIMER 4
|
||||
|
@ -137,9 +124,9 @@
|
|||
#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 SDIO_SLOTNO 0 /* Only one slot */
|
||||
#define SDIO_MINOR 0
|
||||
|
@ -149,12 +136,8 @@
|
|||
#define BOARD_NUM_IO_TIMERS 3
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_sdio_initialize
|
||||
|
@ -166,24 +149,12 @@ __BEGIN_DECLS
|
|||
|
||||
int stm32_sdio_initialize(void);
|
||||
|
||||
/****************************************************************************************************
|
||||
* Name: stm32_spiinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
|
||||
*
|
||||
****************************************************************************************************/
|
||||
|
||||
extern void stm32_spiinitialize(void);
|
||||
|
||||
extern void board_peripheral_reset(int ms);
|
||||
|
||||
extern void stm32_usbinitialize(void);
|
||||
|
||||
extern void board_peripheral_reset(int ms);
|
||||
|
||||
#include <px4_platform_common/board_common.h>
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
__END_DECLS
|
||||
|
|
|
@ -34,34 +34,19 @@
|
|||
/**
|
||||
* @file init.c
|
||||
*
|
||||
* mRO x2.1 777 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.
|
||||
* subsystems and perform board-specific initialisation.
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <debug.h>
|
||||
#include <errno.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 "up_internal.h"
|
||||
|
||||
|
@ -73,71 +58,12 @@
|
|||
#include <px4_platform/gpio.h>
|
||||
#include <px4_platform/board_dma_alloc.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Configuration ************************************************************/
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from up_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_rc_input
|
||||
*
|
||||
* Description:
|
||||
* All boards my optionally provide this API to invert the Serial RC input.
|
||||
* This is needed on SoCs that support the notion RXINV or TXINV as apposed to
|
||||
* and external XOR controlled by a GPIO
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void board_rc_input(bool invert_on, uint32_t uxart_base)
|
||||
{
|
||||
|
||||
irqstate_t irqstate = px4_enter_critical_section();
|
||||
|
||||
uint32_t cr1 = getreg32(STM32_USART_CR1_OFFSET + uxart_base);
|
||||
uint32_t cr2 = getreg32(STM32_USART_CR2_OFFSET + uxart_base);
|
||||
uint32_t regval = cr1;
|
||||
|
||||
/* {R|T}XINV bit fields can only be written when the USART is disabled (UE=0). */
|
||||
|
||||
regval &= ~USART_CR1_UE;
|
||||
|
||||
putreg32(regval, STM32_USART_CR1_OFFSET + uxart_base);
|
||||
|
||||
if (invert_on) {
|
||||
#if defined(BOARD_HAS_RX_TX_SWAP) && RC_SERIAL_PORT_IS_SWAPED == 1
|
||||
|
||||
/* This is only ever turned on */
|
||||
|
||||
cr2 |= (USART_CR2_RXINV | USART_CR2_TXINV | USART_CR2_SWAP);
|
||||
#else
|
||||
cr2 |= (USART_CR2_RXINV | USART_CR2_TXINV);
|
||||
#endif
|
||||
|
||||
} else {
|
||||
cr2 &= ~(USART_CR2_RXINV | USART_CR2_TXINV);
|
||||
}
|
||||
|
||||
putreg32(cr2, STM32_USART_CR2_OFFSET + uxart_base);
|
||||
putreg32(cr1, STM32_USART_CR1_OFFSET + uxart_base);
|
||||
|
||||
leave_critical_section(irqstate);
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_peripheral_reset
|
||||
*
|
||||
|
@ -147,8 +73,8 @@ __EXPORT void board_rc_input(bool invert_on, uint32_t uxart_base)
|
|||
__EXPORT void board_peripheral_reset(int ms)
|
||||
{
|
||||
/* set the peripheral rails off */
|
||||
stm32_configgpio(GPIO_VDD_5V_PERIPH_EN);
|
||||
stm32_gpiowrite(GPIO_VDD_5V_PERIPH_EN, 1);
|
||||
stm32_configgpio(GPIO_nVDD_5V_PERIPH_EN);
|
||||
stm32_gpiowrite(GPIO_nVDD_5V_PERIPH_EN, 1);
|
||||
|
||||
/* wait for the peripheral rail to reach GND */
|
||||
usleep(ms * 1000);
|
||||
|
@ -157,7 +83,7 @@ __EXPORT void board_peripheral_reset(int ms)
|
|||
/* re-enable power */
|
||||
|
||||
/* switch the peripheral rail back on */
|
||||
stm32_gpiowrite(GPIO_VDD_5V_PERIPH_EN, 0);
|
||||
stm32_gpiowrite(GPIO_nVDD_5V_PERIPH_EN, 0);
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
|
@ -188,31 +114,6 @@ __EXPORT void board_on_reset(int status)
|
|||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_app_finalinitialize
|
||||
*
|
||||
* Description:
|
||||
* Perform application specific initialization. This function is never
|
||||
* called directly from application code, but only indirectly via the
|
||||
* (non-standard) boardctl() interface using the command
|
||||
* BOARDIOC_FINALINIT.
|
||||
*
|
||||
* Input Parameters:
|
||||
* arg - The argument has no meaning.
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) is returned on success; a negated errno value is returned on
|
||||
* any failure to indicate the nature of the failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_BOARDCTL_FINALINIT
|
||||
int board_app_finalinitialize(uintptr_t arg)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
|
@ -222,14 +123,12 @@ int board_app_finalinitialize(uintptr_t arg)
|
|||
* 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 */
|
||||
/* Reset PWM first thing */
|
||||
board_on_reset(-1);
|
||||
|
||||
/* configure LEDs */
|
||||
|
||||
board_autoled_initialize();
|
||||
|
||||
/* configure pins */
|
||||
|
@ -243,7 +142,7 @@ stm32_boardinitialize(void)
|
|||
px4_arch_configgpio(GPIO_ADC1_IN15); /* PRESSURE_SENS */
|
||||
|
||||
/* configure power supply control/sense pins */
|
||||
px4_arch_configgpio(GPIO_VDD_5V_PERIPH_EN);
|
||||
px4_arch_configgpio(GPIO_nVDD_5V_PERIPH_EN);
|
||||
px4_arch_configgpio(GPIO_VDD_3V3_SENSORS_EN);
|
||||
px4_arch_configgpio(GPIO_VDD_BRICK_VALID);
|
||||
px4_arch_configgpio(GPIO_VDD_5V_PERIPH_OC);
|
||||
|
@ -253,13 +152,10 @@ stm32_boardinitialize(void)
|
|||
px4_arch_configgpio(GPIO_CAN1_TX);
|
||||
|
||||
/* configure SPI interfaces */
|
||||
|
||||
stm32_spiinitialize();
|
||||
|
||||
/* configure USB interfaces */
|
||||
|
||||
stm32_usbinitialize();
|
||||
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
|
@ -273,39 +169,38 @@ 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 */
|
||||
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, true);
|
||||
stm32_gpiowrite(GPIO_nVDD_5V_PERIPH_EN, false);
|
||||
board_control_spi_sensors_power(true, 0xffff);
|
||||
|
||||
px4_platform_init();
|
||||
|
||||
/* configure the DMA allocator */
|
||||
stm32_spiinitialize();
|
||||
|
||||
/* configure the DMA allocator */
|
||||
if (board_dma_alloc_init() < 0) {
|
||||
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
|
||||
}
|
||||
|
||||
#if defined(SERIAL_HAVE_RXDMA)
|
||||
/* set up the serial DMA polling */
|
||||
static struct hrt_call serial_dma_call;
|
||||
struct timespec ts;
|
||||
|
||||
/*
|
||||
* Poll at 1ms intervals for received bytes that have not triggered
|
||||
* a DMA event.
|
||||
*/
|
||||
struct timespec ts;
|
||||
ts.tv_sec = 0;
|
||||
ts.tv_nsec = 1000000;
|
||||
|
||||
|
@ -314,7 +209,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
|||
ts_to_abstime(&ts),
|
||||
(hrt_callout)stm32_serial_dma_poll,
|
||||
NULL);
|
||||
|
||||
#endif
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
|
|
|
@ -34,7 +34,7 @@
|
|||
#include <px4_arch/io_timer_hw_description.h>
|
||||
|
||||
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
initIOTimer(Timer::Timer1),
|
||||
initIOTimer(Timer::Timer1, DMA{DMA::Index2, DMA::Stream5, DMA::Channel6}),
|
||||
initIOTimer(Timer::Timer4),
|
||||
};
|
||||
|
||||
|
|
Loading…
Reference in New Issue