px4_fmu-v4: deprecate boscch pixracer variant and cleanup SPI devs

This commit is contained in:
Daniel Agar 2019-11-11 16:04:10 -05:00
parent 00a7ac013c
commit 9183f44243
8 changed files with 33 additions and 82 deletions

View File

@ -26,7 +26,9 @@ px4_add_board(
dshot
gps
heater
imu # all available imu drivers
#imu # all available imu drivers
imu/mpu6000
imu/mpu9250
irlock
lights/blinkm
lights/rgbled

View File

@ -18,11 +18,8 @@ fmu sensor_reset 50
hmc5883 -C -T -X start
lis3mdl -X start
ist8310 start
bmp280 -X start
qmc5883 -X start
# expansion i2c used for BMM150 rotated by 90deg
bmm150 -X -R 2 start
rm3100 start
# Internal SPI
ms5611 -s start
@ -38,14 +35,10 @@ fi
if ! hmc5883 -C -T -S -R 2 start
then
# lis3mdl internal SPI bus is rotated 90 deg yaw
if ! lis3mdl start
then
# BMI055 gyro internal SPI bus
bmi055 -G start
fi
lis3mdl start
fi
# Start either ICM2060X or BMI055. They are both connected to the same SPI bus and use the same
# Start either ICM2060X. They are both connected to the same SPI bus and use the same
# chip select pin. There are different boards with either one of them and the WHO_AM_I register
# will prevent the incorrect driver from a successful initialization.
@ -53,23 +46,8 @@ fi
if ! mpu6000 -R 2 -T 20602 start
then
# ICM20608 internal SPI bus ICM-20602-G is rotated 90 deg yaw
if ! mpu6000 -R 2 -T 20608 start
then
# BMI055 accel internal SPI bus
bmi055 -A start
fi
mpu6000 -R 2 -T 20608 start
fi
# Start either MPU9250 or BMI160. They are both connected to the same SPI bus and use the same
# chip select pin. There are different boards with either one of them and the WHO_AM_I register
# will prevent the incorrect driver from a successful initialization.
# mpu9250 internal SPI bus mpu9250 is rotated 90 deg yaw
if ! mpu9250 -R 2 start
then
# BMI160 internal SPI bus
bmi160 start
fi
# External RM3100 (I2C or SPI)
rm3100 start
mpu9250 -R 2 start

View File

@ -23,17 +23,19 @@ px4_add_board(
camera_trigger
differential_pressure # all available differential pressure drivers
distance_sensor # all available distance sensor drivers
dshot
gps
heater
imu # all available imu drivers
#imu # all available imu drivers
imu/mpu6000
imu/mpu9250
irlock
lights/blinkm
lights/rgbled
lights/rgbled_ncp5623c
magnetometer # all available magnetometer drivers
mkblctrl
#optical_flow # all available optical flow drivers
optical_flow/px4flow
optical_flow # all available optical flow drivers
pca9685
protocol_splitter
pwm_input
@ -48,7 +50,9 @@ px4_add_board(
uavcan
MODULES
airspeed_selector
attitude_estimator_q
battery_status
camera_feedback
commander
dataman
@ -56,7 +60,6 @@ px4_add_board(
events
fw_att_control
fw_pos_control_l1
rover_pos_control
land_detector
landing_target_estimator
load_mon
@ -67,12 +70,11 @@ px4_add_board(
mc_pos_control
micrortps_bridge
navigator
battery_status
rover_pos_control
sensors
sih
vmount
vtol_att_control
airspeed_selector
SYSTEMCMDS
bl_update

View File

@ -71,28 +71,14 @@
* Define the Chip Selects for SPI1
* CS Devices DRDY
* ---- ----------------------------------------------- -----
* PC2 MPU9250 BMI160 PD15
* PC15 ICM, ICM_20602, ICM_20608 BMI055_ACCEL PC14
* PE15 HMC5983 BMI055_GYRO PE12
* PC2 MPU9250 PD15
* PC15 ICM, ICM_20602, ICM_20608 PC14
* PE15 HMC5983 PE12
* ---- ----------------------------------------------- -----
*/
/**
* The BMI160 sensor replaces the MPU9250 on some boards. Only one is actually present and connected
* to the second GPIO pin on port C. The wrong driver will fail during start because of an incorrect WHO_AM_I register.
*/
#define GPIO_SPI1_CS_PORTC_PIN2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2)
/**
* The BMI055 acceleration sensor replaces the ICM20608G on some boards. Only one is actually present and connected
* to the second GPIO pin on port C. The wrong driver will fail during start because of an incorrect WHO_AM_I register.
*/
#define GPIO_SPI1_CS_PORTC_PIN15 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
/**
* The BMI055 gyroscope sensor replaces the LIS3MDL, HMC5983 on some boards. Only one is actually present and connected
* to the second GPIO pin on port E. The wrong driver will fail during start because of an incorrect WHO_AM_I register.
*/
#define GPIO_SPI1_CS_PORTE_PIN15 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN15)
/* Define the Data Ready interrupts On SPI 1. */
@ -161,19 +147,12 @@
#define SPI_BUS_INIT_MASK (PX4_SPI_BUS_RAMTRON | PX4_SPI_BUS_SENSORS)
/* Use these in place of the uint32_t enumeration to select a specific SPI device on SPI1 */
#define PX4_SPIDEV_GYRO PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 1)
#define PX4_SPIDEV_ACCEL_MAG PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 2)
#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 4)
#define PX4_SPIDEV_HMC PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 5)
#define PX4_SPIDEV_ICM PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 6)
#define PX4_SPIDEV_LIS PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 7)
#define PX4_SPIDEV_BMI PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 8)
#define PX4_SPIDEV_BMA PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 9)
#define PX4_SPIDEV_ICM_20608 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 10)
#define PX4_SPIDEV_ICM_20602 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 11)
#define PX4_SPIDEV_BMI055_ACC PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 12)
#define PX4_SPIDEV_BMI055_GYR PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 13)
#define PX4_SPIDEV_MPU2 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 14)
#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 1)
#define PX4_SPIDEV_HMC PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 2)
#define PX4_SPIDEV_LIS PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 3)
#define PX4_SPIDEV_ICM_20608 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 4)
#define PX4_SPIDEV_ICM_20602 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 5)
#define PX4_SPIDEV_MPU2 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 6)
/**
* Onboard MS5611 and FRAM are both on bus SPI2.
@ -190,12 +169,6 @@
#define PX4_I2C_BUS_EXPANSION 1
#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION
/**
* Devices on the external bus.
* Note that these are unshifted addresses.
*/
#define PX4_I2C_OBDEV_BMP280 0x76
/**
* ADC channels:
* These are the channel numbers of the ADCs of the microcontroller that can be used by the Px4 Firmware in the adc driver.

View File

@ -324,7 +324,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
SPI_SETFREQUENCY(spi1, 10000000);
SPI_SETBITS(spi1, 8);
SPI_SETMODE(spi1, SPIDEV_MODE3);
SPI_SELECT(spi1, PX4_SPIDEV_GYRO, false);
SPI_SELECT(spi1, PX4_SPIDEV_HMC, false);
SPI_SELECT(spi1, PX4_SPIDEV_MPU, false);
up_udelay(20);

View File

@ -131,7 +131,6 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool s
/* Shared PC2 CS devices */
case PX4_SPIDEV_BMI:
case PX4_SPIDEV_MPU:
/* Making sure the other peripherals are not selected */
px4_arch_gpiowrite(GPIO_SPI1_CS_PORTC_PIN2, !selected);
@ -141,10 +140,8 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool s
/* Shared PC15 CS devices */
case PX4_SPIDEV_ICM:
case PX4_SPIDEV_ICM_20602:
case PX4_SPIDEV_ICM_20608:
case PX4_SPIDEV_BMI055_ACC:
case PX4_SPIDEV_MPU2:
/* Making sure the other peripherals are not selected */
px4_arch_gpiowrite(GPIO_SPI1_CS_PORTC_PIN2, 1);
@ -156,7 +153,6 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool s
case PX4_SPIDEV_HMC:
case PX4_SPIDEV_LIS:
case PX4_SPIDEV_BMI055_GYR:
/* Making sure the other peripherals are not selected */
px4_arch_gpiowrite(GPIO_SPI1_CS_PORTC_PIN2, 1);
px4_arch_gpiowrite(GPIO_SPI1_CS_PORTC_PIN15, 1);

View File

@ -23,9 +23,12 @@ px4_add_board(
camera_trigger
differential_pressure # all available differential pressure drivers
distance_sensor # all available distance sensor drivers
dshot
gps
heater
imu # all available imu drivers
#imu # all available imu drivers
imu/mpu6000
imu/mpu9250
irlock
lights/blinkm
lights/rgbled
@ -46,7 +49,9 @@ px4_add_board(
#uavcan
MODULES
airspeed_selector
attitude_estimator_q
battery_status
camera_feedback
commander
dataman
@ -54,7 +59,6 @@ px4_add_board(
events
fw_att_control
fw_pos_control_l1
rover_pos_control
land_detector
landing_target_estimator
load_mon
@ -64,12 +68,11 @@ px4_add_board(
mc_att_control
mc_pos_control
navigator
battery_status
rover_pos_control
sensors
sih
vmount
vtol_att_control
airspeed_selector
SYSTEMCMDS
bl_update

View File

@ -158,9 +158,7 @@ MPU6000_SPI_interface(int bus, int device_type, bool external_bus)
break;
case MPU_DEVICE_TYPE_ICM20608:
#if defined(PX4_SPIDEV_ICM)
cs = PX4_SPIDEV_ICM;
#elif defined(PX4_SPIDEV_ICM_20608)
#if defined(PX4_SPIDEV_ICM_20608)
cs = PX4_SPIDEV_ICM_20608;
#endif
break;