diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index 2832a2e029..4ceee8642e 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -5,9 +5,7 @@ if ver hwcmp PX4FMU_V1 then - if ms5611 start - then - fi + ms5611 start else if ver hwcmp AEROFC_V1 then @@ -35,19 +33,13 @@ else fi # External SPI - if ms5611 -S start - then - fi + ms5611 -S start # Internal SPI - if ms5611 -s start - then - fi + ms5611 -s start # Blacksheep telemetry - if bst start - then - fi + bst start fi fi @@ -55,50 +47,34 @@ if ver hwcmp AEROFC_V1 then # Aero FC uses separate driver else - if adc start - then - fi + adc start fi if ver hwcmp AUAV_X21 then # External I2C bus - if hmc5883 -C -T -X start - then - fi + hmc5883 -C -T -X start # Internal SPI bus ICM-20608-G is rotated 90 deg yaw - if mpu6000 -R 2 -T 20608 start - then - fi + mpu6000 -R 2 -T 20608 start # Internal SPI bus mpu9250 is rotated 90 deg yaw - if mpu9250 -R 2 start - then - fi + mpu9250 -R 2 start fi if ver hwcmp PX4FMU_V2 then # External I2C bus - if hmc5883 -C -T -X start - then - fi + hmc5883 -C -T -X start # External I2C bus - if lis3mdl -X start - then - fi + lis3mdl -X start # Internal I2C bus - if hmc5883 -C -T -I -R 4 start - then - fi + hmc5883 -C -T -I -R 4 start # Internal SPI bus ICM-20608-G - if mpu6000 -T 20608 start - then - fi + mpu6000 -T 20608 start # V2 build hwtypecmp is always false set BOARD_FMUV3 0 @@ -126,41 +102,29 @@ then param set SENS_EN_THERMAL 0 # external L3GD20H is rotated 180 degrees yaw - if l3gd20 -X -R 4 start - then - fi + l3gd20 -X -R 4 start # external LSM303D is rotated 270 degrees yaw - if lsm303d -X -R 6 start - then - fi + lsm303d -X -R 6 start if [ $BOARD_FMUV3 == 20 ] then # v2.0 internal MPU6000 is rotated 180 deg roll, 270 deg yaw - if mpu6000 -R 14 start - then - fi + mpu6000 -R 14 start # v2.0 Has internal hmc5883 on SPI1 - if hmc5883 -C -T -S -R 8 start - then - fi + hmc5883 -C -T -S -R 8 start fi if [ $BOARD_FMUV3 == 21 ] then # v2.1 internal MPU9250 is rotated 180 deg roll, 270 deg yaw - if mpu9250 -R 14 start - then - fi + mpu9250 -R 14 start fi else # $BOARD_FMUV3 == 0 -> FMUv2 - if mpu6000 start - then - fi + mpu6000 start # As we will use the external mag and the ICM-20608-G # V2 build hwtypecmp is always false @@ -169,115 +133,75 @@ then then # On the PixhawkMini the mpu9250 has been disabled due to HW errata else - if mpu9250 start - then - fi + mpu9250 start fi - if l3gd20 start - then - fi - - if lsm303d start - then - fi + l3gd20 start + lsm303d start fi fi if ver hwcmp PX4FMU_V4 then # External I2C bus - if hmc5883 -C -T -X start - then - fi + hmc5883 -C -T -X start - if lis3mdl -R 2 start - then - fi + lis3mdl -R 2 start # Internal SPI bus is rotated 90 deg yaw - if hmc5883 -C -T -S -R 2 start - then - fi + hmc5883 -C -T -S -R 2 start # Internal SPI bus ICM-20608-G is rotated 90 deg yaw - if mpu6000 -R 2 -T 20608 start - then - fi + mpu6000 -R 2 -T 20608 start # Internal SPI bus ICM-20602-G is rotated 90 deg yaw - if mpu6000 -R 2 -T 20602 start - then - fi + mpu6000 -R 2 -T 20602 start # 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. # Internal SPI bus mpu9250 is rotated 90 deg yaw - if mpu9250 -R 2 start - then - fi + mpu9250 -R 2 start # Internal SPI bus BMI160 - if bmi160 start - then - fi + bmi160 start # Start either ICM2060X or BMI055. 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. # Internal SPI bus BMI055_ACC - if bmi055 -A start - then - fi + bmi055 -A start # Internal SPI bus BMI055_GYR - if bmi055 -G start - then - fi + bmi055 -G start # expansion i2c used for BMM150 rotated by 90deg - if bmm150 -R 2 start - then - fi + bmm150 -R 2 start # expansion i2c used for BMP280 - if bmp280 -I start - then - fi + bmp280 -I start fi if ver hwcmp PX4FMU_V1 then # FMUv1 - if mpu6000 start - then - fi - - if l3gd20 start - then - fi + mpu6000 start + l3gd20 start # MAG selection if param compare SENS_EXT_MAG 2 then - if hmc5883 -C -I start - then - fi + hmc5883 -C -I start else # Use only external as primary if param compare SENS_EXT_MAG 1 then - if hmc5883 -C -X start - then - fi + hmc5883 -C -X start else # auto-detect the primary, prefer external - if hmc5883 start - then - fi + hmc5883 start fi fi fi @@ -285,128 +209,75 @@ fi if ver hwcmp MINDPX_V2 then # External I2C bus - if hmc5883 -C -T -X start - then - fi - + hmc5883 -C -T -X start # Internal I2C bus - if hmc5883 -C -T -I -R 12 start - then - fi - - if mpu6000 -s -R 8 start - then - fi - - if mpu9250 -s -R 8 start - then - fi - - if lsm303d -R 10 start - then - fi - - if l3gd20 -R 14 start - then - fi + hmc5883 -C -T -I -R 12 start + mpu6000 -s -R 8 start + mpu9250 -s -R 8 start + lsm303d -R 10 start + l3gd20 -R 14 start fi if ver hwcmp CRAZYFLIE then # Onboard I2C - if mpu9250 -R 12 start - then - fi + mpu9250 -R 12 start # I2C bypass of mpu - if lps25h start - then - fi + lps25h start fi if ver hwcmp AEROFC_V1 then - if ms5611 -T 0 start - then - fi + ms5611 -T 0 start - if mpu9250 -s -R 14 start - then - fi + mpu9250 -s -R 14 start # Possible external compasses - if hmc5883 -X start - then - fi + hmc5883 -X start - if ist8310 -C -b 1 -R 4 start - then - fi + ist8310 -C -b 1 -R 4 start - if aerofc_adc start - then - fi + aerofc_adc start - if ll40ls start i2c - then - fi + ll40ls start i2c fi if ver hwcmp PX4FMU_V4PRO then # Internal SPI bus ICM-20608-G - if mpu6000 -R 2 -T 20608 start - then - fi + mpu6000 -R 2 -T 20608 start # Internal SPI bus ICM-20602 - if mpu6000 -R 2 -T 20602 start - then - fi + mpu6000 -R 2 -T 20602 start # Internal SPI bus mpu9250 - if mpu9250 -R 2 start - then - fi + mpu9250 -R 2 start # Internal SPI bus - if lis3mdl -R 0 start - then - fi + lis3mdl -R 0 start # Possible external compasses - if hmc5883 -C -T -X start - then - fi + hmc5883 -C -T -X start fi if ver hwcmp PX4FMU_V5 then # Internal SPI bus ICM-20602 - if mpu6000 -R 8 -s -T 20602 start - then - fi + mpu6000 -R 8 -s -T 20602 start # Internal SPI bus ICM-20689 - if mpu6000 -R 8 -z -T 20689 start - then - fi + mpu6000 -R 8 -z -T 20689 start # Internal SPI bus BMI055 accel - if bmi055 -A -R 10 start - then - fi + bmi055 -A -R 10 start # Internal SPI bus BMI055 gyro - if bmi055 -G -R 10 start - then - fi + bmi055 -G -R 10 start # Possible external compasses - if hmc5883 -C -T -X start - then - fi + hmc5883 -C -T -X start fi if ver hwcmp AEROCORE2 @@ -419,85 +290,65 @@ fi # Optional drivers # -if sdp3x_airspeed start -then -fi - -if ms5525_airspeed start -then -fi - -if ms5525_airspeed start -b 2 -then -fi +sdp3x_airspeed start +sdp3x_airspeed start -b 2 -if ms4525_airspeed start -then -fi - -if ms4525_airspeed start -b 2 +# Pixhawk 2.1 has a MS5611 on I2C which gets wrongly +# detected as MS5525 because the chip manufacturer was so +# clever to assign the same I2C address and skip a WHO_AM_I +# register. +if [ $BOARD_FMUV3 == 21 ] then + ms5525_airspeed start -b 2 +else + ms5525_airspeed start fi -if ets_airspeed start -then -fi +ms4525_airspeed start +ms4525_airspeed start -b 2 -if ets_airspeed start -b 1 -then -fi +ets_airspeed start +ets_airspeed start -b 1 # Sensors on the PWM interface bank if param compare SENS_EN_LL40LS 1 then if pwm_input start then - if ll40ls start pwm - then - fi + ll40ls start pwm fi fi # Lidar-Lite on I2C if param compare SENS_EN_LL40LS 2 then - if ll40ls start i2c - then - fi + ll40ls start i2c fi # lightware serial lidar sensor if param compare SENS_EN_SF0X 0 then else - if sf0x start - then - fi + sf0x start fi # lightware i2c lidar sensor if param compare SENS_EN_SF1XX 0 then else - if sf1xx start - then - fi + sf1xx start fi # mb12xx sonar sensor if param compare SENS_EN_MB12XX 1 then - if mb12xx start - then - fi + mb12xx start fi # teraranger one tof sensor if param compare SENS_EN_TRONE 1 then - if trone start - then - fi + trone start fi # Wait 20 ms for sensors (because we need to wait for the HRT and work queue callbacks to fire)