Browse Source

AP_NavEKF_Source: remove defaults for baro and compass

This makes all our defaults "NONE", meaning that a user will not see a
prearm failure for any source other than those in the primary set when
using the default configuration.
zr-v5.1
Peter Barker 4 years ago committed by Peter Barker
parent
commit
fdbffd19c6
  1. 4
      libraries/AP_NavEKF/AP_NavEKF_Source.cpp

4
libraries/AP_NavEKF/AP_NavEKF_Source.cpp

@ -90,7 +90,7 @@ const AP_Param::GroupInfo AP_NavEKF_Source::var_info[] = { @@ -90,7 +90,7 @@ const AP_Param::GroupInfo AP_NavEKF_Source::var_info[] = {
// @Description: Yaw Source (Secondary)
// @Values: 0:None, 1:Compass, 2:External, 3:External with Compass Fallback
// @User: Advanced
AP_GROUPINFO("2_YAW", 10, AP_NavEKF_Source, _source_set[1].yaw, (int8_t)AP_NavEKF_Source::SourceYaw::COMPASS),
AP_GROUPINFO("2_YAW", 10, AP_NavEKF_Source, _source_set[1].yaw, (int8_t)AP_NavEKF_Source::SourceYaw::NONE),
#endif
#if AP_NAKEKF_SOURCE_SET_MAX >= 3
@ -127,7 +127,7 @@ const AP_Param::GroupInfo AP_NavEKF_Source::var_info[] = { @@ -127,7 +127,7 @@ const AP_Param::GroupInfo AP_NavEKF_Source::var_info[] = {
// @Description: Yaw Source (Tertiary)
// @Values: 0:None, 1:Compass, 2:External, 3:External with Compass Fallback
// @User: Advanced
AP_GROUPINFO("3_YAW", 15, AP_NavEKF_Source, _source_set[2].yaw, (int8_t)AP_NavEKF_Source::SourceYaw::COMPASS),
AP_GROUPINFO("3_YAW", 15, AP_NavEKF_Source, _source_set[2].yaw, (int8_t)AP_NavEKF_Source::SourceYaw::NONE),
#endif
// @Param: _OPTIONS

Loading…
Cancel
Save