forked from Archive/PX4-Autopilot
gnss-m9n-f4:Board support clean up
SD is on SPI3 - correct pin mapping Fix DMA Mapping for all SPI and RX DMA on U[S]ART RX Fix Memory MAP SRAM size Removed unused GPIO Used proper I2C definitions Ensure Watchdog is configured for debugging Fixed FLASH param definitions Removed unedded SPI init matek_gnss-m9n-f4:Correct Board ID and Size Build order SJF Added Support for F40x
This commit is contained in:
parent
d92244b664
commit
cb06f82f0f
|
@ -60,8 +60,8 @@ pipeline {
|
|||
"holybro_kakutef7_default",
|
||||
"holybro_pix32v5_default",
|
||||
"matek_h743-slim",
|
||||
"matek_gnss-m9n-f4_default",
|
||||
"matek_gnss-m9n-f4_canbootloader",
|
||||
"matek_gnss-m9n-f4_default",
|
||||
"modalai_fc-v1_default",
|
||||
"modalai_fc-v1_rtps",
|
||||
"modalai_fc-v2_default",
|
||||
|
|
|
@ -9,10 +9,14 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
|
|||
CONFIG_DRIVERS_MAGNETOMETER_RM3100=y
|
||||
CONFIG_BOARD_UAVCAN_INTERFACES=1
|
||||
CONFIG_DRIVERS_UAVCANNODE=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_SYSTEMCMDS_REBOOT=y
|
||||
CONFIG_SYSTEMCMDS_TOP=y
|
||||
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
|
||||
CONFIG_SYSTEMCMDS_UORB=y
|
||||
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
|
||||
CONFIG_SYSTEMCMDS_VER=y
|
||||
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
{
|
||||
"board_id": 140,
|
||||
"board_id": 1014,
|
||||
"magic": "PX4FWv1",
|
||||
"description": "Firmware for the MatekM9nf4can cannode board",
|
||||
"image": "",
|
||||
|
@ -7,7 +7,7 @@
|
|||
"summary": "MateksysGnss-m9n-f4",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"image_maxsize": 1032192,
|
||||
"image_maxsize": 983040,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
||||
|
|
|
@ -10,3 +10,5 @@ icm20602 -s start
|
|||
rm3100 -b 2 -s start
|
||||
|
||||
dps310 -a 118 -X start
|
||||
|
||||
sensors start
|
|
@ -39,13 +39,6 @@ CONFIG_LIB_BOARDCTL=y
|
|||
CONFIG_MM_REGIONS=2
|
||||
CONFIG_NAME_MAX=0
|
||||
CONFIG_NUNGET_CHARS=0
|
||||
CONFIG_NXFONTS_DISABLE_16BPP=y
|
||||
CONFIG_NXFONTS_DISABLE_1BPP=y
|
||||
CONFIG_NXFONTS_DISABLE_24BPP=y
|
||||
CONFIG_NXFONTS_DISABLE_2BPP=y
|
||||
CONFIG_NXFONTS_DISABLE_32BPP=y
|
||||
CONFIG_NXFONTS_DISABLE_4BPP=y
|
||||
CONFIG_NXFONTS_DISABLE_8BPP=y
|
||||
CONFIG_PREALLOC_TIMERS=0
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAM_SIZE=131072
|
||||
|
@ -60,8 +53,7 @@ CONFIG_STACK_COLORATION=y
|
|||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_DISABLE_BUFFERING=y
|
||||
CONFIG_STM32_CCMEXCLUDE=y
|
||||
CONFIG_STM32_DFU=y
|
||||
CONFIG_STM32_JTAG_SW_ENABLE=y
|
||||
CONFIG_STM32_NOEXT_VECTORS=y
|
||||
CONFIG_STM32_TIM8=y
|
||||
CONFIG_TASK_NAME_SIZE=0
|
||||
|
|
|
@ -35,11 +35,16 @@
|
|||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
************************************************************************************/
|
||||
#include "board_dma_map.h"
|
||||
|
||||
#ifndef __ARCH_BOARD_BOARD_H
|
||||
#define __ARCH_BOARD_BOARD_H
|
||||
|
||||
#include "board_dma_map.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#ifndef __ASSEMBLY__
|
||||
# include <stdint.h>
|
||||
|
@ -81,12 +86,12 @@
|
|||
* LSE - 32.768 kHz
|
||||
*/
|
||||
|
||||
#define STM32_BOARD_USEHSE 1
|
||||
#define STM32_BOARD_XTAL 8000000ul
|
||||
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
|
||||
|
||||
#define STM32_HSI_FREQUENCY 16000000ul
|
||||
#define STM32_LSI_FREQUENCY 32000
|
||||
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
|
||||
#define STM32_LSE_FREQUENCY 32768
|
||||
|
||||
/* Main PLL Configuration.
|
||||
*
|
||||
|
@ -164,36 +169,6 @@
|
|||
#define BOARD_TIM13_FREQUENCY STM32_APB1_TIM13_CLKIN
|
||||
#define BOARD_TIM14_FREQUENCY STM32_APB1_TIM14_CLKIN
|
||||
|
||||
/* SDIO dividers. Note that slower clocking is required when DMA is disabled
|
||||
* in order to avoid RX overrun/TX underrun errors due to delayed responses
|
||||
* to service FIFOs in interrupt driven mode. These values have not been
|
||||
* tuned!!!
|
||||
*
|
||||
* SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(118+2)=400 KHz
|
||||
*/
|
||||
|
||||
#define SDIO_INIT_CLKDIV (118 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
|
||||
/* DMA ON: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(1+2)=16 MHz
|
||||
* DMA OFF: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(2+2)=12 MHz
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_STM32_SDIO_DMA
|
||||
# define SDIO_MMCXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
#else
|
||||
# define SDIO_MMCXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
#endif
|
||||
|
||||
/* DMA ON: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(1+2)=16 MHz
|
||||
* DMA OFF: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(2+2)=12 MHz
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_STM32_SDIO_DMA
|
||||
# define SDIO_SDXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
#else
|
||||
# define SDIO_SDXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
#endif
|
||||
|
||||
/* LED definitions ******************************************************************/
|
||||
/* 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.
|
||||
|
@ -299,16 +274,16 @@
|
|||
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1
|
||||
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1
|
||||
|
||||
/* SPI3:
|
||||
* CS: PB3 -- configured in board_config.h
|
||||
* CLK: PC10
|
||||
* MISO: PC11
|
||||
* MOSI: PC12
|
||||
/* SPI3: SD CARD
|
||||
* CS: PC14 -- configured in board_config.h
|
||||
* CLK: PB3
|
||||
* MISO: PB4
|
||||
* MOSI: PB5
|
||||
*/
|
||||
|
||||
#define GPIO_SPI3_SCK GPIO_SPI3_SCK_2
|
||||
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2
|
||||
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_2
|
||||
#define GPIO_SPI3_SCK GPIO_SPI3_SCK_1
|
||||
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_1
|
||||
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_1
|
||||
|
||||
/*
|
||||
* I2C (external)
|
||||
|
|
|
@ -48,7 +48,7 @@
|
|||
| | TIM5_UP_1 | TIM5_TRIG_1 | | TIM5_TRIG_2 | | | | |
|
||||
| Channel 7 | - | TIM6_UP | I2C2_RX | I2C2_RX_1 | USART3_TX_2 | DAC1 | DAC2 | I2C2_TX |
|
||||
| | | | | | | | | |
|
||||
| Usage | | TIM2_UP_1 | TIM3_UP | SPI2_RX | SPI2_TX | | | |
|
||||
| Usage | SPI3_RX | TIM2_UP_1 | UART4_RX | SPI2_RX | SPI2_TX | | | SPI3_TX |
|
||||
|
||||
|
||||
| DMA2 | Stream 0 | Stream 1 | Stream 2 | Stream 3 | Stream 4 | Stream 5 | Stream 6 | Stream 7 |
|
||||
|
@ -68,12 +68,18 @@
|
|||
| | | | | | | | | TIM8_TRIG |
|
||||
| | | | | | | | | TIM8_COM |
|
||||
| | | | | | | | | |
|
||||
| Usage | SPI1_RX_1 | USART6_RX_1 | USART1_RX_1 | SPI1_TX_1 | | | SDIO | |
|
||||
| Usage | SPI1_RX_1 | USART6_RX_1 | USART1_RX_1 | SPI1_TX_1 | | | | |
|
||||
*/
|
||||
|
||||
// DMA2 Channel/Stream Selections
|
||||
//--------------------------------------------//---------------------------//----------------
|
||||
#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_1 // DMA2, Stream 0, Channel 3 (SPI1 RX)
|
||||
#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_1 // DMA2, Stream 3, Channel 3 (SPI1 TX)
|
||||
#define DMAMAP_USART1_RX DMAMAP_USART1_RX_1 // DMA2, Stream 2, Channel 4 (CONSOLE)
|
||||
//#define DMAMAP_UART4_RX DMAMAP_UART4_RX // DMA1, Stream 2, Channel 4 (GPS)
|
||||
|
||||
#define DMACHAN_SPI2_RX DMAMAP_SPI2_RX // DMA1, Stream 3, Channel 0 (SPI2 RX)
|
||||
#define DMACHAN_SPI2_TX DMAMAP_SPI2_TX // DMA1, Stream 4, Channel 0 (SPI2 TX)
|
||||
#define DMACHAN_SPI3_RX DMAMAP_SPI3_RX_1 // DMA1, Stream 0, Channel 0 (SPI3 RX SD)
|
||||
#define DMACHAN_SPI3_TX DMAMAP_SPI3_TX_2 // DMA1, Stream 7, Channel 0 (SPI3 TX SD)
|
||||
|
||||
#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_1 // DMA2, Stream 0, Channel 3 (SPI1 RX)
|
||||
#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_1 // DMA2, Stream 3, Channel 3 (SPI1 TX)
|
||||
|
|
|
@ -38,7 +38,6 @@ CONFIG_ARCH_STACKDUMP=y
|
|||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CUSTOM_LEDS=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=16717
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
|
@ -99,13 +98,14 @@ CONFIG_NSH_DISABLE_IFUPDOWN=y
|
|||
CONFIG_NSH_DISABLE_TELNETD=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_MMCSDSPIPORTNO=2
|
||||
CONFIG_NSH_MMCSDSPIPORTNO=3
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_OTG_ID_GPIO_DISABLE=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
|
@ -160,6 +160,11 @@ CONFIG_STM32_SPI1=y
|
|||
CONFIG_STM32_SPI1_DMA=y
|
||||
CONFIG_STM32_SPI1_DMA_BUFFER=1024
|
||||
CONFIG_STM32_SPI2=y
|
||||
CONFIG_STM32_SPI2_DMA=y
|
||||
CONFIG_STM32_SPI2_DMA_BUFFER=1024
|
||||
CONFIG_STM32_SPI3=y
|
||||
CONFIG_STM32_SPI3_DMA=y
|
||||
CONFIG_STM32_SPI3_DMA_BUFFER=512
|
||||
CONFIG_STM32_SPI_DMA=y
|
||||
CONFIG_STM32_SPI_DMATHRESHOLD=1024
|
||||
CONFIG_STM32_TIM5=y
|
||||
|
@ -173,8 +178,10 @@ CONFIG_SYSTEM_NSH=y
|
|||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_UART4_BAUD=38400
|
||||
CONFIG_UART4_RXBUFSIZE=300
|
||||
CONFIG_UART4_RXDMA=y
|
||||
CONFIG_UART4_TXBUFSIZE=300
|
||||
CONFIG_USART1_RXBUFSIZE=300
|
||||
CONFIG_USART1_RXDMA=y
|
||||
CONFIG_USART1_SERIAL_CONSOLE=y
|
||||
CONFIG_USART1_TXBUFSIZE=300
|
||||
CONFIG_USBDEV=y
|
||||
|
|
|
@ -51,8 +51,7 @@
|
|||
MEMORY
|
||||
{
|
||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 32K
|
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K
|
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
|
|
|
@ -51,8 +51,7 @@
|
|||
MEMORY
|
||||
{
|
||||
flash (rx) : ORIGIN = 0x08010000, LENGTH = 960K
|
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K
|
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2018-2021 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2018-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
|
||||
|
@ -37,8 +37,7 @@ if("${PX4_BOARD_LABEL}" STREQUAL "canbootloader")
|
|||
boot_config.h
|
||||
boot.c
|
||||
led.c
|
||||
led.h
|
||||
usb.c
|
||||
usb.c
|
||||
)
|
||||
target_link_libraries(drivers_board
|
||||
PRIVATE
|
||||
|
@ -50,23 +49,22 @@ if("${PX4_BOARD_LABEL}" STREQUAL "canbootloader")
|
|||
|
||||
else()
|
||||
add_library(drivers_board
|
||||
can.c
|
||||
i2c.cpp
|
||||
led.c
|
||||
init.c
|
||||
spi.cpp
|
||||
autoled.cpp
|
||||
led.c
|
||||
timer_config.cpp
|
||||
usb.c
|
||||
can.c
|
||||
timer_config.cpp
|
||||
usb.c
|
||||
)
|
||||
|
||||
target_link_libraries(drivers_board
|
||||
PRIVATE
|
||||
arch_spi
|
||||
nuttx_arch
|
||||
nuttx_drivers
|
||||
px4_layer
|
||||
arch_spi
|
||||
arch_io_pins
|
||||
arch_io_pins
|
||||
drivers__led
|
||||
)
|
||||
endif()
|
||||
|
|
|
@ -1,63 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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
|
||||
* 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
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file led.cpp
|
||||
*
|
||||
* LED auto on/off functions
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "stm32_gpio.h"
|
||||
#include "board_config.h"
|
||||
#include "led.h"
|
||||
|
||||
#include <nuttx/board.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
__EXPORT void board_autoled_on(int led)
|
||||
{
|
||||
if (led == 1) {
|
||||
stm32_gpiowrite(GPIO_LED1, false);
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT void board_autoled_off(int led)
|
||||
{
|
||||
if (led == 1) {
|
||||
stm32_gpiowrite(GPIO_LED1, true);
|
||||
}
|
||||
}
|
|
@ -76,23 +76,8 @@
|
|||
*/
|
||||
#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTC|GPIO_PIN5)
|
||||
|
||||
#define GPIO_I2C1_SCL_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_I2C1_SDA_RESET /* PB11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN11)
|
||||
|
||||
#define GPIO_USART1_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN10)
|
||||
#define GPIO_USART1_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN9)
|
||||
|
||||
//#define GPIO_USART2_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN11)
|
||||
//#define GPIO_USART2_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN10)
|
||||
|
||||
#define GPIO_USART3_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTC|GPIO_PIN11)
|
||||
#define GPIO_USART3_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTC|GPIO_PIN10)
|
||||
|
||||
#define GPIO_UART4_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_UART4_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN0)
|
||||
|
||||
//#define GPIO_UART5_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTD|GPIO_PIN2)
|
||||
//#define GPIO_UART5_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTC|GPIO_PIN12)
|
||||
#define GPIO_I2C2_SCL_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_I2C2_SDA_RESET /* PB11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN11)
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 3 /* use timer 3 as HRT */
|
||||
|
@ -100,9 +85,13 @@
|
|||
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||
|
||||
/* This board provides a DMA pool and APIs */
|
||||
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
|
||||
|
||||
|
||||
#define PX4_GPIO_INIT_LIST { \
|
||||
GPIO_I2C1_SCL_RESET, \
|
||||
GPIO_I2C1_SDA_RESET, \
|
||||
GPIO_I2C2_SCL_RESET, \
|
||||
GPIO_I2C2_SDA_RESET, \
|
||||
GPIO_BOOT_CONFIG, \
|
||||
GPIO_CAN1_TX, \
|
||||
GPIO_CAN1_RX, \
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2021 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-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
|
||||
|
@ -60,7 +60,6 @@
|
|||
#include <nuttx/i2c/i2c_master.h>
|
||||
#include <nuttx/mmcsd.h>
|
||||
#include <nuttx/analog/adc.h>
|
||||
#include <nuttx/mm/gran.h>
|
||||
|
||||
#include <stm32.h>
|
||||
#include "board_config.h"
|
||||
|
@ -69,80 +68,20 @@
|
|||
#include <arch/board/board.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_board_led.h>
|
||||
#include <drivers/drv_watchdog.h>
|
||||
|
||||
#include "led.h"
|
||||
|
||||
#include <systemlib/px4_macros.h>
|
||||
|
||||
#include <px4_arch/io_timer.h>
|
||||
#include <px4_platform_common/init.h>
|
||||
#include <px4_platform/board_dma_alloc.h>
|
||||
#include <px4_platform/gpio.h>
|
||||
|
||||
#include <px4_platform/gpio.h>
|
||||
#include <px4_platform/board_dma_alloc.h>
|
||||
# if defined(FLASH_BASED_PARAMS)
|
||||
# include <parameters/flashparams/flashfs.h>
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/*
|
||||
* 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
|
||||
|
||||
/****************************************************************************
|
||||
* Protected Functions
|
||||
****************************************************************************/
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
/************************************************************************************
|
||||
* Name: board_peripheral_reset
|
||||
*
|
||||
* Description:
|
||||
*
|
||||
************************************************************************************/
|
||||
__EXPORT void board_peripheral_reset(int ms)
|
||||
{
|
||||
UNUSED(ms);
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_on_reset
|
||||
*
|
||||
* Description:
|
||||
* Optionally provided function called on entry to board_system_reset
|
||||
* It should perform any house keeping prior to the rest.
|
||||
*
|
||||
* status - 1 if resetting to boot loader
|
||||
* 0 if just resetting
|
||||
*
|
||||
************************************************************************************/
|
||||
__EXPORT void board_on_reset(int status)
|
||||
{
|
||||
/* configure the GPIO pins to outputs and keep them low */
|
||||
/*for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) {
|
||||
px4_arch_configgpio(io_timer_channel_get_gpio_output(i));
|
||||
}*/
|
||||
|
||||
/* On resets invoked from system (not boot) insure we establish a low
|
||||
* output state (discharge the pins) on PWM pins before they become inputs.
|
||||
*/
|
||||
|
||||
if (status >= 0) {
|
||||
up_mdelay(400);
|
||||
}
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
|
@ -156,6 +95,12 @@ __EXPORT void board_on_reset(int status)
|
|||
__EXPORT void
|
||||
stm32_boardinitialize(void)
|
||||
{
|
||||
watchdog_init();
|
||||
|
||||
|
||||
/* configure LEDs */
|
||||
|
||||
board_autoled_initialize();
|
||||
|
||||
/* configure pins */
|
||||
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
|
||||
|
@ -163,7 +108,9 @@ stm32_boardinitialize(void)
|
|||
|
||||
/* configure SPI all interfaces GPIO */
|
||||
|
||||
stm32_spiinitialize();
|
||||
/* configure USB interfaces */
|
||||
|
||||
stm32_usbinitialize();
|
||||
|
||||
}
|
||||
|
||||
|
@ -192,20 +139,12 @@ stm32_boardinitialize(void)
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
static struct spi_dev_s *spi1;
|
||||
static struct spi_dev_s *spi2;
|
||||
static struct spi_dev_s *spi3;
|
||||
|
||||
__EXPORT int board_app_initialize(uintptr_t arg)
|
||||
{
|
||||
px4_platform_init();
|
||||
|
||||
/* configure the DMA allocator */
|
||||
|
||||
if (board_dma_alloc_init() < 0) {
|
||||
syslog(LOG_ERR, "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. */
|
||||
|
@ -214,63 +153,36 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
|||
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_BLUE);
|
||||
/* configure the DMA allocator */
|
||||
|
||||
/*if (board_hardfault_init(2, true) != 0) {
|
||||
led_on(LED_BLUE);
|
||||
}*/
|
||||
|
||||
/* Configure SPI-based devices */
|
||||
|
||||
spi1 = stm32_spibus_initialize(1);
|
||||
|
||||
if (!spi1) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 1\n");
|
||||
led_on(LED_BLUE);
|
||||
return -ENODEV;
|
||||
if (board_dma_alloc_init() < 0) {
|
||||
syslog(LOG_ERR, "DMA alloc FAILED\n");
|
||||
}
|
||||
|
||||
/* SPI1: ICM20602 IMU */
|
||||
|
||||
SPI_SETFREQUENCY(spi1, 10000000);
|
||||
SPI_SETBITS(spi1, 8);
|
||||
SPI_SETMODE(spi1, SPIDEV_MODE3);
|
||||
up_udelay(20);
|
||||
|
||||
/* SPI2: RM3100 Magnetometer */
|
||||
|
||||
spi2 = stm32_spibus_initialize(2);
|
||||
|
||||
if (!spi2) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", 2);
|
||||
led_on(LED_BLUE);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
up_udelay(20);
|
||||
stm32_spiinitialize();
|
||||
|
||||
|
||||
/* SPI3: SD card */
|
||||
|
||||
spi3 = stm32_spibus_initialize(3);
|
||||
spi3 = stm32_spibus_initialize(CONFIG_NSH_MMCSDSPIPORTNO);
|
||||
|
||||
if (!spi3) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 3\n");
|
||||
led_on(LED_BLUE);
|
||||
rgb_led(255, 0, 0, 0);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
SPI_SETFREQUENCY(spi3, 10 * 1000 * 1000);
|
||||
SPI_SETBITS(spi3, 8);
|
||||
SPI_SETMODE(spi3, SPIDEV_MODE3);
|
||||
up_udelay(20);
|
||||
int ret = mmcsd_spislotinitialize(CONFIG_NSH_MMCSDMINOR, CONFIG_NSH_MMCSDSLOTNO, spi3);
|
||||
|
||||
if (ret < 0) {
|
||||
syslog(LOG_ERR, "[boot] Failed to bind SPI port 0 to SD slot 0\n");
|
||||
rgb_led(255, 0, 0, 0);
|
||||
return ret;
|
||||
}
|
||||
|
||||
#if defined(FLASH_BASED_PARAMS)
|
||||
static sector_descriptor_t params_sector_map[] = {
|
||||
{1, 16 * 1024, 0x08008000},
|
||||
{2, 16 * 1024, 0x0800C000},
|
||||
{2, 16 * 1024, 0x08008000},
|
||||
{3, 16 * 1024, 0x0800C000},
|
||||
{0, 0, 0},
|
||||
};
|
||||
|
||||
|
@ -279,15 +191,13 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
|||
|
||||
if (result != OK) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
|
||||
led_on(LED_AMBER);
|
||||
rgb_led(255, 0, 0, 0);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif // FLASH_BASED_PARAMS
|
||||
|
||||
/* Configure the HW based on the manifest */
|
||||
|
||||
px4_platform_configure();
|
||||
rgb_led(0, 255, 0, 0);
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
|
|
@ -37,11 +37,14 @@
|
|||
|
||||
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortA, GPIO::Pin4}),
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortA, GPIO::Pin4}, SPI::DRDY{GPIO::PortC, GPIO::Pin4}),
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI2, {
|
||||
initSPIDevice(DRV_MAG_DEVTYPE_RM3100, SPI::CS{GPIO::PortB, GPIO::Pin12})
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI3, {
|
||||
initSPIDevice(DRV_DEVTYPE_UNUSED, SPI::CS{GPIO::PortC, GPIO::Pin14})
|
||||
}),
|
||||
};
|
||||
|
||||
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
|
||||
|
|
|
@ -6,8 +6,8 @@ add_definitions(
|
|||
-DAPP_VERSION_MINOR=${uavcanblid_sw_version_minor}
|
||||
)
|
||||
|
||||
set(uavcanblid_hw_version_major 0)
|
||||
set(uavcanblid_hw_version_minor 140)
|
||||
set(uavcanblid_hw_version_major 3)
|
||||
set(uavcanblid_hw_version_minor 246)
|
||||
set(uavcanblid_name "\"org.matek.gnss-m9n-f4\"")
|
||||
|
||||
add_definitions(
|
||||
|
|
|
@ -99,6 +99,10 @@ int board_mcu_version(char *rev, const char **revstr, const char **errata)
|
|||
*revstr = "STM32F76xxx";
|
||||
break;
|
||||
|
||||
case STM32F40x_41x:
|
||||
*revstr = "STM32F40x";
|
||||
break;
|
||||
|
||||
case STM32F42x_43x:
|
||||
*revstr = "STM32F42x";
|
||||
/* Set possible errata */
|
||||
|
|
Loading…
Reference in New Issue