mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF: Allow EK3_SRCx_POSZ to be set to 0 (NONE)
This commit is contained in:
parent
276578c509
commit
b05919ea88
|
@ -385,6 +385,7 @@ bool AP_NavEKF_Source::pre_arm_check(bool requires_position, char *failure_msg,
|
|||
visualodom_required = true;
|
||||
break;
|
||||
case SourceZ::NONE:
|
||||
break;
|
||||
default:
|
||||
// invalid posz value
|
||||
hal.util->snprintf(failure_msg, failure_msg_len, "Check EK3_SRC%d_POSZ", (int)i+1);
|
||||
|
|
Loading…
Reference in New Issue