mirror of https://github.com/ArduPilot/ardupilot
hwdef: removed baro from HolybroG4_GPS
not included in production versions, and baro is not generally a good idea on a GPS due to impact of airflow also disable unused IMU, SPI bus and 2nd I2C and re-enable 2nd CAN as helical units have dual CAN
This commit is contained in:
parent
95c13faac2
commit
aaec99ae31
|
@ -67,19 +67,19 @@ PA14 JTCK-SWCLK SWD
|
|||
PB7 I2C1_SDA I2C1
|
||||
PB8 I2C1_SCL I2C1
|
||||
|
||||
# I2C2 bus
|
||||
PA8 I2C2_SDA I2C2
|
||||
PA9 I2C2_SCL I2C2
|
||||
# I2C2 bus (unused)
|
||||
#PA8 I2C2_SDA I2C2
|
||||
#PA9 I2C2_SCL I2C2
|
||||
|
||||
define HAL_I2C_INTERNAL_MASK 3
|
||||
|
||||
# I2C buses
|
||||
I2C_ORDER I2C1 I2C2
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# one SPI bus
|
||||
PA5 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PA7 SPI1_MOSI SPI1
|
||||
# one SPI bus (for IMU, unused)
|
||||
#PA5 SPI1_SCK SPI1
|
||||
#PA6 SPI1_MISO SPI1
|
||||
#PA7 SPI1_MOSI SPI1
|
||||
|
||||
# SPI CS
|
||||
PC4 GYR_CS CS
|
||||
|
@ -89,21 +89,9 @@ PC14 ICM_CS CS
|
|||
# GPS PPS
|
||||
PA15 GPS_PPS_IN INPUT
|
||||
|
||||
# SPI devices
|
||||
SPIDEV bmi088_a SPI1 DEVID1 ACC_CS MODE3 10*MHZ 10*MHZ
|
||||
SPIDEV bmi088_g SPI1 DEVID2 GYR_CS MODE3 10*MHZ 10*MHZ
|
||||
|
||||
# compass
|
||||
COMPASS BMM150 I2C:0:0x10 false ROTATION_YAW_90
|
||||
|
||||
# baro
|
||||
BARO BMP388 I2C:0:0x77
|
||||
|
||||
# IMU
|
||||
IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_ROLL_180_YAW_90
|
||||
|
||||
define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||
|
||||
define HAL_USE_ADC FALSE
|
||||
define STM32_ADC_USE_ADC1 FALSE
|
||||
define HAL_DISABLE_ADC_DRIVER TRUE
|
||||
|
@ -126,9 +114,9 @@ PA11 CAN1_RX CAN1
|
|||
PA12 CAN1_TX CAN1
|
||||
PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
#PB12 CAN2_RX CAN2
|
||||
#PB13 CAN2_TX CAN2
|
||||
#PB14 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
PB12 CAN2_RX CAN2
|
||||
PB13 CAN2_TX CAN2
|
||||
PB14 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.HolybroG4_GPS"
|
||||
|
||||
|
@ -150,16 +138,12 @@ DMA_NOSHARE USART3*
|
|||
# add support for moving baseline yaw
|
||||
define GPS_MOVING_BASELINE 1
|
||||
|
||||
# GPS+MAG+BARO+LEDs
|
||||
# GPS+MAG+LEDs
|
||||
define HAL_PERIPH_ENABLE_GPS
|
||||
define HAL_PERIPH_ENABLE_MAG
|
||||
define HAL_PERIPH_ENABLE_BARO
|
||||
define HAL_PERIPH_ENABLE_NOTIFY
|
||||
define HAL_PERIPH_ENABLE_RC_OUT
|
||||
|
||||
# single baro
|
||||
define BARO_MAX_INSTANCES 1
|
||||
|
||||
# GPS on 2nd port
|
||||
define HAL_PERIPH_GPS_PORT_DEFAULT 1
|
||||
|
||||
|
|
Loading…
Reference in New Issue