Browse Source

v5x/v6x: update IMU sensors (remove ISM330DLC)

release/1.12
Beat Küng 4 years ago committed by Daniel Agar
parent
commit
9f5dee2ecf
  1. 2
      boards/px4/fmu-v5x/base_phy_DP83848C.cmake
  2. 2
      boards/px4/fmu-v5x/default.cmake
  3. 14
      boards/px4/fmu-v5x/init/rc.board_sensors
  4. 2
      boards/px4/fmu-v5x/src/spi.cpp
  5. 1
      boards/px4/fmu-v6x/default.cmake
  6. 19
      boards/px4/fmu-v6x/init/rc.board_sensors
  7. 2
      boards/px4/fmu-v6x/src/spi.cpp
  8. 1
      boards/px4/fmu-v6x/stackcheck.cmake

2
boards/px4/fmu-v5x/base_phy_DP83848C.cmake

@ -33,7 +33,7 @@ px4_add_board( @@ -33,7 +33,7 @@ px4_add_board(
imu/adis16497
imu/bosch/bmi088
imu/invensense/icm20602
imu/st/ism330dlc
imu/invensense/icm42688p
irlock
lights/blinkm
lights/rgbled

2
boards/px4/fmu-v5x/default.cmake

@ -34,7 +34,7 @@ px4_add_board( @@ -34,7 +34,7 @@ px4_add_board(
imu/adis16497
imu/bosch/bmi088
imu/invensense/icm20602
imu/st/ism330dlc
imu/invensense/icm42688p
irlock
lights/blinkm
lights/rgbled

14
boards/px4/fmu-v5x/init/rc.board_sensors

@ -8,17 +8,17 @@ board_adc start @@ -8,17 +8,17 @@ board_adc start
ina226 -X -b 1 -t 1 -k start
ina226 -X -b 2 -t 2 -k start
# Internal SPI bus ICM-20602
icm20602 -R 10 -s start
# Internal SPI bus ISM300DLC
ism330dlc -s start
# Internal SPI BMI088
bmi088 -A -R 4 -s start
bmi088 -G -R 4 -s start
# Possible internal compass
# Internal SPI bus ICM42688p
icm42688p -R 6 -s start
# Internal SPI bus ICM-20602 (hard-mounted)
icm20602 -R 10 -s start
# Internal magnetometer on I2c
bmm150 -I start
# Possible internal Baro

2
boards/px4/fmu-v5x/src/spi.cpp

@ -40,7 +40,7 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { @@ -40,7 +40,7 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
}, {GPIO::PortI, GPIO::Pin11}),
initSPIBus(SPI::Bus::SPI2, {
initSPIDevice(DRV_IMU_DEVTYPE_ST_ISM330DLC, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortH, GPIO::Pin12}),
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortH, GPIO::Pin12}),
}, {GPIO::PortD, GPIO::Pin15}),
initSPIBus(SPI::Bus::SPI3, {
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}),

1
boards/px4/fmu-v6x/default.cmake

@ -34,7 +34,6 @@ px4_add_board( @@ -34,7 +34,6 @@ px4_add_board(
imu/adis16497
imu/bosch/bmi088
imu/invensense/icm20649
imu/st/ism330dlc
irlock
lights/blinkm
lights/rgbled

19
boards/px4/fmu-v6x/init/rc.board_sensors

@ -2,29 +2,28 @@ @@ -2,29 +2,28 @@
#
# PX4 FMUv6X specific board sensors init
#------------------------------------------------------------------------------
board_adc start
# Start Digital power monitors
ina226 -X -b 1 -t 1 -k start
ina226 -X -b 2 -t 2 -k start
# Internal SPI bus ICM-20649
icm20649 -R 2 -s start
# Internal SPI BMI088
bmi088 -A -R 4 -s start
bmi088 -G -R 4 -s start
# Internal SPI bus ISM300DLC
ism330dlc -s start
# Internal SPI bus ICM42688p
icm42688p -R 6 -s start
# Internal SPI bus BMI088 accel/gyro
bmi088 -A -R 12 -s start
bmi088 -G -R 12 -s start
# Internal SPI bus ICM-20649 (hard-mounted)
icm20649 -R 2 -s start
# Possible internal compass
# Internal magnetometer on I2c
bmm150 -I start
# Possible internal Baro
bmp388 -I start
bmp388 -I -a 0x77 start
bmp388 -I start
# Baro on I2C3
ms5611 -X start

2
boards/px4/fmu-v6x/src/spi.cpp

@ -40,7 +40,7 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { @@ -40,7 +40,7 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
}, {GPIO::PortI, GPIO::Pin11}),
initSPIBus(SPI::Bus::SPI2, {
initSPIDevice(DRV_IMU_DEVTYPE_ST_ISM330DLC, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}),
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}),
}, {GPIO::PortF, GPIO::Pin4}),
initSPIBus(SPI::Bus::SPI3, {
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}),

1
boards/px4/fmu-v6x/stackcheck.cmake

@ -34,7 +34,6 @@ px4_add_board( @@ -34,7 +34,6 @@ px4_add_board(
imu/adis16497
imu/bosch/bmi088
imu/invensense/icm20649
imu/st/ism330dlc
irlock
lights/blinkm
lights/rgbled

Loading…
Cancel
Save