diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 2722464df5..89ab69a571 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -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 #endif #if AP_AHRS_ENABLED - case AUX_FUNC::EKF_POS_SOURCE: + case AUX_FUNC::EKF_SOURCE_SET: #endif #if HAL_TORQEEDO_ENABLED 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; #endif - case AUX_FUNC::EKF_POS_SOURCE: { + case AUX_FUNC::EKF_SOURCE_SET: { AP_NavEKF_Source::SourceSetSelection source_set = AP_NavEKF_Source::SourceSetSelection::PRIMARY; switch (ch_flag) { case AuxSwitchPos::LOW: diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 6e5c766e05..b999d007ca 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -191,7 +191,7 @@ public: CROW_SELECT = 87, // select CROW mode for diff spoilers;high disables,mid forces progressive SOARING = 88, // three-position switch to set soaring mode 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 FBWA = 92, // Fly-By-Wire-A RELOCATE_MISSION = 93, // used in separate branch MISSION_RELATIVE