px4-firmware/ROMFS/px4fmu_common/init.d/rc.sensors

153 lines
2.0 KiB
Plaintext
Raw Normal View History

#!nsh
#
2015-02-09 08:57:04 -04:00
# Standard startup script for PX4FMU v1, v2, v3 onboard sensor drivers.
#
2015-11-22 07:33:01 -04:00
if ver hwcmp PX4FMU_V1
then
2015-11-22 07:33:01 -04:00
if ms5611 start
then
fi
else
if ms5611 -s start
then
fi
# Blacksheep telemetry
if bst start
then
fi
fi
if adc start
then
fi
2015-02-09 08:57:04 -04:00
if ver hwcmp PX4FMU_V2
then
# External I2C bus
if hmc5883 -C -T -X start
2015-02-09 08:57:04 -04:00
then
fi
# Internal I2C bus
if hmc5883 -C -T -I -R 4 start
2015-02-09 08:57:04 -04:00
then
fi
2015-02-09 08:57:04 -04:00
# external MPU6K is rotated 180 degrees yaw
if mpu6000 -X -R 4 start
then
2015-02-09 08:57:04 -04:00
set BOARD_FMUV3 true
else
set BOARD_FMUV3 false
fi
2015-02-09 08:57:04 -04:00
if [ $BOARD_FMUV3 == true ]
then
2015-02-09 08:57:04 -04: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 08:57:04 -04: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 08:57:04 -04:00
# FMUv2
if mpu6000 start
then
fi
2015-02-09 08:57:04 -04:00
if l3gd20 start
then
fi
if lsm303d start
then
fi
fi
else
2015-11-18 15:20:40 -04:00
if ver hwcmp PX4FMU_V4
then
2015-11-18 15:20:40 -04:00
# External I2C bus
if hmc5883 -C -T -X start
then
fi
2015-11-19 10:53:51 -04:00
# Internal SPI bus is rotated 90 deg yaw
if hmc5883 -C -T -S -R 2 start
2015-11-18 15:20:40 -04:00
then
fi
2014-10-15 11:33:46 -03:00
# Internal SPI bus ICM-20608-G is rotated 90 deg yaw
if mpu6000 -R 2 -T 20608 start
2015-11-18 15:20:40 -04:00
then
fi
# Internal SPI bus mpu9250 is rotated 90 deg yaw
if mpu9250 -R 2 start
2015-02-09 08:57:04 -04:00
then
fi
else
2015-11-18 15:20:40 -04:00
# FMUv1
if mpu6000 start
then
fi
if l3gd20 start
then
fi
# MAG selection
if param compare SENS_EXT_MAG 2
2015-02-09 08:57:04 -04:00
then
2015-11-18 15:20:40 -04:00
if hmc5883 -C -I start
2015-02-09 08:57:04 -04:00
then
fi
else
2015-11-18 15:20:40 -04:00
# Use only external as primary
if param compare SENS_EXT_MAG 1
2015-02-09 08:57:04 -04:00
then
2015-11-18 15:20:40 -04:00
if hmc5883 -C -X start
then
fi
else
# auto-detect the primary, prefer external
if hmc5883 start
then
fi
2015-02-09 08:57:04 -04:00
fi
fi
2014-10-15 11:33:46 -03:00
fi
fi
if meas_airspeed start
then
else
if ets_airspeed start
then
else
if ets_airspeed start -b 1
then
fi
fi
fi
2015-09-07 10:43:43 -03: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