Files
bizhang_-obav/ROMFS/px4fmu_common/init.d/rc.sensors

190 lines
2.3 KiB
Plaintext
Raw Normal View History

#!nsh
#
2015-02-09 13:57:04 +01:00
# Standard startup script for PX4FMU v1, v2, v3 onboard sensor drivers.
#
2015-11-22 12:33:01 +01:00
if ver hwcmp PX4FMU_V1
then
2015-11-22 12:33:01 +01:00
if ms5611 start
then
fi
else
# Configure all I2C buses to 100 KHz as they
# are all external or slow
fmu i2c 1 100000
fmu i2c 2 100000
2015-11-22 12:33:01 +01:00
if ms5611 -s start
then
fi
# Blacksheep telemetry
if bst start
then
fi
fi
if adc start
then
fi
2015-02-09 13:57:04 +01:00
if ver hwcmp PX4FMU_V2
then
# External I2C bus
if hmc5883 -C -T -X start
2015-02-09 13:57:04 +01:00
then
fi
# Internal I2C bus
if hmc5883 -C -T -I -R 4 start
2015-02-09 13:57:04 +01:00
then
fi
2015-02-09 13:57:04 +01:00
# external MPU6K is rotated 180 degrees yaw
if mpu6000 -X -R 4 start
then
2015-02-09 13:57:04 +01:00
set BOARD_FMUV3 true
else
set BOARD_FMUV3 false
fi
2015-02-09 13:57:04 +01:00
if [ $BOARD_FMUV3 == true ]
then
2015-02-09 13:57:04 +01:00
# external L3GD20H is rotated 180 degrees yaw
if l3gd20 -X -R 4 start
then
fi
# external LSM303D is rotated 270 degrees yaw
if lsm303d -X -R 6 start
then
fi
2015-02-09 13:57:04 +01:00
# internal MPU6000 is rotated 180 deg roll, 270 deg yaw
if mpu6000 -R 14 start
then
fi
if hmc5883 -C -T -S -R 8 start
then
fi
else
2015-02-09 13:57:04 +01:00
# FMUv2
if mpu6000 start
then
fi
2015-02-09 13:57:04 +01:00
if l3gd20 start
then
fi
if lsm303d start
then
fi
fi
2016-03-30 10:27:39 +08:00
fi
if ver hwcmp PX4FMU_V4
then
# External I2C bus
if hmc5883 -C -T -X start
then
2016-03-30 10:27:39 +08:00
fi
2016-03-30 10:27:39 +08:00
# Internal SPI bus is rotated 90 deg yaw
if hmc5883 -C -T -S -R 2 start
then
fi
2014-10-15 16:33:46 +02:00
2016-03-30 10:27:39 +08:00
# Internal SPI bus ICM-20608-G is rotated 90 deg yaw
if mpu6000 -R 2 -T 20608 start
then
fi
# Internal SPI bus mpu9250 is rotated 90 deg yaw
if mpu9250 -R 2 start
then
fi
fi
if ver hwcmp PX4FMU_V1
then
# FMUv1
if mpu6000 start
then
fi
if l3gd20 start
then
fi
2015-11-18 09:20:40 -10:00
2016-03-30 10:27:39 +08:00
# MAG selection
if param compare SENS_EXT_MAG 2
then
if hmc5883 -C -I start
2015-02-09 13:57:04 +01:00
then
fi
else
2016-03-30 10:27:39 +08:00
# Use only external as primary
if param compare SENS_EXT_MAG 1
2015-11-18 09:20:40 -10:00
then
2016-03-30 10:27:39 +08:00
if hmc5883 -C -X start
then
fi
2016-03-30 10:27:39 +08:00
else
# auto-detect the primary, prefer external
if hmc5883 start
then
fi
2016-03-30 10:27:39 +08:00
fi
fi
fi
2015-11-18 09:20:40 -10:00
2016-03-30 10:27:39 +08:00
if ver hwcmp MINDPX_V2
then
if mpu6500 start
then
fi
2016-03-30 10:27:39 +08:00
if lsm303d start
then
fi
2016-03-30 10:27:39 +08:00
if l3gd20 start
then
fi
2016-03-30 10:27:39 +08:00
# External I2C bus
if hmc5883 -C -T -X start
then
2014-10-15 16:33:46 +02:00
fi
fi
if meas_airspeed start
then
else
if ets_airspeed start
then
else
if ets_airspeed start -b 1
then
else
if [ $BOARD_FMUV3 == true ]
then
meas_airspeed start -b 2
fi
fi
fi
fi
2016-01-15 14:27:14 +01:00
if sf10a start
then
fi
2015-09-07 15:43:43 +02:00
# Wait 20 ms for sensors (because we need to wait for the HRT and work queue callbacks to fire)
usleep 20000
if sensors start
then
fi