Compass: use_for_yaw to use primary compass health

This allows the internal compass to be used if the external compass
fails.
This commit is contained in:
Randy Mackay 2014-09-18 15:19:55 +09:00 committed by Andrew Tridgell
parent d6c56b8f7a
commit 84d792216e

View File

@ -152,7 +152,7 @@ public:
/// return true if the compass should be used for yaw calculations
bool use_for_yaw(void) const {
return _healthy[0] && _use_for_yaw;
return healthy() && _use_for_yaw;
}
/// Sets the local magnetic field declination.