2013-04-26 20:14:32 -03:00
|
|
|
#!nsh
|
|
|
|
#
|
2016-03-19 03:27:09 -03:00
|
|
|
# Standard startup script for PX4FMU v1, v2, v3, v4 onboard sensor drivers.
|
2013-04-26 20:14:32 -03:00
|
|
|
#
|
|
|
|
|
2015-11-22 07:33:01 -04:00
|
|
|
if ver hwcmp PX4FMU_V1
|
2015-05-10 05:21:16 -03:00
|
|
|
then
|
2015-11-22 07:33:01 -04:00
|
|
|
if ms5611 start
|
|
|
|
then
|
|
|
|
fi
|
2016-08-20 22:04:42 -03:00
|
|
|
|
2015-11-22 07:33:01 -04:00
|
|
|
else
|
2016-11-08 16:58:32 -04:00
|
|
|
if ver hwcmp AEROFC_V1
|
|
|
|
then
|
2016-12-04 00:53:50 -04:00
|
|
|
# Aero FC uses separate driver
|
2016-11-08 16:58:32 -04:00
|
|
|
else
|
2016-12-04 00:53:50 -04:00
|
|
|
if ver hwcmp CRAZYFLIE
|
|
|
|
then
|
|
|
|
# Crazyflie uses separate driver
|
|
|
|
else
|
|
|
|
# Configure all I2C buses to 100 KHz as they
|
|
|
|
# are all external or slow
|
|
|
|
fmu i2c 1 100000
|
|
|
|
fmu i2c 2 100000
|
|
|
|
fi
|
|
|
|
|
|
|
|
if ver hwcmp PX4FMU_V4
|
|
|
|
then
|
|
|
|
# We know there are sketchy boards out there
|
|
|
|
# as chinese companies produce Pixracers without
|
|
|
|
# fully understanding the critical parts of the
|
|
|
|
# schematic and BOM, leading to sensor brownouts
|
|
|
|
# on boot. Original Pixracers following the
|
|
|
|
# open hardware design do not require this.
|
|
|
|
fmu sensor_reset 50
|
|
|
|
fi
|
|
|
|
|
|
|
|
# External SPI
|
|
|
|
if ms5611 -S start
|
|
|
|
then
|
|
|
|
fi
|
|
|
|
|
|
|
|
# Internal SPI
|
|
|
|
if ms5611 -s start
|
|
|
|
then
|
|
|
|
fi
|
|
|
|
|
|
|
|
# Blacksheep telemetry
|
|
|
|
if bst start
|
|
|
|
then
|
|
|
|
fi
|
2016-11-08 16:58:32 -04:00
|
|
|
fi
|
2015-05-10 05:21:16 -03:00
|
|
|
fi
|
|
|
|
|
|
|
|
if adc start
|
|
|
|
then
|
|
|
|
fi
|
2013-04-26 20:14:32 -03:00
|
|
|
|
2016-11-23 21:20:23 -04:00
|
|
|
if ver hwcmp AUAV_X21
|
|
|
|
then
|
|
|
|
# I2C bus
|
|
|
|
if hmc5883 -C -T start
|
|
|
|
then
|
|
|
|
fi
|
|
|
|
|
|
|
|
# I2C bus
|
|
|
|
if lis3mdl start
|
|
|
|
then
|
|
|
|
fi
|
|
|
|
|
|
|
|
# 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
|
|
|
|
|
2015-02-09 08:57:04 -04:00
|
|
|
if ver hwcmp PX4FMU_V2
|
2014-07-16 10:02:25 -03:00
|
|
|
then
|
2015-02-09 09:50:26 -04:00
|
|
|
# External I2C bus
|
2015-04-10 19:59:58 -03:00
|
|
|
if hmc5883 -C -T -X start
|
2015-02-09 08:57:04 -04:00
|
|
|
then
|
|
|
|
fi
|
2014-07-16 10:02:25 -03:00
|
|
|
|
2016-03-19 03:27:09 -03:00
|
|
|
# External I2C bus
|
|
|
|
if lis3mdl -X start
|
|
|
|
then
|
|
|
|
fi
|
|
|
|
|
2015-02-09 09:50:26 -04:00
|
|
|
# Internal I2C bus
|
2015-04-10 19:59:58 -03:00
|
|
|
if hmc5883 -C -T -I -R 4 start
|
2015-02-09 08:57:04 -04:00
|
|
|
then
|
|
|
|
fi
|
2013-12-15 14:35:23 -04:00
|
|
|
|
2016-08-18 16:02:48 -03:00
|
|
|
# Internal SPI bus ICM-20608-G
|
|
|
|
if mpu6000 -T 20608 start
|
|
|
|
then
|
|
|
|
fi
|
|
|
|
|
2015-02-09 08:57:04 -04:00
|
|
|
# external MPU6K is rotated 180 degrees yaw
|
|
|
|
if mpu6000 -X -R 4 start
|
2014-07-16 06:26:32 -03:00
|
|
|
then
|
2015-02-09 08:57:04 -04:00
|
|
|
set BOARD_FMUV3 true
|
|
|
|
else
|
2016-11-12 07:57:33 -04:00
|
|
|
# Check for Pixhawk 2 board
|
|
|
|
if mpu9250 -S -R 4 start
|
|
|
|
then
|
|
|
|
set BOARD_FMUV3 true
|
|
|
|
else
|
|
|
|
set BOARD_FMUV3 false
|
|
|
|
fi
|
2014-07-16 06:26:32 -03:00
|
|
|
fi
|
2015-02-09 08:57:04 -04:00
|
|
|
|
|
|
|
if [ $BOARD_FMUV3 == true ]
|
2014-07-16 06:26:32 -03:00
|
|
|
then
|
2016-12-04 07:15:16 -04:00
|
|
|
# sensor heating is available, but we disable it for now
|
|
|
|
param set SENS_EN_THERMAL 0
|
|
|
|
|
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
|
2014-07-16 09:58:43 -03:00
|
|
|
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
|
2016-11-12 07:57:33 -04:00
|
|
|
else
|
|
|
|
if mpu9250 -R 14 start
|
|
|
|
then
|
|
|
|
fi
|
2015-02-09 08:57:04 -04:00
|
|
|
fi
|
|
|
|
|
2015-04-10 19:59:58 -03:00
|
|
|
if hmc5883 -C -T -S -R 8 start
|
2015-02-09 09:50:26 -04:00
|
|
|
then
|
|
|
|
fi
|
|
|
|
|
2016-03-30 14:45:12 -03:00
|
|
|
if meas_airspeed start -b 2
|
|
|
|
then
|
|
|
|
fi
|
|
|
|
|
2014-07-16 09:58:43 -03:00
|
|
|
else
|
2015-02-09 08:57:04 -04:00
|
|
|
# FMUv2
|
|
|
|
if mpu6000 start
|
2014-07-16 06:26:32 -03:00
|
|
|
then
|
|
|
|
fi
|
2014-07-16 09:58:43 -03:00
|
|
|
|
2016-08-23 14:51:57 -03:00
|
|
|
if mpu9250 start
|
|
|
|
then
|
|
|
|
fi
|
|
|
|
|
2015-02-09 08:57:04 -04:00
|
|
|
if l3gd20 start
|
|
|
|
then
|
|
|
|
fi
|
|
|
|
|
|
|
|
if lsm303d start
|
|
|
|
then
|
|
|
|
fi
|
|
|
|
fi
|
2016-03-29 23:27:39 -03:00
|
|
|
fi
|
|
|
|
|
|
|
|
if ver hwcmp PX4FMU_V4
|
|
|
|
then
|
|
|
|
# External I2C bus
|
|
|
|
if hmc5883 -C -T -X start
|
2014-07-16 10:02:25 -03:00
|
|
|
then
|
2016-03-29 23:27:39 -03:00
|
|
|
fi
|
2014-07-16 10:02:25 -03:00
|
|
|
|
2016-03-19 03:27:09 -03:00
|
|
|
if lis3mdl -R 2 start
|
|
|
|
then
|
|
|
|
fi
|
|
|
|
|
2016-03-29 23:27:39 -03:00
|
|
|
# Internal SPI bus is rotated 90 deg yaw
|
|
|
|
if hmc5883 -C -T -S -R 2 start
|
|
|
|
then
|
|
|
|
fi
|
2014-10-15 11:33:46 -03:00
|
|
|
|
2016-03-29 23:27:39 -03:00
|
|
|
# Internal SPI bus ICM-20608-G is rotated 90 deg yaw
|
|
|
|
if mpu6000 -R 2 -T 20608 start
|
|
|
|
then
|
|
|
|
fi
|
|
|
|
|
2016-12-02 05:03:07 -04:00
|
|
|
# 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.
|
|
|
|
|
2016-03-29 23:27:39 -03:00
|
|
|
# Internal SPI bus mpu9250 is rotated 90 deg yaw
|
|
|
|
if mpu9250 -R 2 start
|
|
|
|
then
|
|
|
|
fi
|
2016-12-01 13:45:26 -04:00
|
|
|
|
|
|
|
# Internal SPI bus BMI160
|
|
|
|
if bmi160 start
|
|
|
|
then
|
|
|
|
fi
|
2016-03-29 23:27:39 -03:00
|
|
|
fi
|
|
|
|
|
|
|
|
if ver hwcmp PX4FMU_V1
|
|
|
|
then
|
|
|
|
# FMUv1
|
|
|
|
if mpu6000 start
|
|
|
|
then
|
|
|
|
fi
|
|
|
|
|
|
|
|
if l3gd20 start
|
|
|
|
then
|
|
|
|
fi
|
2015-11-18 15:20:40 -04:00
|
|
|
|
2016-03-29 23:27:39 -03:00
|
|
|
# MAG selection
|
|
|
|
if param compare SENS_EXT_MAG 2
|
|
|
|
then
|
|
|
|
if hmc5883 -C -I start
|
2015-02-09 08:57:04 -04:00
|
|
|
then
|
|
|
|
fi
|
|
|
|
else
|
2016-03-29 23:27:39 -03:00
|
|
|
# Use only external as primary
|
|
|
|
if param compare SENS_EXT_MAG 1
|
2015-11-18 15:20:40 -04:00
|
|
|
then
|
2016-03-29 23:27:39 -03:00
|
|
|
if hmc5883 -C -X start
|
2016-03-12 00:50:14 -04:00
|
|
|
then
|
|
|
|
fi
|
2016-03-29 23:27:39 -03:00
|
|
|
else
|
|
|
|
# auto-detect the primary, prefer external
|
|
|
|
if hmc5883 start
|
2016-03-12 00:50:14 -04:00
|
|
|
then
|
|
|
|
fi
|
2016-03-29 23:27:39 -03:00
|
|
|
fi
|
|
|
|
fi
|
|
|
|
fi
|
2015-11-18 15:20:40 -04:00
|
|
|
|
2016-03-29 23:27:39 -03:00
|
|
|
if ver hwcmp MINDPX_V2
|
|
|
|
then
|
2016-08-17 04:37:19 -03:00
|
|
|
# External I2C bus
|
|
|
|
if hmc5883 -C -T -X start
|
2016-03-29 23:27:39 -03:00
|
|
|
then
|
|
|
|
fi
|
2016-03-12 00:50:14 -04:00
|
|
|
|
2016-08-17 04:37:19 -03:00
|
|
|
# Internal I2C bus
|
|
|
|
if hmc5883 -C -T -I -R 8 start
|
2016-03-29 23:27:39 -03:00
|
|
|
then
|
|
|
|
fi
|
2016-03-12 00:50:14 -04:00
|
|
|
|
2016-08-17 04:37:19 -03:00
|
|
|
if mpu6500 -R 8 start
|
2016-03-29 23:27:39 -03:00
|
|
|
then
|
|
|
|
fi
|
2016-03-12 00:50:14 -04:00
|
|
|
|
2016-08-17 04:37:19 -03:00
|
|
|
if lsm303d -R 10 start
|
2016-03-29 23:27:39 -03:00
|
|
|
then
|
2014-10-15 11:33:46 -03:00
|
|
|
fi
|
2016-03-19 03:27:09 -03:00
|
|
|
|
2016-08-17 04:37:19 -03:00
|
|
|
if l3gd20 -R 14 start
|
2016-03-19 03:27:09 -03:00
|
|
|
then
|
|
|
|
fi
|
2013-04-26 20:14:32 -03:00
|
|
|
fi
|
|
|
|
|
2016-08-20 22:04:42 -03:00
|
|
|
if ver hwcmp CRAZYFLIE
|
|
|
|
then
|
|
|
|
# Onboard I2C
|
|
|
|
if mpu9250 -R 12 start
|
|
|
|
then
|
|
|
|
fi
|
|
|
|
|
|
|
|
# I2C bypass of mpu
|
|
|
|
if lps25h start
|
|
|
|
then
|
|
|
|
fi
|
|
|
|
fi
|
|
|
|
|
2016-09-12 21:10:55 -03:00
|
|
|
if ver hwcmp AEROFC_V1
|
|
|
|
then
|
|
|
|
if ms5611 start
|
|
|
|
then
|
|
|
|
fi
|
|
|
|
|
2016-09-27 17:34:20 -03:00
|
|
|
if mpu6500 -R 14 start
|
2016-09-12 21:10:55 -03:00
|
|
|
then
|
|
|
|
fi
|
|
|
|
|
2016-10-25 11:34:18 -03:00
|
|
|
# Internal compass
|
2016-10-10 18:39:55 -03:00
|
|
|
if hmc5883 -I -R 4 start
|
|
|
|
then
|
|
|
|
fi
|
|
|
|
|
2016-10-25 11:34:18 -03:00
|
|
|
# Possible external compasses
|
2016-10-10 18:39:55 -03:00
|
|
|
if hmc5883 -X start
|
2016-09-12 21:10:55 -03:00
|
|
|
then
|
|
|
|
fi
|
2016-10-25 11:34:18 -03:00
|
|
|
|
|
|
|
if ist8310 -C -b 1 -R 8 start
|
|
|
|
then
|
|
|
|
fi
|
2016-09-12 21:10:55 -03:00
|
|
|
fi
|
|
|
|
|
2013-09-29 09:07:01 -03:00
|
|
|
if meas_airspeed start
|
|
|
|
then
|
|
|
|
else
|
|
|
|
if ets_airspeed start
|
|
|
|
then
|
|
|
|
else
|
|
|
|
if ets_airspeed start -b 1
|
|
|
|
then
|
|
|
|
fi
|
|
|
|
fi
|
|
|
|
fi
|
|
|
|
|
2016-07-28 15:22:00 -03:00
|
|
|
if sf1xx start
|
2016-01-15 09:27:14 -04:00
|
|
|
then
|
|
|
|
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
|
2015-10-11 10:43:17 -03:00
|
|
|
if sensors start
|
|
|
|
then
|
|
|
|
fi
|