mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: rename EKF_POS_SOURCE to EKF_SOURCE_SET
Co-authored-by: Michelle Rossouw <michelleros128@gmail.com> these data sources span more than just position
This commit is contained in:
parent
27b202e984
commit
6d8f0decac
|
@ -670,7 +670,7 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos
|
||||||
case AUX_FUNC::GENERATOR: // don't turn generator on or off initially
|
case AUX_FUNC::GENERATOR: // don't turn generator on or off initially
|
||||||
#endif
|
#endif
|
||||||
#if AP_AHRS_ENABLED
|
#if AP_AHRS_ENABLED
|
||||||
case AUX_FUNC::EKF_POS_SOURCE:
|
case AUX_FUNC::EKF_SOURCE_SET:
|
||||||
#endif
|
#endif
|
||||||
#if HAL_TORQEEDO_ENABLED
|
#if HAL_TORQEEDO_ENABLED
|
||||||
case AUX_FUNC::TORQEEDO_CLEAR_ERR:
|
case AUX_FUNC::TORQEEDO_CLEAR_ERR:
|
||||||
|
@ -1626,7 +1626,7 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
case AUX_FUNC::EKF_POS_SOURCE: {
|
case AUX_FUNC::EKF_SOURCE_SET: {
|
||||||
AP_NavEKF_Source::SourceSetSelection source_set = AP_NavEKF_Source::SourceSetSelection::PRIMARY;
|
AP_NavEKF_Source::SourceSetSelection source_set = AP_NavEKF_Source::SourceSetSelection::PRIMARY;
|
||||||
switch (ch_flag) {
|
switch (ch_flag) {
|
||||||
case AuxSwitchPos::LOW:
|
case AuxSwitchPos::LOW:
|
||||||
|
|
|
@ -191,7 +191,7 @@ public:
|
||||||
CROW_SELECT = 87, // select CROW mode for diff spoilers;high disables,mid forces progressive
|
CROW_SELECT = 87, // select CROW mode for diff spoilers;high disables,mid forces progressive
|
||||||
SOARING = 88, // three-position switch to set soaring mode
|
SOARING = 88, // three-position switch to set soaring mode
|
||||||
LANDING_FLARE = 89, // force flare, throttle forced idle, pitch to LAND_PITCH_DEG, tilts up
|
LANDING_FLARE = 89, // force flare, throttle forced idle, pitch to LAND_PITCH_DEG, tilts up
|
||||||
EKF_POS_SOURCE = 90, // change EKF position source between primary, secondary and tertiary sources
|
EKF_SOURCE_SET = 90, // change EKF data source set between primary, secondary and tertiary
|
||||||
ARSPD_CALIBRATE= 91, // calibrate airspeed ratio
|
ARSPD_CALIBRATE= 91, // calibrate airspeed ratio
|
||||||
FBWA = 92, // Fly-By-Wire-A
|
FBWA = 92, // Fly-By-Wire-A
|
||||||
RELOCATE_MISSION = 93, // used in separate branch MISSION_RELATIVE
|
RELOCATE_MISSION = 93, // used in separate branch MISSION_RELATIVE
|
||||||
|
|
Loading…
Reference in New Issue