diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-F405V2/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-F405V2/defaults.parm deleted file mode 100755 index e4f10116fd234..0000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-F405V2/defaults.parm +++ /dev/null @@ -1,4 +0,0 @@ -# logging -LOG_BACKEND_TYPE 4 -LOG_FILE_BUFSIZE 4 - diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-F405V2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-F405V2/hwdef.dat index 45dda5c1c0042..1948525f694e0 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-F405V2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-F405V2/hwdef.dat @@ -1,68 +1,15 @@ # hw definition file for processing by chibios_pins.py # Aocoda-RC-F405V2 MPU6500/MPU6000 -# This hwdef.dat file contains a lot of comments so it can act as a -# reference for developers adding new boards. - -# The hwdef.dat file defines all the hardware peripherals and pins for -# a port of ArduPilot to a board using the ChibiOS HAL. You should be -# able to write the hwdef.dat file for a new board with just the -# schematic for the board. - -# This file is processed by chibios_hwdef.py to create hwdef.h for -# this board. You may find it useful to run chibios_hwdef.py manually -# when building this file for a new board. The resulting hwdef.h file -# is formatted to make it quite readable. It is strongly suggested -# that you read the resulting hwdef.h file when porting to a new board -# to make sure it has resulted in what you want. - -# You should read this file in conjunction with the schematic for your -# board, the datasheet for the MCU for your board and the python -# tables file that we have extracted from the datasheet for your -# MCU. The python tables file is particularly important, so if you -# haven't seen it before go and look at it now. For the STM32F427 it -# it called STM32F427xx.py and it is in the hwdef/script/ directory -# inside the HAL_ChibiOS directory. That file tells you what each pin -# can do (the alternate functions table) and what DMA channels can be -# used for each peripheral type. The alternative functions table is -# particularly useful when doing a new hwdef.dat file as you can work -# out peripheral numbers given a port/pin name. - -# We need to start off by saying what main CPU is on the board. There -# are two CPU identifiers that you need to specify. The first is the -# ChibiOS MCU type. The second string needs to match the name of a config -# file in the libraries/AP_HAL_ChibiOS/hwdef/script directory. -# In this case we are using a H743 MCU, so we select STM32H743xx to match the -# STM32H743xx.py file in the script directory. If you are supporting a -# board type that doesn't have a python hardware database file yet -# then you will need to create one. There are scripts in the scripts -# directory to help with that by parsing the STM32 datasheets to -# extract the required DMA and alternate function tables. - # MCU class and specific type MCU STM32F4xx STM32F405xx -# Now we need to specify the APJ_BOARD_ID. This is the ID that the -# bootloader presents to GCS software so it knows if this firmware is -# suitable for the board. Please see -# https://github.com/ArduPilot/Bootloader/blob/master/hw_config.h for -# a list of current board IDs. If you add a new board type then please -# get it added to that repository so we don't get conflicts. - -# Note that APJ is "ArduPilot JSON Firmware Format". - # board ID for firmware load APJ_BOARD_ID 5211 -# Now you need to say what crystal frequency you have for this -# board. All of the clocks are scaled against this. Typical values are -# 24000000 or 8000000. - # crystal frequency, setup to use external oscillator OSCILLATOR_HZ 8000000 -# Now the size of flash in kilobytes, for creating the ld.script. - # flash size FLASH_SIZE_KB 1024 @@ -72,20 +19,6 @@ FLASH_RESERVE_START_KB 64 define HAL_STORAGE_SIZE 15360 STORAGE_FLASH_PAGE 1 -# On some boards you will need to also set the various PLL values. See -# the defaults in common/mcuconf.h, and use the define mechanism -# explained later in this file to override values suitable for your -# board. Refer to your MCU datasheet or examples from supported boards -# in ChibiOS for the right values. - -# Now define the voltage the MCU runs at. This is needed for ChibiOS -# to set various internal driver limits. It is in 0.01 volt units. - - -# This is the STM32 timer that ChibiOS will use for the low level -# driver. This must be a 32 bit timer. We currently only support -# timers 2, 3, 4, 5 and 21. See hal_st_lld.c in ChibiOS for details. - # ChibiOS system timer define STM32_ST_USE_TIMER 5 define CH_CFG_ST_RESOLUTION 32 @@ -97,15 +30,11 @@ USB_STRING_MANUFACTURER "Aocoda-RC-F405V2" PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 +# OTG USB VBUS PB12 VBUS INPUT OPENDRAIN -# Now the first SPI bus. At minimum you need SCK, MISO and MOSI pin -# definitions. You can add speed modifiers if you want them, otherwise -# the defaults for the peripheral class are used. - # IMU SPI PA4 MPU_CS CS -#PB11 MPU_CS CS PA5 SPI1_SCK SPI1 PA6 SPI1_MISO SPI1 PA7 SPI1_MOSI SPI1 @@ -122,43 +51,17 @@ PB4 SPI3_MISO SPI3 PB5 SPI3_MOSI SPI3 PC0 FLASH_CS CS -# Now define the order that I2C buses are presented in the hal.i2c API -# in ArduPilot. For historical reasons inherited from HAL_PX4 the -# 'external' I2C bus should be bus 1 in hal.i2c, and internal I2C bus -# should be bus 0. On fmuv3 the STM32 I2C1 is our external bus and -# I2C2 is our internal bus, so we need to setup the order as I2C2 -# followed by I2C1 in order to achieve the conventional order that -# drivers expect. - # I2C Buses I2C_ORDER I2C1 -# Now the first I2C bus. The pin speeds are automatically setup -# correctly, but can be overridden here if needed. - # I2C1 PB6 I2C1_SCL I2C1 PB7 I2C1_SDA I2C1 -# Now define the primary battery connectors. The labels we choose here -# are used to create defines for pins in the various drivers, so -# choose names that match existing board setups where possible. Here -# we define two pins PA2 and PA3 for voltage and current sensing, with -# a scale factor of 1.0 and connected on ADC1. The pin number this -# maps to in hal.adc is automatically determined using the datasheet -# tables in STM32F427xx.py. - # ADC for Power PC2 BATT_VOLTAGE_SENS ADC1 SCALE(1) PC1 BATT_CURRENT_SENS ADC1 SCALE(1) -# This adds a C define which sets up the ArduPilot architecture -# define. Any line starting with 'define' is copied literally as -# a #define in the hwdef.h header. - -# Now setup the default battery pins driver analog pins and default -# scaling for the power brick. - # PC1 = IN11 PC2 = IN12 define HAL_BATT_MONITOR_DEFAULT 4 define HAL_BATT_VOLT_PIN 12 @@ -167,7 +70,6 @@ define HAL_BATT_VOLT_SCALE 11 define HAL_BATT_CURR_SCALE 30.1 # ADC for airspeed(or rssi) - # PC3 - ADC123_IN13 define BOARD_RSSI_ANA_PIN 13 PC3 RSSI_ADC_PIN ADC1 SCALE(1) @@ -176,16 +78,10 @@ PC3 RSSI_ADC_PIN ADC1 SCALE(1) # PE12 FMU_LED_AMBER OUTPUT HIGH OPENDRAIN GPIO(0) # green LED1 marked as B/E # blue LED0 marked as ACT - PC13 LED_BLUE OUTPUT LOW GPIO(1) define HAL_GPIO_A_LED_PIN 1 define HAL_GPIO_B_LED_PIN 2 -# Now the serial ordering. These map to the SERIALn_ parameter numbers -# If you use a shorter list then HAL_Empty::UARTDriver -# objects are substituted for later UARTs, or you can leave a gap by -# listing one or more of the uarts as EMPTY. - # The normal usage of this ordering is: # 1) SERIAL0: console (primary mavlink, usually USB) # 2) SERIAL1: GPS @@ -197,41 +93,6 @@ define HAL_GPIO_B_LED_PIN 2 # order of UARTs (and USB) SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 -# Now we start on the pin definitions. Every pin used by ArduPilot -# needs to be in this file. The pins in this file can be defined in any order. - -# The format is P+port+pin. So PC4 is portC pin4. -# For every pin the second column is the label. If this is a -# peripheral that has an alternate function defined in the STM32 -# datasheet then the label must be the name of that alternative -# function. The names are looked up in the python database for this -# MCU. Please see STM32F427xx.py for the F427 database. That database -# is used to automatically fill in the alternative function (and later -# for the DMA channels). - -# The third column is the peripheral type. This must be one of the -# following: UARTn, USARTn, OTGn, SPIn, I2Cn, ADCn, TIMn, SWD, SDIO, -# INPUT, OUTPUT, CS. - -# The fourth and later columns are for modifiers on the pin. The -# possible modifiers are: -# pin speed: SPEED_VERYLOW, SPEED_LOW, SPEED_MEDIUM, SPEED_HIGH -# pullup: PULLUP, PULLDOWN, FLOATING -# out type: OPENDRAIN, PUSHPULL -# default value: LOW, HIGH - -# Additionally, each class of pin peripheral can have extra modifiers -# suitable for that pin type. For example, for an OUTPUT you can map -# it to a GPIO number in hal.gpio using the GPIO(n) modifier. For ADC -# inputs you can apply a scaling factor (to bring it to unit volts) -# using the SCALE(x) modifier. See the examples below for more -# modifiers, or read the python code in chibios_hwdef.py. - -# Now we define UART4 which is for the GPS. Be careful -# of the difference between USART and UART. Check the STM32F427xx.py -# if unsure which it is. For a UART we need to specify at least TX and -# RX pins. - # USART1 (GPS), SERIAL1 PA9 USART1_TX USART1 PA10 USART1_RX USART1 @@ -260,12 +121,6 @@ PC12 UART5_TX UART5 PD2 UART5_RX UART5 define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_None -# Now we start defining some PWM pins. We also map these pins to GPIO -# values, so users can set BRD_PWM_COUNT to choose how many of the PWM -# outputs on the primary MCU are setup as PWM and how many as -# GPIOs. To match HAL_PX4 we number the GPIOs for the PWM outputs -# starting at 50. - # Motors #pwm output PC6 TIM8_CH1 TIM8 PWM(1) GPIO(50) @@ -278,10 +133,6 @@ PB10 TIM2_CH3 TIM2 PWM(7) GPIO(56) PB11 TIM2_CH4 TIM2 PWM(8) GPIO(57) PB1 TIM3_CH4 TIM3 PWM(9) GPIO(58) -# This defines the PWM pin for the buzzer (if there is one). It is -# also mapped to a GPIO output so you can play with the buzzer via -# MAVLink relay commands if you want to. - # PWM output for buzzer/Beeper #PB8 TIM4_CH3 TIM4 GPIO(80) ALARM PULLDOWN LOW PB8 BUZZER OUTPUT GPIO(80) LOW @@ -289,24 +140,7 @@ define HAL_BUZZER_PIN 80 define HAL_BUZZER_ON 1 define HAL_BUZZER_OFF 0 -# Now the SPI device table. This table creates all accessible SPI -# devices, giving the name of the device (which is used by device -# drivers to open the device), plus which SPI bus it it on, what -# device ID will be used (which controls the IDs used in parameters -# such as COMPASS_DEV_ID, so we can detect when the list of devices -# changes between reboots for calibration purposes), the SPI mode to -# use, and the low and high speed settings for the device. - -# You can define more SPI devices than you actually have, to allow for -# flexibility in board setup, and the driver code can probe to see -# which are responding. - -# The DEVID values and device names are chosen to match the PX4 port -# of ArduPilot so users don't need to re-do their accel and compass -# calibrations when moving to ChibiOS. - -# spi devices -# MP6500/MPU6000 on SPI +# IMU MP6500/MPU6000 on SPI SPIDEV mpu6500 SPI1 DEVID1 MPU_CS MODE3 1*MHZ 4*MHZ SPIDEV mpu6000 SPI1 DEVID1 MPU_CS MODE3 1*MHZ 4*MHZ @@ -340,13 +174,6 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin # enable logging to dataflash define HAL_LOGGING_DATAFLASH_ENABLED 1 -################################################# -### Others from manufacture ### -################################################# - -#DMA_PRIORITY SPI3* TIM1_CH3 -#DMA_NOSHARE TIM8* TIM1* - # support VTX IRC tramp protocol define AP_TRAMP_ENABLED 1 @@ -370,5 +197,6 @@ define AC_OAPATHPLANNER_ENABLED 0 define PRECISION_LANDING 0 define HAL_BARO_WIND_COMP_ENABLED 0 define GRIPPER_ENABLED 0 + # minimal drivers to reduce flash usage include ../include/minimal.inc \ No newline at end of file