mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_NavEKF: source returns YawSource None if COMPASS_USE all zero
This commit is contained in:
parent
dfd1c23cd3
commit
4998b536b4
@ -213,6 +213,17 @@ bool AP_NavEKF_Source::haveVelZSource() const
|
||||
return false;
|
||||
}
|
||||
|
||||
// get yaw source
|
||||
AP_NavEKF_Source::SourceYaw AP_NavEKF_Source::getYawSource() const
|
||||
{
|
||||
// check for special case of disabled compasses
|
||||
if ((_source_set[active_source_set].yaw == SourceYaw::COMPASS) && (AP::dal().compass().get_num_enabled() == 0)) {
|
||||
return SourceYaw::NONE;
|
||||
}
|
||||
|
||||
return _source_set[active_source_set].yaw;
|
||||
}
|
||||
|
||||
// align position of inactive sources to ahrs
|
||||
void AP_NavEKF_Source::align_inactive_sources()
|
||||
{
|
||||
|
@ -71,7 +71,7 @@ public:
|
||||
bool haveVelZSource() const;
|
||||
|
||||
// get yaw source
|
||||
SourceYaw getYawSource() const { return _source_set[active_source_set].yaw; }
|
||||
SourceYaw getYawSource() const;
|
||||
|
||||
// align position of inactive sources to ahrs
|
||||
void align_inactive_sources();
|
||||
|
Loading…
Reference in New Issue
Block a user