mirror of https://github.com/ArduPilot/ardupilot
PX4: change IMU order so vib isolated IMUs are 1 and 2
also try to start external ms5611
This commit is contained in:
parent
d57c99f1cc
commit
a9ee2ae253
|
@ -261,15 +261,6 @@ else
|
||||||
fi
|
fi
|
||||||
if [ $HAVE_FMUV3 == true ]
|
if [ $HAVE_FMUV3 == true ]
|
||||||
then
|
then
|
||||||
# internal MPU6000 is rotated ROLL_180_YAW_270 from standard
|
|
||||||
if mpu6000 -R 14 start
|
|
||||||
then
|
|
||||||
echo "Found MPU6000 internal"
|
|
||||||
else
|
|
||||||
echo "No MPU6000"
|
|
||||||
echo "No MPU6000" >> $logfile
|
|
||||||
sh /etc/init.d/rc.error
|
|
||||||
fi
|
|
||||||
# external L3GD20 is rotated YAW_180 from standard
|
# external L3GD20 is rotated YAW_180 from standard
|
||||||
if l3gd20 -X -R 4 start
|
if l3gd20 -X -R 4 start
|
||||||
then
|
then
|
||||||
|
@ -286,6 +277,19 @@ else
|
||||||
echo "No lsm303d"
|
echo "No lsm303d"
|
||||||
sh /etc/init.d/rc.error
|
sh /etc/init.d/rc.error
|
||||||
fi
|
fi
|
||||||
|
# internal MPU6000 is rotated ROLL_180_YAW_270 from standard
|
||||||
|
if mpu6000 -R 14 start
|
||||||
|
then
|
||||||
|
echo "Found MPU6000 internal"
|
||||||
|
else
|
||||||
|
echo "No MPU6000"
|
||||||
|
echo "No MPU6000" >> $logfile
|
||||||
|
sh /etc/init.d/rc.error
|
||||||
|
fi
|
||||||
|
if ms5611 -X start
|
||||||
|
then
|
||||||
|
echo "ms5611 external started OK"
|
||||||
|
fi
|
||||||
else
|
else
|
||||||
if mpu6000 start
|
if mpu6000 start
|
||||||
then
|
then
|
||||||
|
|
Loading…
Reference in New Issue