mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
PX4: make compass calibrate fail non-fatal
until we sort out what is going on with compass calibration failures this is the best option
This commit is contained in:
parent
a26bcddb9b
commit
11956ece7c
@ -198,7 +198,7 @@ then
|
|||||||
else
|
else
|
||||||
echo "hmc5883 calibrate failed"
|
echo "hmc5883 calibrate failed"
|
||||||
echo "hmc5883 calibrate failed" >> $logfile
|
echo "hmc5883 calibrate failed" >> $logfile
|
||||||
sh /etc/init.d/rc.error
|
tone_alarm MSBBB
|
||||||
fi
|
fi
|
||||||
else
|
else
|
||||||
echo "hmc5883 start failed"
|
echo "hmc5883 start failed"
|
||||||
@ -229,7 +229,7 @@ else
|
|||||||
else
|
else
|
||||||
echo "hmc5883 calibrate failed"
|
echo "hmc5883 calibrate failed"
|
||||||
echo "hmc5883 calibrate failed" >> $logfile
|
echo "hmc5883 calibrate failed" >> $logfile
|
||||||
sh /etc/init.d/rc.error
|
tone_alarm MSBBB
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user