mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
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.
This commit is contained in:
parent
8124c3fea8
commit
fdbffd19c6
@ -90,7 +90,7 @@ const AP_Param::GroupInfo AP_NavEKF_Source::var_info[] = {
|
|||||||
// @Description: Yaw Source (Secondary)
|
// @Description: Yaw Source (Secondary)
|
||||||
// @Values: 0:None, 1:Compass, 2:External, 3:External with Compass Fallback
|
// @Values: 0:None, 1:Compass, 2:External, 3:External with Compass Fallback
|
||||||
// @User: Advanced
|
// @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
|
#endif
|
||||||
|
|
||||||
#if AP_NAKEKF_SOURCE_SET_MAX >= 3
|
#if AP_NAKEKF_SOURCE_SET_MAX >= 3
|
||||||
@ -127,7 +127,7 @@ const AP_Param::GroupInfo AP_NavEKF_Source::var_info[] = {
|
|||||||
// @Description: Yaw Source (Tertiary)
|
// @Description: Yaw Source (Tertiary)
|
||||||
// @Values: 0:None, 1:Compass, 2:External, 3:External with Compass Fallback
|
// @Values: 0:None, 1:Compass, 2:External, 3:External with Compass Fallback
|
||||||
// @User: Advanced
|
// @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
|
#endif
|
||||||
|
|
||||||
// @Param: _OPTIONS
|
// @Param: _OPTIONS
|
||||||
|
Loading…
Reference in New Issue
Block a user