Browse Source
Signed-off-by: dirksavage88 <dirksavage88@gmail.com> Added uavcan board identity Signed-off-by: dirksavage88 <dirksavage88@gmail.com> Added usb.c, LED rework may be needed Signed-off-by: dirksavage88 <dirksavage88@gmail.com> PX4 dates added to all files Signed-off-by: dirksavage88 <dirksavage88@gmail.com> Matek M9NF4 CAN Node initial board support Signed-off-by: dirksavage88 <dirksavage88@gmail.com> Changed GPS to ttyS3 in board sensors, led board on/off definitions Signed-off-by: dirksavage88 <dirksavage88@gmail.com> Added app descriptor section to canbootloader linker script Signed-off-by: dirksavage88 <dirksavage88@gmail.com> Changed board naming convention to match vendor Signed-off-by: dirksavage88 <dirksavage88@gmail.com> Changed canbootloader and nsh menuconfig Signed-off-by: dirksavage88 <dirksavage88@gmail.com> Test defconfig changes, IRQ hardfault in bootloader Signed-off-by: dirksavage88 <dirksavage88@gmail.com> Working canbootloader, App firmware stil WIP Working App firmware: changed romfsroot to 'cannode', TODO: verify GPS & IMU config Signed-off-by: dirksavage88 <dirksavage88@gmail.com> TODO: Debug GPS no sats/low sats issue, no magnetometer on some boards Signed-off-by: dirksavage88 <dirksavage88@gmail.com>master
27 changed files with 2518 additions and 0 deletions
@ -0,0 +1,7 @@
@@ -0,0 +1,7 @@
|
||||
CONFIG_PLATFORM_NUTTX=y |
||||
CONFIG_BOARD_PLATFORM="nuttx" |
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" |
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m4" |
||||
CONFIG_BOARD_ROMFSROOT="" |
||||
CONFIG_BOARD_CONSTRAINED_MEMORY=y |
||||
CONFIG_DRIVERS_BOOTLOADERS=y |
@ -0,0 +1,18 @@
@@ -0,0 +1,18 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" |
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m4" |
||||
CONFIG_BOARD_ROMFSROOT="cannode" |
||||
CONFIG_BOARD_CONSTRAINED_MEMORY=y |
||||
CONFIG_DRIVERS_BAROMETER_DPS310=y |
||||
CONFIG_DRIVERS_BOOTLOADERS=y |
||||
CONFIG_DRIVERS_GPS=y |
||||
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_SYSTEMCMDS_NSHTERM=y |
||||
CONFIG_SYSTEMCMDS_PARAM=y |
||||
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y |
||||
CONFIG_SYSTEMCMDS_USB_CONNECTED=y |
||||
CONFIG_SYSTEMCMDS_VER=y |
@ -0,0 +1,13 @@
@@ -0,0 +1,13 @@
|
||||
{ |
||||
"board_id": 140, |
||||
"magic": "PX4FWv1", |
||||
"description": "Firmware for the MatekM9nf4can cannode board", |
||||
"image": "", |
||||
"build_time": 0, |
||||
"summary": "MateksysGnss-m9n-f4", |
||||
"version": "0.1", |
||||
"image_size": 0, |
||||
"image_maxsize": 1032192, |
||||
"git_identity": "", |
||||
"board_revision": 0 |
||||
} |
@ -0,0 +1,12 @@
@@ -0,0 +1,12 @@
|
||||
#!/bin/sh |
||||
# |
||||
# Matek M9NF4 CAN specific board sensors init |
||||
#------------------------------------------------------------------------------ |
||||
|
||||
gps start -d /dev/ttyS2 |
||||
|
||||
icm20602 -s start |
||||
|
||||
rm3100 -b 2 -s start |
||||
|
||||
dps310 -a 118 -X start |
@ -0,0 +1,72 @@
@@ -0,0 +1,72 @@
|
||||
# |
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT. |
||||
# |
||||
# You can use "make menuconfig" to make any modifications to the installed .config file. |
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your |
||||
# modifications. |
||||
# |
||||
CONFIG_ARCH="arm" |
||||
CONFIG_ARCH_BOARD_CUSTOM=y |
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/matek/gnss-m9n-f4/nuttx-config" |
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y |
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" |
||||
CONFIG_ARCH_CHIP="stm32" |
||||
CONFIG_ARCH_CHIP_STM32=y |
||||
CONFIG_ARCH_CHIP_STM32F405RG=y |
||||
CONFIG_ARCH_INTERRUPTSTACK=4096 |
||||
CONFIG_ARMV7M_MEMCPY=y |
||||
CONFIG_ARMV7M_USEBASEPRI=y |
||||
CONFIG_BINFMT_DISABLE=y |
||||
CONFIG_BOARD_LOOPSPERMSEC=16717 |
||||
CONFIG_C99_BOOL8=y |
||||
CONFIG_CLOCK_MONOTONIC=y |
||||
CONFIG_DEBUG_FULLOPT=y |
||||
CONFIG_DEBUG_SYMBOLS=y |
||||
CONFIG_DEFAULT_SMALL=y |
||||
CONFIG_DISABLE_MOUNTPOINT=y |
||||
CONFIG_DISABLE_MQUEUE=y |
||||
CONFIG_DISABLE_PTHREAD=y |
||||
CONFIG_EXPERIMENTAL=y |
||||
CONFIG_FDCLONE_DISABLE=y |
||||
CONFIG_FDCLONE_STDIO=y |
||||
CONFIG_HAVE_CXX=y |
||||
CONFIG_HAVE_CXXINITIALIZE=y |
||||
CONFIG_IDLETHREAD_STACKSIZE=4096 |
||||
CONFIG_LIBC_FLOATINGPOINT=y |
||||
CONFIG_LIBC_LONG_LONG=y |
||||
CONFIG_LIBC_STRERROR=y |
||||
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 |
||||
CONFIG_RAM_START=0x20010000 |
||||
CONFIG_RAW_BINARY=y |
||||
CONFIG_SDCLONE_DISABLE=y |
||||
CONFIG_SIG_DEFAULT=y |
||||
CONFIG_SIG_SIGALRM_ACTION=y |
||||
CONFIG_SIG_SIGUSR1_ACTION=y |
||||
CONFIG_SIG_SIGUSR2_ACTION=y |
||||
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_NOEXT_VECTORS=y |
||||
CONFIG_STM32_TIM8=y |
||||
CONFIG_TASK_NAME_SIZE=0 |
||||
CONFIG_USBDEV=y |
||||
CONFIG_USBDEV_BUSPOWERED=y |
||||
CONFIG_USBDEV_MAXPOWER=500 |
||||
CONFIG_USEC_PER_TICK=1000 |
||||
CONFIG_USERMAIN_STACKSIZE=2944 |
@ -0,0 +1,327 @@
@@ -0,0 +1,327 @@
|
||||
/************************************************************************************
|
||||
* include/arch/board/board.h |
||||
* |
||||
* Copyright (C) 2012 Gregory Nutt. All rights reserved. |
||||
* Author: Gregory Nutt <gnutt@nuttx.org> |
||||
* |
||||
* Copyright (c) 2018 PX4 Development Team. All rights reserved. |
||||
* Author: Nathan Tsoi <nathan@vertile.com> |
||||
* |
||||
* 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. |
||||
* |
||||
************************************************************************************/ |
||||
#include "board_dma_map.h" |
||||
|
||||
#ifndef __ARCH_BOARD_BOARD_H |
||||
#define __ARCH_BOARD_BOARD_H |
||||
|
||||
#include <nuttx/config.h> |
||||
#ifndef __ASSEMBLY__ |
||||
# include <stdint.h> |
||||
#endif |
||||
|
||||
#include <stm32.h> |
||||
|
||||
/************************************************************************************
|
||||
* Definitions |
||||
************************************************************************************/ |
||||
|
||||
/* Clocking *************************************************************************/ |
||||
/* The Mateksys GNSS M9N-F4 board features a single 8MHz crystal.
|
||||
* |
||||
* This is the canonical configuration: |
||||
* System Clock source : PLL (HSE) |
||||
* SYSCLK(Hz) : 168000000 Determined by PLL configuration |
||||
* HCLK(Hz) : 168000000 (STM32_RCC_CFGR_HPRE) |
||||
* AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE) |
||||
* APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1) |
||||
* APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2) |
||||
* HSE Frequency(Hz) : 8000000 (STM32_BOARD_XTAL) |
||||
* PLLM : 8 (STM32_PLLCFG_PLLM) |
||||
* PLLN : 336 (STM32_PLLCFG_PLLN) |
||||
* PLLP : 2 (STM32_PLLCFG_PLLP) |
||||
* PLLQ : 7 (STM32_PLLCFG_PLLQ) |
||||
* Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK |
||||
* Flash Latency(WS) : 5 |
||||
* Prefetch Buffer : OFF |
||||
* Instruction cache : ON |
||||
* Data cache : ON |
||||
* Require 48MHz for USB OTG FS, : Enabled |
||||
* SDIO and RNG clock |
||||
*/ |
||||
|
||||
/* HSI - 16 MHz RC factory-trimmed
|
||||
* LSI - 32 KHz RC |
||||
* HSE - On-board crystal frequency is 8MHz |
||||
* LSE - 32.768 kHz |
||||
*/ |
||||
|
||||
#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 |
||||
|
||||
/* Main PLL Configuration.
|
||||
* |
||||
* PLL source is HSE |
||||
* PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN |
||||
* = (8,000,000 / 8) * 336 |
||||
* = 336,000,000 |
||||
* SYSCLK = PLL_VCO / PLLP |
||||
* = 336,000,000 / 2 = 168,000,000 |
||||
* USB OTG FS, SDIO and RNG Clock |
||||
* = PLL_VCO / PLLQ |
||||
* = 48,000,000 |
||||
*/ |
||||
|
||||
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8) |
||||
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336) |
||||
#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2 |
||||
#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(7) |
||||
|
||||
#define STM32_SYSCLK_FREQUENCY 168000000ul |
||||
|
||||
/* AHB clock (HCLK) is SYSCLK (168MHz) */ |
||||
|
||||
#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 (42MHz) */ |
||||
|
||||
#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) |
||||
#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
|
||||
/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */ |
||||
|
||||
#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) |
||||
#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY) |
||||
#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY) |
||||
|
||||
/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx
|
||||
* otherwise frequency is 2xAPBx. |
||||
* Note: TIM1,8-11 are on APB2, others on APB1 |
||||
*/ |
||||
|
||||
#define BOARD_TIM1_FREQUENCY STM32_APB2_TIM1_CLKIN |
||||
#define BOARD_TIM2_FREQUENCY STM32_APB1_TIM2_CLKIN |
||||
#define BOARD_TIM3_FREQUENCY STM32_APB1_TIM3_CLKIN |
||||
#define BOARD_TIM4_FREQUENCY STM32_APB1_TIM4_CLKIN |
||||
#define BOARD_TIM5_FREQUENCY STM32_APB1_TIM5_CLKIN |
||||
#define BOARD_TIM6_FREQUENCY STM32_APB1_TIM6_CLKIN |
||||
#define BOARD_TIM7_FREQUENCY STM32_APB1_TIM7_CLKIN |
||||
#define BOARD_TIM8_FREQUENCY STM32_APB2_TIM8_CLKIN |
||||
#define BOARD_TIM9_FREQUENCY STM32_APB2_TIM9_CLKIN |
||||
#define BOARD_TIM10_FREQUENCY STM32_APB2_TIM10_CLKIN |
||||
#define BOARD_TIM11_FREQUENCY STM32_APB2_TIM11_CLKIN |
||||
#define BOARD_TIM12_FREQUENCY STM32_APB1_TIM12_CLKIN |
||||
#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. |
||||
*/ |
||||
|
||||
/* LED index values for use with stm32_setled() */ |
||||
|
||||
#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 stm32_setleds() */ |
||||
|
||||
#define BOARD_LED1_BIT (1 << BOARD_LED1) |
||||
#define BOARD_LED2_BIT (1 << BOARD_LED2) |
||||
|
||||
/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 2 LEDs on board
|
||||
* The following definitions describe how NuttX controls the LEDs: |
||||
*/ |
||||
|
||||
#define LED_STARTED 0 /* LED1 */ |
||||
#define LED_HEAPALLOCATE 1 /* LED2 */ |
||||
#define LED_IRQSENABLED 2 /* LED1 */ |
||||
#define LED_STACKCREATED 3 /* LED1 + LED2 */ |
||||
#define LED_INIRQ 4 /* LED1 */ |
||||
#define LED_SIGNAL 5 /* LED2 */ |
||||
#define LED_ASSERTION 6 /* LED1 + LED2 */ |
||||
#define LED_PANIC 7 /* LED1 + LED2 */ |
||||
|
||||
/* Alternate function pin selections ************************************************/ |
||||
|
||||
/* UART1:
|
||||
* |
||||
* PA10 (RX) and PA9 (TX) are broken out on J5 |
||||
*/ |
||||
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_1 |
||||
#define GPIO_USART1_TX GPIO_USART1_TX_1 |
||||
|
||||
/* UART2:
|
||||
* |
||||
* PA10 (RX) and PA9 (TX) are broken out on J5 |
||||
*/ |
||||
|
||||
//#define GPIO_USART2_RX GPIO_USART2_RX_1
|
||||
//#define GPIO_USART2_TX GPIO_USART2_TX_1
|
||||
|
||||
/* USART3:
|
||||
* |
||||
* PC10 (TX) and PC11 (RX) are broken out on J4 |
||||
* |
||||
* |
||||
* The Silkscreen pin labeled SCL is TX |
||||
* MISO is RX |
||||
*/ |
||||
#define GPIO_USART3_RX GPIO_USART3_RX_2 |
||||
#define GPIO_USART3_TX GPIO_USART3_TX_2 |
||||
|
||||
/* UART4:
|
||||
* |
||||
* PA0 (TX) -- Labeled RSSI on the silkscreen is only broken out on a test pad |
||||
* on the pro version. It's on a 2.54mm header on other versions |
||||
* PA1 (RX) -- Motor 5 out |
||||
*/ |
||||
#define GPIO_UART4_RX GPIO_UART4_RX_1 |
||||
#define GPIO_UART4_TX GPIO_UART4_TX_1 |
||||
|
||||
/* UART5:
|
||||
* |
||||
* PC6 (TX) and PC7 (RX) are broken out on J10 |
||||
*/ |
||||
|
||||
//#define GPIO_UART5_RX GPIO_UART5_RX_1
|
||||
//#define GPIO_UART5_TX GPIO_UART5_TX_1
|
||||
|
||||
/* CAN */ |
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_2 |
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_2 |
||||
|
||||
/* SPI1:
|
||||
* CS: PA4 -- configured in board_config.h |
||||
* CLK: PA5 |
||||
* MISO: PA6 |
||||
* MOSI: PA7 |
||||
*/ |
||||
|
||||
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 |
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 |
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 |
||||
|
||||
/* SPI2:
|
||||
* SD Card |
||||
* CS: PB12 -- configured in board_config.h |
||||
* CLK: PB13 |
||||
* MISO: PB14 |
||||
* MOSI: PB15 |
||||
*/ |
||||
|
||||
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2 |
||||
#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 |
||||
*/ |
||||
|
||||
#define GPIO_SPI3_SCK GPIO_SPI3_SCK_2 |
||||
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 |
||||
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_2 |
||||
|
||||
/*
|
||||
* I2C (external) |
||||
* |
||||
* SCL: PB10 |
||||
* SDA: PB11 |
||||
* |
||||
* TODO: |
||||
* 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_I2C2_SCL GPIO_I2C2_SCL_1 |
||||
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 |
||||
|
||||
#endif /* __CONFIG_M9NF4_INCLUDE_BOARD_H */ |
@ -0,0 +1,79 @@
@@ -0,0 +1,79 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* 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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#pragma once |
||||
|
||||
/*
|
||||
| DMA1 | Stream 0 | Stream 1 | Stream 2 | Stream 3 | Stream 4 | Stream 5 | Stream 6 | Stream 7 | |
||||
|------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------| |
||||
| Channel 0 | SPI3_RX_1 | - | SPI3_RX_2 | SPI2_RX | SPI2_TX | SPI3_TX_1 | - | SPI3_TX_2 | |
||||
| Channel 1 | I2C1_RX | - | TIM7_UP_1 | - | TIM7_UP_2 | I2C1_RX_1 | I2C1_TX | I2C1_TX_1 | |
||||
| Channel 2 | TIM4_CH1 | - | I2C4_RX | TIM4_CH2 | - | I2C4_RX | TIM4_UP | TIM4_CH3 | |
||||
| Channel 3 | - | TIM2_UP_1 | I2C3_RX_1 | I2C2_EXT_RX | I2C3_TX | TIM2_CH1 | TIM2_CH2 | TIM2_UP_2 | |
||||
| | | TIM2_CH3 | | | | | TIM2_CH4_1 | TIM2_CH4_2 | |
||||
| Channel 4 | UART5_RX | USART3_RX | UART4_RX | USART3_TX_1 | UART4_TX | USART2_RX | USART2_TX | UART5_TX | |
||||
| Channel 5 | UART8_TX | UART7_TX | TIM3_CH4 | UART7_RX | TIM3_CH1 | TIM3_CH2 | UART8_RX | TIM3_CH3 | |
||||
| | | | TIM3_UP | | TIM3_TRIG | | | | |
||||
| Channel 6 | TIM5_CH3 | TIM5_CH4_1 | TIM5_CH1 | TIM5_CH4_2 | TIM5_CH2 | - | TIM5_UP_2 | - | |
||||
| | 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 | | | | |
||||
|
||||
|
||||
| DMA2 | Stream 0 | Stream 1 | Stream 2 | Stream 3 | Stream 4 | Stream 5 | Stream 6 | Stream 7 | |
||||
|------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------| |
||||
| Channel 0 | ADC1_1 | SAI1_A | TIM8_CH1_1 | SAI1_A_1 | ADC1_2 | SAI1_B_1 | TIM1_CH1_1 | - | |
||||
| | | | TIM8_CH2_1 | | | | TIM1_CH2_1 | | |
||||
| | | | TIM8_CH3_1 | | | | TIM1_CH3_1 | | |
||||
| Channel 1 | - | DCMI_1 | ADC2_1 | ADC2_2 | SAI1_B | SPI6_TX | SPI6_RX | DCMI_2 | |
||||
| Channel 2 | ADC3_1 | ADC3_2 | - | SPI5_RX_1 | SPI5_TX_1 | CRYP_OUT | CRYP_IN | HASH_IN | |
||||
| Channel 3 | SPI1_RX_1 | - | SPI1_RX_2 | SPI1_TX_1 | - | SPI1_TX_2 | - | QUADSPI | |
||||
| Channel 4 | SPI4_RX_1 | SPI4_TX_1 | USART1_RX_1 | SDIO | - | USART1_RX_2 | SDIO | USART1_TX | |
||||
| Channel 5 | - | USART6_RX_1 | USART6_RX_2 | SPI4_RX_2 | SPI4_TX_2 | - | USART6_TX_1 | USART6_TX_2 | |
||||
| Channel 6 | TIM1_TRIG_1 | TIM1_CH1_2 | TIM1_CH2_2 | TIM1_CH1 | TIM1_CH4 | TIM1_UP | TIM1_CH3_2 | - | |
||||
| | | | | | TIM1_TRIG_2 | | | | |
||||
| | | | | | TIM1_COM | | | | |
||||
| Channel 7 | - | TIM8_UP | TIM8_CH1_2 | TIM8_CH2_2 | TIM8_CH3_2 | SPI5_RX_2 | SPI5_TX_2 | TIM8_CH4 | |
||||
| | | | | | | | | TIM8_TRIG | |
||||
| | | | | | | | | TIM8_COM | |
||||
| | | | | | | | | | |
||||
| Usage | SPI1_RX_1 | USART6_RX_1 | USART1_RX_1 | SPI1_TX_1 | | | SDIO | | |
||||
*/ |
||||
|
||||
// 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 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)
|
@ -0,0 +1,186 @@
@@ -0,0 +1,186 @@
|
||||
# |
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT. |
||||
# |
||||
# You can use "make menuconfig" to make any modifications to the installed .config file. |
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your |
||||
# modifications. |
||||
# |
||||
# CONFIG_DISABLE_OS_API is not set |
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set |
||||
# CONFIG_MMCSD_HAVE_CARDDETECT is not set |
||||
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set |
||||
# CONFIG_MMCSD_MMCSUPPORT is not set |
||||
# CONFIG_NSH_DISABLEBG is not set |
||||
# CONFIG_NSH_DISABLESCRIPT is not set |
||||
# CONFIG_NSH_DISABLE_CMP is not set |
||||
# CONFIG_NSH_DISABLE_DF is not set |
||||
# CONFIG_NSH_DISABLE_EXEC is not set |
||||
# CONFIG_NSH_DISABLE_EXIT is not set |
||||
# CONFIG_NSH_DISABLE_GET is not set |
||||
# CONFIG_NSH_DISABLE_ITEF is not set |
||||
# CONFIG_NSH_DISABLE_LOOPS is not set |
||||
# CONFIG_NSH_DISABLE_MKFATFS is not set |
||||
# CONFIG_NSH_DISABLE_SEMICOLON is not set |
||||
# CONFIG_NSH_DISABLE_TIME is not set |
||||
# CONFIG_SPI_CALLBACK is not set |
||||
# CONFIG_STM32_CCMEXCLUDE is not set |
||||
# CONFIG_STM32_DMACAPABLE is not set |
||||
CONFIG_ARCH="arm" |
||||
CONFIG_ARCH_BOARD_CUSTOM=y |
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/matek/gnss-m9n-f4/nuttx-config" |
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y |
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" |
||||
CONFIG_ARCH_CHIP="stm32" |
||||
CONFIG_ARCH_CHIP_STM32=y |
||||
CONFIG_ARCH_CHIP_STM32F405RG=y |
||||
CONFIG_ARCH_INTERRUPTSTACK=512 |
||||
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 |
||||
CONFIG_C99_BOOL8=y |
||||
CONFIG_CDCACM=y |
||||
CONFIG_CDCACM_BULKIN_REQLEN=96 |
||||
CONFIG_CDCACM_PRODUCTID=0x1004 |
||||
CONFIG_CDCACM_PRODUCTSTR="Matekgnssm9nf4" |
||||
CONFIG_CDCACM_RXBUFSIZE=600 |
||||
CONFIG_CDCACM_TXBUFSIZE=2000 |
||||
CONFIG_CDCACM_VENDORID=0x120A |
||||
CONFIG_CDCACM_VENDORSTR="PX4" |
||||
CONFIG_CLOCK_MONOTONIC=y |
||||
CONFIG_DEBUG_FULLOPT=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_FAT_DMAMEMORY=y |
||||
CONFIG_FAT_LCNAMES=y |
||||
CONFIG_FAT_LFN=y |
||||
CONFIG_FDCLONE_STDIO=y |
||||
CONFIG_FS_BINFS=y |
||||
CONFIG_FS_CROMFS=y |
||||
CONFIG_FS_FAT=y |
||||
CONFIG_FS_FATTIME=y |
||||
CONFIG_FS_PROCFS=y |
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y |
||||
CONFIG_FS_PROCFS_REGISTER=y |
||||
CONFIG_FS_ROMFS=y |
||||
CONFIG_GRAN=y |
||||
CONFIG_GRAN_INTR=y |
||||
CONFIG_HAVE_CXX=y |
||||
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 |
||||
CONFIG_MEMSET_OPTSPEED=y |
||||
CONFIG_MMCSD=y |
||||
CONFIG_MM_REGIONS=2 |
||||
CONFIG_MTD=y |
||||
CONFIG_MTD_BYTE_WRITE=y |
||||
CONFIG_MTD_PARTITION=y |
||||
CONFIG_MTD_RAMTRON=y |
||||
CONFIG_NAME_MAX=40 |
||||
CONFIG_NSH_ARCHINIT=y |
||||
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_MMCSDSPIPORTNO=2 |
||||
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_PIPES=y |
||||
CONFIG_PREALLOC_TIMERS=50 |
||||
CONFIG_PRIORITY_INHERITANCE=y |
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y |
||||
CONFIG_PTHREAD_STACK_MIN=512 |
||||
CONFIG_RAMTRON_SETSPEED=y |
||||
CONFIG_RAM_SIZE=131072 |
||||
CONFIG_RAM_START=0x20000000 |
||||
CONFIG_RAW_BINARY=y |
||||
CONFIG_RTC_DATETIME=y |
||||
CONFIG_SCHED_ATEXIT=y |
||||
CONFIG_SCHED_HPWORK=y |
||||
CONFIG_SCHED_HPWORKPRIORITY=249 |
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280 |
||||
CONFIG_SCHED_INSTRUMENTATION=y |
||||
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y |
||||
CONFIG_SCHED_LPWORK=y |
||||
CONFIG_SCHED_LPWORKPRIORITY=50 |
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632 |
||||
CONFIG_SCHED_WAITPID=y |
||||
CONFIG_SEM_NNESTPRIO=8 |
||||
CONFIG_SEM_PREALLOCHOLDERS=0 |
||||
CONFIG_SERIAL_TERMIOS=y |
||||
CONFIG_SIG_DEFAULT=y |
||||
CONFIG_SIG_SIGALRM_ACTION=y |
||||
CONFIG_SIG_SIGUSR1_ACTION=y |
||||
CONFIG_SIG_SIGUSR2_ACTION=y |
||||
CONFIG_SIG_SIGWORK=4 |
||||
CONFIG_STACK_COLORATION=y |
||||
CONFIG_START_DAY=30 |
||||
CONFIG_START_MONTH=11 |
||||
CONFIG_STDIO_BUFFER_SIZE=32 |
||||
CONFIG_STM32_ADC1=y |
||||
CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y |
||||
CONFIG_STM32_DMA1=y |
||||
CONFIG_STM32_DMA2=y |
||||
CONFIG_STM32_FLASH_PREFETCH=y |
||||
CONFIG_STM32_FLOWCONTROL_BROKEN=y |
||||
CONFIG_STM32_I2C2=y |
||||
CONFIG_STM32_JTAG_SW_ENABLE=y |
||||
CONFIG_STM32_OTGFS=y |
||||
CONFIG_STM32_OTGHS=y |
||||
CONFIG_STM32_PWR=y |
||||
CONFIG_STM32_RTC=y |
||||
CONFIG_STM32_RTC_HSECLOCK=y |
||||
CONFIG_STM32_RTC_MAGIC=0xfacefeee |
||||
CONFIG_STM32_RTC_MAGIC_REG=1 |
||||
CONFIG_STM32_RTC_MAGIC_TIME_SET=0xfacefeef |
||||
CONFIG_STM32_SERIALBRK_BSDCOMPAT=y |
||||
CONFIG_STM32_SERIAL_DISABLE_REORDERING=y |
||||
CONFIG_STM32_SPI1=y |
||||
CONFIG_STM32_SPI1_DMA=y |
||||
CONFIG_STM32_SPI1_DMA_BUFFER=1024 |
||||
CONFIG_STM32_SPI2=y |
||||
CONFIG_STM32_SPI_DMA=y |
||||
CONFIG_STM32_SPI_DMATHRESHOLD=1024 |
||||
CONFIG_STM32_TIM5=y |
||||
CONFIG_STM32_UART4=y |
||||
CONFIG_STM32_USART1=y |
||||
CONFIG_STM32_USART3=y |
||||
CONFIG_STM32_USART_BREAKS=y |
||||
CONFIG_STM32_WWDG=y |
||||
CONFIG_SYSTEM_CDCACM=y |
||||
CONFIG_SYSTEM_NSH=y |
||||
CONFIG_TASK_NAME_SIZE=24 |
||||
CONFIG_UART4_BAUD=38400 |
||||
CONFIG_UART4_RXBUFSIZE=300 |
||||
CONFIG_UART4_TXBUFSIZE=300 |
||||
CONFIG_USART1_RXBUFSIZE=300 |
||||
CONFIG_USART1_SERIAL_CONSOLE=y |
||||
CONFIG_USART1_TXBUFSIZE=300 |
||||
CONFIG_USBDEV=y |
||||
CONFIG_USBDEV_BUSPOWERED=y |
||||
CONFIG_USBDEV_DUALSPEED=y |
||||
CONFIG_USBDEV_MAXPOWER=500 |
||||
CONFIG_USEC_PER_TICK=1000 |
||||
CONFIG_USERMAIN_STACKSIZE=2944 |
||||
CONFIG_USER_ENTRYPOINT="nsh_main" |
@ -0,0 +1,138 @@
@@ -0,0 +1,138 @@
|
||||
/**************************************************************************** |
||||
* configs/gnss-m9n-f4/scripts/ld.canbootloader |
||||
* |
||||
* Copyright (C) 2011 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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/* The STM32F405RG has 1024Kb of FLASH beginning at address 0x0800:0000 and |
||||
* 192Kb of SRAM. SRAM is split up into three blocks: |
||||
* |
||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000 |
||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000 |
||||
* 3) 64Kb of CCM SRAM beginning at address 0x1000:0000 |
||||
* |
||||
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 |
||||
* where the code expects to begin execution by jumping to the entry point in |
||||
* the 0x0800:0000 address range. |
||||
* |
||||
* The first 32 KiB of flash is reserved for the bootloader. |
||||
* Paramater storage will use the next 32KiB Sector. |
||||
*/ |
||||
|
||||
MEMORY |
||||
{ |
||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 32K |
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K |
||||
ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K |
||||
} |
||||
|
||||
OUTPUT_ARCH(arm) |
||||
|
||||
ENTRY(__start) /* treat __start as the anchor for dead code stripping */ |
||||
EXTERN(_vectors) /* force the vectors to be included in the output */ |
||||
|
||||
/* |
||||
* Ensure that abort() is present in the final object. The exception handling |
||||
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided). |
||||
*/ |
||||
EXTERN(abort) |
||||
|
||||
SECTIONS |
||||
{ |
||||
.text : { |
||||
_stext = ABSOLUTE(.); |
||||
*(.vectors) |
||||
*(.text .text.*) |
||||
*(.fixup) |
||||
*(.gnu.warning) |
||||
*(.rodata .rodata.*) |
||||
*(.gnu.linkonce.t.*) |
||||
*(.got) |
||||
*(.gcc_except_table) |
||||
*(.gnu.linkonce.r.*) |
||||
_etext = ABSOLUTE(.); |
||||
|
||||
} > flash |
||||
|
||||
/* |
||||
* Init functions (static constructors and the like) |
||||
*/ |
||||
.init_section : { |
||||
_sinit = ABSOLUTE(.); |
||||
KEEP(*(.init_array .init_array.*)) |
||||
_einit = ABSOLUTE(.); |
||||
} > flash |
||||
|
||||
|
||||
.ARM.extab : { |
||||
*(.ARM.extab*) |
||||
} > flash |
||||
|
||||
__exidx_start = ABSOLUTE(.); |
||||
.ARM.exidx : { |
||||
*(.ARM.exidx*) |
||||
} > flash |
||||
__exidx_end = ABSOLUTE(.); |
||||
|
||||
_eronly = ABSOLUTE(.); |
||||
|
||||
.data : { |
||||
_sdata = ABSOLUTE(.); |
||||
*(.data .data.*) |
||||
*(.gnu.linkonce.d.*) |
||||
CONSTRUCTORS |
||||
_edata = ABSOLUTE(.); |
||||
} > sram AT > flash |
||||
|
||||
.bss : { |
||||
_sbss = ABSOLUTE(.); |
||||
*(.bss .bss.*) |
||||
*(.gnu.linkonce.b.*) |
||||
*(COMMON) |
||||
. = ALIGN(4); |
||||
_ebss = ABSOLUTE(.); |
||||
} > sram |
||||
|
||||
/* Stabs debugging sections. */ |
||||
.stab 0 : { *(.stab) } |
||||
.stabstr 0 : { *(.stabstr) } |
||||
.stab.excl 0 : { *(.stab.excl) } |
||||
.stab.exclstr 0 : { *(.stab.exclstr) } |
||||
.stab.index 0 : { *(.stab.index) } |
||||
.stab.indexstr 0 : { *(.stab.indexstr) } |
||||
.comment 0 : { *(.comment) } |
||||
.debug_abbrev 0 : { *(.debug_abbrev) } |
||||
.debug_info 0 : { *(.debug_info) } |
||||
.debug_line 0 : { *(.debug_line) } |
||||
.debug_pubnames 0 : { *(.debug_pubnames) } |
||||
.debug_aranges 0 : { *(.debug_aranges) } |
||||
} |
@ -0,0 +1,148 @@
@@ -0,0 +1,148 @@
|
||||
/**************************************************************************** |
||||
* configs/gnss-m9n-f4/scripts/ld.script |
||||
* |
||||
* Copyright (C) 2011 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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/* The STM32F405RG has 1024Kb of FLASH beginning at address 0x0800:0000 and |
||||
* 192Kb of SRAM. SRAM is split up into three blocks: |
||||
* |
||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000 |
||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000 |
||||
* 3) 64Kb of CCM SRAM beginning at address 0x1000:0000 |
||||
* |
||||
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 |
||||
* where the code expects to begin execution by jumping to the entry point in |
||||
* the 0x0800:0000 address range. |
||||
* |
||||
* The first 32 KiB of flash is reserved for the bootloader. |
||||
* Paramater storage will use the next 32KiB Sector. |
||||
*/ |
||||
|
||||
MEMORY |
||||
{ |
||||
flash (rx) : ORIGIN = 0x08010000, LENGTH = 960K |
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K |
||||
ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K |
||||
} |
||||
|
||||
OUTPUT_ARCH(arm) |
||||
|
||||
ENTRY(__start) /* treat __start as the anchor for dead code stripping */ |
||||
EXTERN(_vectors) /* force the vectors to be included in the output */ |
||||
|
||||
/* |
||||
* Ensure that abort() is present in the final object. The exception handling |
||||
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided). |
||||
*/ |
||||
EXTERN(abort) |
||||
EXTERN(_bootdelay_signature) |
||||
|
||||
SECTIONS |
||||
{ |
||||
.text : { |
||||
_stext = ABSOLUTE(.); |
||||
*(.vectors) |
||||
. = ALIGN(8); |
||||
/* |
||||
* This section positions the app_descriptor_t used |
||||
* by the make_can_boot_descriptor.py tool to set |
||||
* the application image's descriptor so that the |
||||
* uavcan bootloader has the ability to validate the |
||||
* image crc, size etc |
||||
*/ |
||||
KEEP(*(.app_descriptor)) |
||||
*(.text .text.*) |
||||
*(.fixup) |
||||
*(.gnu.warning) |
||||
*(.rodata .rodata.*) |
||||
*(.gnu.linkonce.t.*) |
||||
*(.got) |
||||
*(.gcc_except_table) |
||||
*(.gnu.linkonce.r.*) |
||||
_etext = ABSOLUTE(.); |
||||
|
||||
} > flash |
||||
|
||||
/* |
||||
* Init functions (static constructors and the like) |
||||
*/ |
||||
.init_section : { |
||||
_sinit = ABSOLUTE(.); |
||||
KEEP(*(.init_array .init_array.*)) |
||||
_einit = ABSOLUTE(.); |
||||
} > flash |
||||
|
||||
|
||||
.ARM.extab : { |
||||
*(.ARM.extab*) |
||||
} > flash |
||||
|
||||
__exidx_start = ABSOLUTE(.); |
||||
.ARM.exidx : { |
||||
*(.ARM.exidx*) |
||||
} > flash |
||||
__exidx_end = ABSOLUTE(.); |
||||
|
||||
_eronly = ABSOLUTE(.); |
||||
|
||||
.data : { |
||||
_sdata = ABSOLUTE(.); |
||||
*(.data .data.*) |
||||
*(.gnu.linkonce.d.*) |
||||
CONSTRUCTORS |
||||
_edata = ABSOLUTE(.); |
||||
} > sram AT > flash |
||||
|
||||
.bss : { |
||||
_sbss = ABSOLUTE(.); |
||||
*(.bss .bss.*) |
||||
*(.gnu.linkonce.b.*) |
||||
*(COMMON) |
||||
. = ALIGN(4); |
||||
_ebss = ABSOLUTE(.); |
||||
} > sram |
||||
|
||||
/* Stabs debugging sections. */ |
||||
.stab 0 : { *(.stab) } |
||||
.stabstr 0 : { *(.stabstr) } |
||||
.stab.excl 0 : { *(.stab.excl) } |
||||
.stab.exclstr 0 : { *(.stab.exclstr) } |
||||
.stab.index 0 : { *(.stab.index) } |
||||
.stab.indexstr 0 : { *(.stab.indexstr) } |
||||
.comment 0 : { *(.comment) } |
||||
.debug_abbrev 0 : { *(.debug_abbrev) } |
||||
.debug_info 0 : { *(.debug_info) } |
||||
.debug_line 0 : { *(.debug_line) } |
||||
.debug_pubnames 0 : { *(.debug_pubnames) } |
||||
.debug_aranges 0 : { *(.debug_aranges) } |
||||
} |
@ -0,0 +1,72 @@
@@ -0,0 +1,72 @@
|
||||
############################################################################ |
||||
# |
||||
# Copyright (c) 2018-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 |
||||
# POSSIBILITY OF SUCH DAMAGE. |
||||
# |
||||
############################################################################ |
||||
|
||||
if("${PX4_BOARD_LABEL}" STREQUAL "canbootloader") |
||||
|
||||
add_library(drivers_board |
||||
boot_config.h |
||||
boot.c |
||||
led.c |
||||
led.h |
||||
usb.c |
||||
) |
||||
target_link_libraries(drivers_board |
||||
PRIVATE |
||||
nuttx_arch |
||||
nuttx_drivers |
||||
canbootloader |
||||
) |
||||
target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/canbootloader) |
||||
|
||||
else() |
||||
add_library(drivers_board |
||||
i2c.cpp |
||||
init.c |
||||
spi.cpp |
||||
autoled.cpp |
||||
led.c |
||||
timer_config.cpp |
||||
usb.c |
||||
can.c |
||||
) |
||||
|
||||
target_link_libraries(drivers_board |
||||
PRIVATE |
||||
nuttx_arch |
||||
nuttx_drivers |
||||
px4_layer |
||||
arch_spi |
||||
arch_io_pins |
||||
drivers__led |
||||
) |
||||
endif() |
@ -0,0 +1,63 @@
@@ -0,0 +1,63 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* 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); |
||||
} |
||||
} |
@ -0,0 +1,157 @@
@@ -0,0 +1,157 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2014, 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 |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file board_config.h |
||||
* |
||||
* M9nf4 can internal definitions |
||||
*/ |
||||
|
||||
#pragma once |
||||
|
||||
/****************************************************************************************************
|
||||
* Included Files |
||||
****************************************************************************************************/ |
||||
|
||||
#include <px4_platform_common/px4_config.h> |
||||
#include <nuttx/compiler.h> |
||||
#include <stdint.h> |
||||
|
||||
/****************************************************************************************************
|
||||
* Definitions |
||||
****************************************************************************************************/ |
||||
/* Configuration ************************************************************************************/ |
||||
|
||||
/* Matek M9nf4can GPIOs ***********************************************************************************/ |
||||
/* LEDs */ |
||||
// LED1 - PA14 - blue
|
||||
// LED2 - PA13 - green
|
||||
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN14) |
||||
#define GPIO_LED_BLUE GPIO_LED1 |
||||
|
||||
#define GPIO_LED2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN13) |
||||
#define GPIO_LED_GREEN GPIO_LED2 |
||||
|
||||
/* Boot config */ |
||||
#define GPIO_BOOT_CONFIG /* PB7 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN7|GPIO_EXTI) |
||||
|
||||
#define FLASH_BASED_PARAMS |
||||
|
||||
#define GPIO_CAN1_SILENT_S0 /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) |
||||
|
||||
/* USB OTG FS
|
||||
* |
||||
* PA9 OTG_FS_VBUS VBUS sensing |
||||
*/ |
||||
#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)
|
||||
|
||||
/* High-resolution timer */ |
||||
#define HRT_TIMER 3 /* use timer 3 as HRT */ |
||||
#define HRT_TIMER_CHANNEL 4 /* use capture/compare channel 4 */ |
||||
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER |
||||
|
||||
#define PX4_GPIO_INIT_LIST { \ |
||||
GPIO_I2C1_SCL_RESET, \
|
||||
GPIO_I2C1_SDA_RESET, \
|
||||
GPIO_BOOT_CONFIG, \
|
||||
GPIO_CAN1_TX, \
|
||||
GPIO_CAN1_RX, \
|
||||
GPIO_CAN1_SILENT_S0, \
|
||||
GPIO_OTGFS_VBUS \
|
||||
} |
||||
|
||||
|
||||
__BEGIN_DECLS |
||||
|
||||
/****************************************************************************************************
|
||||
* Public Types |
||||
****************************************************************************************************/ |
||||
|
||||
/****************************************************************************************************
|
||||
* Public data |
||||
****************************************************************************************************/ |
||||
|
||||
#ifndef __ASSEMBLY__ |
||||
|
||||
/****************************************************************************************************
|
||||
* Public Functions |
||||
****************************************************************************************************/ |
||||
|
||||
/****************************************************************************************************
|
||||
* Name: stm32_spiinitialize |
||||
* |
||||
* Description: |
||||
* Called to configure SPI chip select GPIO pins for the PX4FMU board. |
||||
* |
||||
****************************************************************************************************/ |
||||
|
||||
extern void stm32_spiinitialize(void); |
||||
|
||||
|
||||
/****************************************************************************************************
|
||||
* Name: stm32_usbinitialize |
||||
* |
||||
* Description: |
||||
* Called to configure USB IO. |
||||
* |
||||
****************************************************************************************************/ |
||||
|
||||
extern void stm32_usbinitialize(void); |
||||
|
||||
//extern void board_peripheral_reset(int ms);
|
||||
|
||||
#include <px4_platform_common/board_common.h> |
||||
|
||||
#endif /* __ASSEMBLY__ */ |
||||
|
||||
__END_DECLS |
@ -0,0 +1,190 @@
@@ -0,0 +1,190 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2021 PX4 Development Team. All rights reserved. |
||||
* Author: Ben Dyer <ben_dyer@mac.com> |
||||
* Pavel Kirienko <pavel.kirienko@zubax.com> |
||||
* David Sidrane <david_s5@nscdg.com> |
||||
* |
||||
* 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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/****************************************************************************
|
||||
* Included Files |
||||
****************************************************************************/ |
||||
|
||||
#include <px4_config.h> |
||||
#include <stdint.h> |
||||
#include "boot_config.h" |
||||
#include "board.h" |
||||
|
||||
#include <debug.h> |
||||
#include <string.h> |
||||
#include <arch/board/board.h> |
||||
|
||||
#include "led.h" |
||||
#include <nuttx/board.h> |
||||
|
||||
|
||||
/************************************************************************************
|
||||
* 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. |
||||
* |
||||
************************************************************************************/ |
||||
|
||||
__EXPORT void stm32_boardinitialize(void) |
||||
{ |
||||
putreg32(getreg32(STM32_RCC_APB1ENR) | RCC_APB1ENR_CAN1EN, STM32_RCC_APB1ENR); |
||||
stm32_configgpio(GPIO_CAN1_RX); |
||||
stm32_configgpio(GPIO_CAN1_TX); |
||||
stm32_configgpio(GPIO_CAN1_SILENT_S0); |
||||
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR); |
||||
putreg32(getreg32(STM32_RCC_APB1RSTR) & ~RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR); |
||||
|
||||
//led_init();
|
||||
|
||||
#if defined(OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO) |
||||
stm32_configgpio(GPIO_GETNODEINFO_JUMPER); |
||||
#endif |
||||
|
||||
} |
||||
|
||||
/************************************************************************************
|
||||
* Name: board_deinitialize |
||||
* |
||||
* Description: |
||||
* This function is called by the bootloader code prior to booting |
||||
* the application. Is should place the HW into an benign initialized state. |
||||
* |
||||
************************************************************************************/ |
||||
|
||||
void board_deinitialize(void) |
||||
{ |
||||
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR); |
||||
} |
||||
|
||||
/****************************************************************************
|
||||
* Name: board_get_product_name |
||||
* |
||||
* Description: |
||||
* Called to retrieve the product name. The returned value is a assumed |
||||
* to be written to a pascal style string that will be length prefixed |
||||
* and not null terminated |
||||
* |
||||
* Input Parameters: |
||||
* product_name - A pointer to a buffer to write the name. |
||||
* maxlen - The maximum number of charter that can be written |
||||
* |
||||
* Returned Value: |
||||
* The length of characters written to the buffer. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
uint8_t board_get_product_name(uint8_t *product_name, size_t maxlen) |
||||
{ |
||||
DEBUGASSERT(maxlen > UAVCAN_STRLEN(HW_UAVCAN_NAME)); |
||||
memcpy(product_name, HW_UAVCAN_NAME, UAVCAN_STRLEN(HW_UAVCAN_NAME)); |
||||
return UAVCAN_STRLEN(HW_UAVCAN_NAME); |
||||
} |
||||
|
||||
/****************************************************************************
|
||||
* Name: board_get_hardware_version |
||||
* |
||||
* Description: |
||||
* Called to retrieve the hardware version information. The function |
||||
* will first initialize the the callers struct to all zeros. |
||||
* |
||||
* Input Parameters: |
||||
* hw_version - A pointer to a uavcan_hardwareversion_t. |
||||
* |
||||
* Returned Value: |
||||
* Length of the unique_id |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
size_t board_get_hardware_version(uavcan_HardwareVersion_t *hw_version) |
||||
{ |
||||
memset(hw_version, 0, sizeof(uavcan_HardwareVersion_t)); |
||||
|
||||
hw_version->major = HW_VERSION_MAJOR; |
||||
hw_version->minor = HW_VERSION_MINOR; |
||||
|
||||
return board_get_mfguid(*(mfguid_t *) hw_version->unique_id); |
||||
} |
||||
|
||||
/****************************************************************************
|
||||
* Name: board_indicate |
||||
* |
||||
* Description: |
||||
* Provides User feedback to indicate the state of the bootloader |
||||
* on board specific hardware. |
||||
* |
||||
* Input Parameters: |
||||
* indication - A member of the uiindication_t |
||||
* |
||||
* Returned Value: |
||||
* None |
||||
* |
||||
****************************************************************************/ |
||||
#define led(n, code, r , g , b, h) {.red = (r),.green = (g), .blue = (b),.hz = (h)} |
||||
|
||||
typedef begin_packed_struct struct led_t { |
||||
uint8_t red; |
||||
uint8_t green; |
||||
uint8_t blue; |
||||
uint8_t hz; |
||||
} end_packed_struct led_t; |
||||
|
||||
static const led_t i2l[] = { |
||||
|
||||
led(0, off, 0, 0, 0, 0), |
||||
led(1, reset, 128, 128, 128, 30), |
||||
led(2, autobaud_start, 0, 128, 0, 1), |
||||
led(3, autobaud_end, 0, 128, 0, 2), |
||||
led(4, allocation_start, 0, 0, 64, 2), |
||||
led(5, allocation_end, 0, 128, 64, 3), |
||||
led(6, fw_update_start, 32, 128, 64, 3), |
||||
led(7, fw_update_erase_fail, 32, 128, 32, 3), |
||||
led(8, fw_update_invalid_response, 64, 0, 0, 1), |
||||
led(9, fw_update_timeout, 64, 0, 0, 2), |
||||
led(a, fw_update_invalid_crc, 64, 0, 0, 4), |
||||
led(b, jump_to_app, 0, 128, 0, 10), |
||||
|
||||
}; |
||||
|
||||
void board_indicate(uiindication_t indication) |
||||
{ |
||||
rgb_led(i2l[indication].red, |
||||
i2l[indication].green, |
||||
i2l[indication].blue, |
||||
i2l[indication].hz); |
||||
} |
@ -0,0 +1,129 @@
@@ -0,0 +1,129 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* 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 |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/*
|
||||
* @file boot_config.h |
||||
* |
||||
* bootloader definitions that configures the behavior and options |
||||
* of the Boot loader |
||||
* This file is relies on the parent folder's boot_config.h file and defines |
||||
* different usages of the hardware for bootloading |
||||
*/ |
||||
|
||||
#pragma once |
||||
|
||||
/************************************************************************************
|
||||
* Included Files |
||||
************************************************************************************/ |
||||
|
||||
/* Bring in the board_config.h definitions
|
||||
* todo:make this be pulled in from a targed's build |
||||
* files in nuttx*/ |
||||
|
||||
#include "board_config.h" |
||||
#include "uavcan.h" |
||||
#include <nuttx/compiler.h> |
||||
|
||||
#include <stdint.h> |
||||
|
||||
#include <stm32_flash.h> |
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions |
||||
****************************************************************************/ |
||||
|
||||
#define OPT_PREFERRED_NODE_ID ANY_NODE_ID |
||||
|
||||
//todo:wrap OPT_x in in ifdefs for command line definitions
|
||||
#define OPT_TBOOT_MS 5000 |
||||
#define OPT_NODE_STATUS_RATE_MS 800 |
||||
#define OPT_NODE_INFO_RATE_MS 50 |
||||
#define OPT_BL_NUMBER_TIMERS 7 |
||||
|
||||
/*
|
||||
* This Option set is set to 1 ensure a provider of firmware has an |
||||
* opportunity update the node's firmware. |
||||
* This Option is the default policy and can be overridden by |
||||
* a jumper |
||||
* When this Policy is set, the node will ignore tboot and |
||||
* wait indefinitely for a GetNodeInfo request before booting. |
||||
* |
||||
* OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT is used to allow |
||||
* the polarity of the jumper to be True Active |
||||
* |
||||
* wait OPT_WAIT_FOR_GETNODEINFO OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO |
||||
* Jumper |
||||
* yes 1 0 x |
||||
* yes 1 1 Active |
||||
* no 1 1 Not Active |
||||
* no 0 0 X |
||||
* yes 0 1 Active |
||||
* no 0 1 Not Active |
||||
* |
||||
*/ |
||||
#define OPT_WAIT_FOR_GETNODEINFO 0 |
||||
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO 1 |
||||
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 0 |
||||
#define OPT_ENABLE_WD 1 |
||||
|
||||
#define OPT_RESTART_TIMEOUT_MS 20000 |
||||
|
||||
/* Reserved for the Booloader */ |
||||
#define OPT_BOOTLOADER_SIZE_IN_K (1024*64) |
||||
|
||||
/* Reserved for the application out of the total
|
||||
* system flash minus the BOOTLOADER_SIZE_IN_K |
||||
*/ |
||||
#define OPT_APPLICATION_RESERVER_IN_K 0 |
||||
|
||||
#define OPT_APPLICATION_IMAGE_OFFSET OPT_BOOTLOADER_SIZE_IN_K |
||||
#define OPT_APPLICATION_IMAGE_LENGTH (FLASH_SIZE-(OPT_BOOTLOADER_SIZE_IN_K+OPT_APPLICATION_RESERVER_IN_K)) |
||||
|
||||
|
||||
#define FLASH_BASE STM32_FLASH_BASE |
||||
#define FLASH_SIZE STM32_FLASH_SIZE |
||||
|
||||
#define APPLICATION_LOAD_ADDRESS (FLASH_BASE + OPT_APPLICATION_IMAGE_OFFSET) |
||||
#define APPLICATION_SIZE (FLASH_SIZE-OPT_APPLICATION_IMAGE_OFFSET) |
||||
#define APPLICATION_LAST_8BIT_ADDRRESS ((uint8_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint8_t))) |
||||
#define APPLICATION_LAST_32BIT_ADDRRESS ((uint32_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint32_t))) |
||||
#define APPLICATION_LAST_64BIT_ADDRRESS ((uint64_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint64_t))) |
||||
|
||||
//* If this board uses big flash that have large sectors */
|
||||
|
||||
#define OPT_USE_YIELD |
||||
|
||||
/* Bootloader Option*****************************************************************
|
||||
* |
||||
*/ |
||||
#define GPIO_GETNODEINFO_JUMPER (GPIO_BOOT_CONFIG & ~GPIO_EXTI) |
@ -0,0 +1,130 @@
@@ -0,0 +1,130 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* 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 |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file can.c |
||||
* |
||||
* Board-specific CAN functions. |
||||
*/ |
||||
|
||||
/************************************************************************************
|
||||
* Included Files |
||||
************************************************************************************/ |
||||
|
||||
#include <px4_platform_common/px4_config.h> |
||||
|
||||
#include <errno.h> |
||||
#include <debug.h> |
||||
|
||||
#include <nuttx/can/can.h> |
||||
#include <arch/board/board.h> |
||||
|
||||
#include "chip.h" |
||||
#include "arm_arch.h" |
||||
|
||||
#include "stm32.h" |
||||
#include "stm32_can.h" |
||||
#include "board_config.h" |
||||
|
||||
#ifdef CONFIG_CAN |
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions |
||||
************************************************************************************/ |
||||
/* Configuration ********************************************************************/ |
||||
|
||||
#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) |
||||
# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." |
||||
# undef CONFIG_STM32_CAN2 |
||||
#endif |
||||
|
||||
#ifdef CONFIG_STM32_CAN1 |
||||
# define CAN_PORT 1 |
||||
#else |
||||
# define CAN_PORT 2 |
||||
#endif |
||||
|
||||
/************************************************************************************
|
||||
* Private Functions |
||||
************************************************************************************/ |
||||
|
||||
/************************************************************************************
|
||||
* Public Functions |
||||
************************************************************************************/ |
||||
int can_devinit(void); |
||||
|
||||
/************************************************************************************
|
||||
* Name: can_devinit |
||||
* |
||||
* Description: |
||||
* All STM32 architectures must provide the following interface to work with |
||||
* examples/can. |
||||
* |
||||
************************************************************************************/ |
||||
|
||||
int can_devinit(void) |
||||
{ |
||||
static bool initialized = false; |
||||
struct can_dev_s *can; |
||||
int ret; |
||||
|
||||
/* Check if we have already initialized */ |
||||
|
||||
if (!initialized) { |
||||
/* Call stm32_caninitialize() to get an instance of the CAN interface */ |
||||
|
||||
can = stm32_caninitialize(CAN_PORT); |
||||
|
||||
if (can == NULL) { |
||||
canerr("ERROR: Failed to get CAN interface\n"); |
||||
return -ENODEV; |
||||
} |
||||
|
||||
/* Register the CAN driver at "/dev/can0" */ |
||||
|
||||
ret = can_register("/dev/can0", can); |
||||
|
||||
if (ret < 0) { |
||||
canerr("ERROR: can_register failed: %d\n", ret); |
||||
return ret; |
||||
} |
||||
|
||||
/* Now we are initialized */ |
||||
|
||||
initialized = true; |
||||
} |
||||
|
||||
return OK; |
||||
} |
||||
|
||||
#endif |
@ -0,0 +1,38 @@
@@ -0,0 +1,38 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2020-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 |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#include <px4_arch/i2c_hw_description.h> |
||||
|
||||
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { |
||||
initI2CBusExternal(2), |
||||
}; |
@ -0,0 +1,293 @@
@@ -0,0 +1,293 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2012-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 |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file init.c |
||||
* |
||||
* Matek M9NF4 CAN -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 <px4_platform_common/px4_config.h> |
||||
#include <px4_platform_common/tasks.h> |
||||
|
||||
#include <stdbool.h> |
||||
#include <stdio.h> |
||||
#include <string.h> |
||||
#include <debug.h> |
||||
#include <errno.h> |
||||
#include <syslog.h> |
||||
|
||||
#include <nuttx/board.h> |
||||
#include <nuttx/spi/spi.h> |
||||
#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" |
||||
#include <stm32_uart.h> |
||||
|
||||
#include <arch/board/board.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/board_dma_alloc.h> |
||||
#include <px4_platform/gpio.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 |
||||
* |
||||
* 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. |
||||
* |
||||
************************************************************************************/ |
||||
|
||||
__EXPORT void |
||||
stm32_boardinitialize(void) |
||||
{ |
||||
|
||||
/* configure pins */ |
||||
const uint32_t gpio[] = PX4_GPIO_INIT_LIST; |
||||
px4_gpio_init(gpio, arraySize(gpio)); |
||||
|
||||
/* configure SPI all interfaces GPIO */ |
||||
|
||||
stm32_spiinitialize(); |
||||
|
||||
} |
||||
|
||||
/****************************************************************************
|
||||
* Name: board_app_initialize |
||||
* |
||||
* 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_INIT. |
||||
* |
||||
* 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. |
||||
* |
||||
* Returned Value: |
||||
* Zero (OK) is returned on success; a negated errno value is returned on |
||||
* any failure to indicate the nature of the failure. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
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. */ |
||||
|
||||
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_BLUE); |
||||
|
||||
/*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; |
||||
} |
||||
|
||||
/* 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); |
||||
|
||||
|
||||
/* SPI3: SD card */ |
||||
|
||||
spi3 = stm32_spibus_initialize(3); |
||||
|
||||
if (!spi3) { |
||||
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 3\n"); |
||||
led_on(LED_BLUE); |
||||
return -ENODEV; |
||||
} |
||||
|
||||
SPI_SETFREQUENCY(spi3, 10 * 1000 * 1000); |
||||
SPI_SETBITS(spi3, 8); |
||||
SPI_SETMODE(spi3, SPIDEV_MODE3); |
||||
up_udelay(20); |
||||
|
||||
#if defined(FLASH_BASED_PARAMS) |
||||
static sector_descriptor_t params_sector_map[] = { |
||||
{1, 16 * 1024, 0x08008000}, |
||||
{2, 16 * 1024, 0x0800C000}, |
||||
{0, 0, 0}, |
||||
}; |
||||
|
||||
/* Initialize the flashfs layer to use heap allocated memory */ |
||||
int result = parameter_flashfs_init(params_sector_map, NULL, 0); |
||||
|
||||
if (result != OK) { |
||||
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result); |
||||
led_on(LED_AMBER); |
||||
return -ENODEV; |
||||
} |
||||
|
||||
#endif |
||||
|
||||
/* Configure the HW based on the manifest */ |
||||
|
||||
px4_platform_configure(); |
||||
|
||||
return OK; |
||||
} |
@ -0,0 +1,172 @@
@@ -0,0 +1,172 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* 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 |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file led.c |
||||
* |
||||
* LED backend. |
||||
*/ |
||||
|
||||
#include <px4_platform_common/px4_config.h> |
||||
|
||||
#include <stdbool.h> |
||||
|
||||
#include "chip.h" |
||||
#include "stm32_gpio.h" |
||||
#include "board_config.h" |
||||
|
||||
#include <nuttx/board.h> |
||||
#include <arch/board/board.h> |
||||
|
||||
#include "led.h" |
||||
|
||||
#define TMR_BASE STM32_TIM1_BASE |
||||
#define TMR_FREQUENCY STM32_APB2_TIM1_CLKIN |
||||
#define TMR_REG(o) (TMR_BASE+(o)) |
||||
|
||||
static uint32_t g_ledmap[] = { |
||||
GPIO_LED_BLUE, |
||||
}; |
||||
|
||||
void rgb_led(int r, int g, int b, int freqs) |
||||
{ |
||||
|
||||
long fosc = TMR_FREQUENCY; |
||||
long prescale = 2048; |
||||
long p1s = fosc / prescale; |
||||
long p0p5s = p1s / 2; |
||||
uint16_t val; |
||||
static bool once = 0; |
||||
|
||||
if (!once) { |
||||
once = 1; |
||||
|
||||
/* Enabel Clock to Block */ |
||||
modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_TIM1EN); |
||||
|
||||
/* Reload */ |
||||
|
||||
val = getreg16(TMR_REG(STM32_BTIM_EGR_OFFSET)); |
||||
val |= ATIM_EGR_UG; |
||||
putreg16(val, TMR_REG(STM32_BTIM_EGR_OFFSET)); |
||||
|
||||
/* Set Prescaler STM32_TIM_SETCLOCK */ |
||||
|
||||
putreg16(prescale, TMR_REG(STM32_BTIM_PSC_OFFSET)); |
||||
|
||||
/* Enable STM32_TIM_SETMODE*/ |
||||
|
||||
putreg16(ATIM_CR1_CEN | ATIM_CR1_ARPE, TMR_REG(STM32_BTIM_CR1_OFFSET)); |
||||
|
||||
|
||||
putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC1M_SHIFT) | ATIM_CCMR1_OC1PE | |
||||
(ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC2M_SHIFT) | ATIM_CCMR1_OC2PE, TMR_REG(STM32_GTIM_CCMR1_OFFSET)); |
||||
putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC3M_SHIFT) | ATIM_CCMR2_OC3PE, TMR_REG(STM32_GTIM_CCMR2_OFFSET)); |
||||
putreg16(ATIM_CCER_CC3E | ATIM_CCER_CC3P | |
||||
ATIM_CCER_CC2E | ATIM_CCER_CC2P | |
||||
ATIM_CCER_CC1E | ATIM_CCER_CC1P, TMR_REG(STM32_GTIM_CCER_OFFSET)); |
||||
|
||||
|
||||
stm32_configgpio(GPIO_TIM1_CH1N_1); |
||||
stm32_configgpio(GPIO_TIM1_CH2N_1); |
||||
stm32_configgpio(GPIO_TIM1_CH3N_1); |
||||
|
||||
/* master output enable = on */ |
||||
putreg16(ATIM_BDTR_MOE, (TMR_REG(STM32_ATIM_BDTR_OFFSET))); |
||||
} |
||||
|
||||
long p = freqs == 0 ? p1s : p1s / freqs; |
||||
putreg32(p, TMR_REG(STM32_BTIM_ARR_OFFSET)); |
||||
|
||||
p = freqs == 0 ? p1s + 1 : p0p5s / freqs; |
||||
|
||||
putreg32((r * p) / 255, TMR_REG(STM32_GTIM_CCR1_OFFSET)); |
||||
putreg32((g * p) / 255, TMR_REG(STM32_GTIM_CCR2_OFFSET)); |
||||
putreg32((b * p) / 255, TMR_REG(STM32_GTIM_CCR3_OFFSET)); |
||||
|
||||
val = getreg16(TMR_REG(STM32_BTIM_CR1_OFFSET)); |
||||
|
||||
if (freqs == 0) { |
||||
val &= ~ATIM_CR1_CEN; |
||||
|
||||
} else { |
||||
val |= ATIM_CR1_CEN; |
||||
} |
||||
|
||||
putreg16(val, TMR_REG(STM32_BTIM_CR1_OFFSET)); |
||||
|
||||
} |
||||
|
||||
__EXPORT void led_init(void) |
||||
{ |
||||
for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { |
||||
stm32_configgpio(g_ledmap[l]); |
||||
} |
||||
} |
||||
|
||||
static void phy_set_led(int led, bool state) |
||||
{ |
||||
if (led == 0) { |
||||
stm32_gpiowrite(g_ledmap[led], !state); |
||||
} |
||||
} |
||||
/*
|
||||
__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); |
||||
} |
||||
}*/ |
||||
|
||||
__EXPORT void led_on(int led) |
||||
{ |
||||
phy_set_led(led, true); |
||||
} |
||||
|
||||
|
||||
__EXPORT void led_off(int led) |
||||
{ |
||||
phy_set_led(led, false); |
||||
} |
||||
|
||||
__EXPORT void led_toggle(int led) |
||||
{ |
||||
if (led == 0) { |
||||
phy_set_led(led, !stm32_gpioread(g_ledmap[led])); |
||||
} |
||||
} |
@ -0,0 +1,41 @@
@@ -0,0 +1,41 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2015-2021 PX4 Development Team. All rights reserved. |
||||
* Author: David Sidrane<david_s5@nscdg.com> |
||||
* |
||||
* 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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
__BEGIN_DECLS |
||||
void rgb_led(int r, int g, int b, int freqs); |
||||
extern void led_init(void); |
||||
extern void led_on(int led); |
||||
extern void led_off(int led); |
||||
extern void led_toggle(int led); |
||||
__END_DECLS |
@ -0,0 +1,47 @@
@@ -0,0 +1,47 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2018-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 |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#include <px4_arch/spi_hw_description.h> |
||||
#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_ICM20602, SPI::CS{GPIO::PortA, GPIO::Pin4}), |
||||
}), |
||||
initSPIBus(SPI::Bus::SPI2, { |
||||
initSPIDevice(DRV_MAG_DEVTYPE_RM3100, SPI::CS{GPIO::PortB, GPIO::Pin12}) |
||||
}), |
||||
}; |
||||
|
||||
static constexpr bool unused = validateSPIConfig(px4_spi_buses); |
@ -0,0 +1,49 @@
@@ -0,0 +1,49 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2018-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 |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#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::Timer2, DMA{DMA::Index1, DMA::Stream1, DMA::Channel3}), |
||||
}; |
||||
|
||||
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { |
||||
initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel3}, {GPIO::PortB, GPIO::Pin0}), |
||||
initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel4}, {GPIO::PortB, GPIO::Pin1}), |
||||
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel4}, {GPIO::PortA, GPIO::Pin3}), |
||||
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel3}, {GPIO::PortA, GPIO::Pin2}), |
||||
}; |
||||
|
||||
//constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
|
||||
// initIOTimerChannelMapping(io_timers, timer_io_channels);
|
@ -0,0 +1,107 @@
@@ -0,0 +1,107 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2018-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 |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @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 <nuttx/usb/usbdev.h> |
||||
#include <nuttx/usb/usbdev_trace.h> |
||||
|
||||
#include <arm_arch.h> |
||||
#include <stm32.h> |
||||
#include "board_config.h" |
||||
|
||||
/************************************************************************************
|
||||
* Definitions |
||||
************************************************************************************/ |
||||
|
||||
/************************************************************************************
|
||||
* Private Functions |
||||
************************************************************************************/ |
||||
|
||||
/************************************************************************************
|
||||
* Public Functions |
||||
************************************************************************************/ |
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbinitialize |
||||
* |
||||
* Description: |
||||
* Called to setup USB-related GPIO pins for the omnibusf4sd 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_STM32_OTGFS |
||||
stm32_configgpio(GPIO_OTGFS_VBUS); |
||||
/* XXX We only support device mode
|
||||
stm32_configgpio(GPIO_OTGFS_PWRON); |
||||
stm32_configgpio(GPIO_OTGFS_OVER); |
||||
*/ |
||||
#endif |
||||
} |
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbsuspend |
||||
* |
||||
* Description: |
||||
* Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is |
||||
* used. This function is called whenever the USB enters or leaves suspend mode. |
||||
* This is an opportunity for the board logic to shutdown clocks, power, etc. |
||||
* while the USB is suspended. |
||||
* |
||||
************************************************************************************/ |
||||
|
||||
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) |
||||
{ |
||||
uinfo("resume: %d\n", resume); |
||||
} |
@ -0,0 +1,17 @@
@@ -0,0 +1,17 @@
|
||||
# UAVCAN boot loadable Module ID |
||||
set(uavcanblid_sw_version_major 0) |
||||
set(uavcanblid_sw_version_minor 1) |
||||
add_definitions( |
||||
-DAPP_VERSION_MAJOR=${uavcanblid_sw_version_major} |
||||
-DAPP_VERSION_MINOR=${uavcanblid_sw_version_minor} |
||||
) |
||||
|
||||
set(uavcanblid_hw_version_major 0) |
||||
set(uavcanblid_hw_version_minor 140) |
||||
set(uavcanblid_name "\"org.matek.gnss-m9n-f4\"") |
||||
|
||||
add_definitions( |
||||
-DHW_UAVCAN_NAME=${uavcanblid_name} |
||||
-DHW_VERSION_MAJOR=${uavcanblid_hw_version_major} |
||||
-DHW_VERSION_MINOR=${uavcanblid_hw_version_minor} |
||||
) |
Loading…
Reference in new issue