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

124 lines
1.5 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.
#
ms5611 start
adc start
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
else
# FMUv1
if mpu6000 start
then
fi
2015-02-09 13:57:04 +01:00
if l3gd20 start
then
fi
2014-10-15 16:33:46 +02:00
2015-02-09 13:57:04 +01:00
# MAG selection
if param compare SENS_EXT_MAG 2
2014-10-15 16:33:46 +02:00
then
2015-02-09 13:57:04 +01:00
if hmc5883 -C -I start
then
fi
else
# Use only external as primary
if param compare SENS_EXT_MAG 1
then
if hmc5883 -C -X start
then
fi
else
# auto-detect the primary, prefer external
if hmc5883 start
then
fi
fi
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
fi
fi
fi
# Check for flow sensor
if px4flow start
then
fi
2014-12-14 11:37:12 +01:00
if ll40ls start
then
fi
#
2014-11-15 16:19:51 +01:00
# Start sensors -> preflight_check
#
if sensors start
then
2013-07-18 15:26:14 +02:00
preflight_check &
fi