mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 18:23:57 -04:00
PX4: run hmc5883 compass calibration on every boot
this gives us more consistent compass readings between boots
This commit is contained in:
parent
54562b0b9a
commit
02c98f901d
@ -192,7 +192,17 @@ then
|
|||||||
if hmc5883 start
|
if hmc5883 start
|
||||||
then
|
then
|
||||||
echo "hmc5883 started OK"
|
echo "hmc5883 started OK"
|
||||||
|
if hmc5883 calibrate
|
||||||
|
then
|
||||||
|
echo "hmc5883 calibrate OK"
|
||||||
|
else
|
||||||
|
echo "hmc5883 calibrate failed"
|
||||||
|
echo "hmc5883 calibrate failed" >> $logfile
|
||||||
|
sh /etc/init.d/rc.error
|
||||||
|
fi
|
||||||
else
|
else
|
||||||
|
echo "hmc5883 start failed"
|
||||||
|
echo "hmc5883 start failed" >> $logfile
|
||||||
sh /etc/init.d/rc.error
|
sh /etc/init.d/rc.error
|
||||||
fi
|
fi
|
||||||
if mpu6000 start
|
if mpu6000 start
|
||||||
@ -213,7 +223,16 @@ else
|
|||||||
if hmc5883 start
|
if hmc5883 start
|
||||||
then
|
then
|
||||||
echo "Using external magnetometer"
|
echo "Using external magnetometer"
|
||||||
|
if hmc5883 calibrate
|
||||||
|
then
|
||||||
|
echo "hmc5883 calibrate OK"
|
||||||
|
else
|
||||||
|
echo "hmc5883 calibrate failed"
|
||||||
|
echo "hmc5883 calibrate failed" >> $logfile
|
||||||
|
sh /etc/init.d/rc.error
|
||||||
|
fi
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if mpu6000 start
|
if mpu6000 start
|
||||||
then
|
then
|
||||||
echo "Found MPU6000"
|
echo "Found MPU6000"
|
||||||
|
Loading…
Reference in New Issue
Block a user