AP_HAL_ChibiOS: spro H7 extreme updates.

cannot currently use both IMUs on spro H7 extreme due to CPU load
This commit is contained in:
Andy Piper 2022-03-27 19:07:19 +01:00 committed by Randy Mackay
parent 45aebfdf74
commit 4f8c486278
5 changed files with 23 additions and 10 deletions

View File

@ -27,7 +27,6 @@
#include "Util.h"
#include "Scheduler.h"
#include <stdio.h>
#include "hwdef/common/stm32_util.h"
#if HAL_USE_WSPI == TRUE && defined(HAL_QSPI_DEVICE_LIST)

View File

@ -29,6 +29,7 @@
#if !defined(HAL_BOOTLOADER_BUILD)
#include "Semaphores.h"
#endif
#include "hwdef/common/stm32_util.h"
#include "Scheduler.h"
#include "Device.h"

View File

@ -5,3 +5,6 @@ NTF_LED_TYPES 257
# setup SERIAL2 for RCIN
SERIAL2_BAUD 115
SERIAL2_OPTIONS 8
# currently using both IMUs is too CPU intensive
INS_ENABLE_MASK 1

View File

@ -35,7 +35,7 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
PE3 LED_BOOTLOADER OUTPUT LOW # Blue LED
PE3 LED_BOOTLOADER OUTPUT LOW # Red LED
define HAL_LED_ON 0
# QuadSPI Flash
@ -57,3 +57,6 @@ DEFAULTGPIO OUTPUT LOW PULLDOWN
PB12 ICM20602_2_CS CS
PA15 ICM20602_1_CS CS
PE11 AT7456E_CS CS
## pull up VTX power
PB01 VTX_PWR OUTPUT HIGH GPIO(81)

View File

@ -66,28 +66,33 @@ PE14 SPI4_MOSI SPI4
PB8 I2C1_SCL I2C1 PULLUP
PB9 I2C1_SDA I2C1 PULLUP
# Internal current sensor
PC1 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PC0 BATT_CURRENT_SENS ADC1 SCALE(1)
# External current sensor
PC5 BATT_CURRENT_SENS2 ADC1 SCALE(1) # analog pin 8
# VTX Power control - should be high at startup to ensure power
PB01 VTX_PWR OUTPUT HIGH GPIO(81)
define RELAY2_PIN_DEFAULT 81
PC4 RSSI_IN ADC1
define BOARD_RSSI_ANA_PIN 0
# define default battery setup
define HAL_BATT_VOLT_PIN 13
define HAL_BATT_CURR_PIN 12
define HAL_BATT_VOLT_PIN 11
define HAL_BATT_CURR_PIN 10
define HAL_BATT_VOLT_SCALE 10.9
define HAL_BATT_CURR_SCALE 28.5
define HAL_BATT_MONITOR_DEFAULT 4
PC5 RSSI_ADC ADC1
# USART1
# USART1 (RCIN)
PB15 USART1_RX USART1
PB14 USART1_TX USART1
define HAL_SERIAL1_PROTOCOL SerialProtocol_RCIN
# USART2 (RCIN)
# USART2 (SmartPort)
PD5 USART2_TX USART2
define HAL_SERIAL2_PROTOCOL SerialProtocol_RCIN
# USART3
PD9 USART3_RX USART3
@ -148,7 +153,8 @@ PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) # M10
# NeoPixel LED strip
PA8 TIM1_CH1 TIM1 PWM(11) GPIO(60)
PE3 LED0 OUTPUT LOW GPIO(90) # Blue LED
# Red LED
PE3 LED0 OUTPUT LOW GPIO(90)
# spi devices
SPIDEV icm20602_1 SPI3 DEVID1 ICM20602_1_CS MODE3 2*MHZ 10*MHZ
@ -160,6 +166,7 @@ DMA_PRIORITY SPI3* SPI2* TIM5*
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
define ALLOW_ARM_NO_COMPASS
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
# two IMUs
IMU Invensense SPI:icm20602_1 ROTATION_YAW_90