mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_NavEKF_Source: set compass_required if we require a compass
This commit is contained in:
parent
9e20f4a68d
commit
8124c3fea8
@ -417,11 +417,13 @@ bool AP_NavEKF_Source::pre_arm_check(char *failure_msg, uint8_t failure_msg_len)
|
||||
// check yaw
|
||||
switch ((SourceYaw)_source_set[i].yaw.get()) {
|
||||
case SourceYaw::NONE:
|
||||
case SourceYaw::COMPASS:
|
||||
case SourceYaw::EXTERNAL:
|
||||
case SourceYaw::EXTERNAL_COMPASS_FALLBACK:
|
||||
// valid yaw value
|
||||
break;
|
||||
case SourceYaw::COMPASS:
|
||||
case SourceYaw::EXTERNAL_COMPASS_FALLBACK:
|
||||
compass_required = true;
|
||||
break;
|
||||
default:
|
||||
// invalid yaw value
|
||||
hal.util->snprintf(failure_msg, failure_msg_len, "Check EK3_SRC%d_YAW", (int)i+1);
|
||||
|
Loading…
Reference in New Issue
Block a user