mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 18:18:49 -04:00
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:
parent
d6c56b8f7a
commit
84d792216e
@ -152,7 +152,7 @@ public:
|
|||||||
|
|
||||||
/// return true if the compass should be used for yaw calculations
|
/// return true if the compass should be used for yaw calculations
|
||||||
bool use_for_yaw(void) const {
|
bool use_for_yaw(void) const {
|
||||||
return _healthy[0] && _use_for_yaw;
|
return healthy() && _use_for_yaw;
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Sets the local magnetic field declination.
|
/// Sets the local magnetic field declination.
|
||||||
|
Loading…
Reference in New Issue
Block a user