|
|
@ -264,9 +264,15 @@ else |
|
|
|
echo "Found MPU6000 external" |
|
|
|
echo "Found MPU6000 external" |
|
|
|
set HAVE_FMUV3 true |
|
|
|
set HAVE_FMUV3 true |
|
|
|
else |
|
|
|
else |
|
|
|
echo "No MPU6000 external" |
|
|
|
if mpu9250 -X -R 4 start |
|
|
|
|
|
|
|
then |
|
|
|
|
|
|
|
echo "Found MPU9250 external" |
|
|
|
|
|
|
|
set HAVE_FMUV3 true |
|
|
|
|
|
|
|
else |
|
|
|
|
|
|
|
echo "No MPU6000 or MPU9250 external" |
|
|
|
set HAVE_FMUV3 false |
|
|
|
set HAVE_FMUV3 false |
|
|
|
fi |
|
|
|
fi |
|
|
|
|
|
|
|
fi |
|
|
|
if [ $HAVE_FMUV3 == true ] |
|
|
|
if [ $HAVE_FMUV3 == true ] |
|
|
|
then |
|
|
|
then |
|
|
|
# external L3GD20 is rotated YAW_180 from standard |
|
|
|
# external L3GD20 is rotated YAW_180 from standard |
|
|
@ -290,10 +296,15 @@ else |
|
|
|
then |
|
|
|
then |
|
|
|
echo "Found MPU6000 internal" |
|
|
|
echo "Found MPU6000 internal" |
|
|
|
else |
|
|
|
else |
|
|
|
echo "No MPU6000" |
|
|
|
if mpu9250 -R 14 start |
|
|
|
echo "No MPU6000" >> $logfile |
|
|
|
then |
|
|
|
|
|
|
|
echo "Found MPU9250 internal" |
|
|
|
|
|
|
|
else |
|
|
|
|
|
|
|
echo "No MPU6000 or MPU9250" |
|
|
|
|
|
|
|
echo "No MPU6000 or MPU9250" >> $logfile |
|
|
|
sh /etc/init.d/rc.error |
|
|
|
sh /etc/init.d/rc.error |
|
|
|
fi |
|
|
|
fi |
|
|
|
|
|
|
|
fi |
|
|
|
if hmc5883 -C -T -S -R 8 start |
|
|
|
if hmc5883 -C -T -S -R 8 start |
|
|
|
then |
|
|
|
then |
|
|
|
echo "Found SPI hmc5883" |
|
|
|
echo "Found SPI hmc5883" |
|
|
@ -303,8 +314,13 @@ else |
|
|
|
then |
|
|
|
then |
|
|
|
echo "Found MPU6000" |
|
|
|
echo "Found MPU6000" |
|
|
|
else |
|
|
|
else |
|
|
|
echo "No MPU6000" |
|
|
|
if mpu9250 start |
|
|
|
echo "No MPU6000" >> $logfile |
|
|
|
then |
|
|
|
|
|
|
|
echo "Found MPU9250" |
|
|
|
|
|
|
|
else |
|
|
|
|
|
|
|
echo "No MPU6000 or MPU9250" |
|
|
|
|
|
|
|
echo "No MPU9250" >> $logfile |
|
|
|
|
|
|
|
fi |
|
|
|
fi |
|
|
|
fi |
|
|
|
if l3gd20 start |
|
|
|
if l3gd20 start |
|
|
|
then |
|
|
|
then |
|
|
|