mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
RC_Channel: added AUX switch for EKF3 GPS disable
This commit is contained in:
parent
b52d7d9027
commit
3ec68a9c0a
@ -731,6 +731,9 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos
|
||||
#if AP_GRIPPER_ENABLED
|
||||
case AUX_FUNC::GRIPPER:
|
||||
#endif
|
||||
#if HAL_NAVEKF3_AVAILABLE
|
||||
case AUX_FUNC::GPS_DISABLE_EK3:
|
||||
#endif
|
||||
#if AP_INERTIALSENSOR_KILL_IMU_ENABLED
|
||||
case AUX_FUNC::KILL_IMU1:
|
||||
case AUX_FUNC::KILL_IMU2:
|
||||
@ -892,6 +895,9 @@ const RC_Channel::LookupTable RC_Channel::lookuptable[] = {
|
||||
#if HAL_MOUNT_ENABLED
|
||||
{ AUX_FUNC::MOUNT_LRF_ENABLE, "Mount LRF Enable"},
|
||||
#endif
|
||||
#if HAL_NAVEKF3_AVAILABLE
|
||||
{ AUX_FUNC::GPS_DISABLE_EK3,"GPSDisableEK3"},
|
||||
#endif
|
||||
};
|
||||
|
||||
/* lookup the announcement for switch change */
|
||||
@ -1574,6 +1580,12 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch
|
||||
#endif
|
||||
break;
|
||||
|
||||
#if HAL_NAVEKF3_AVAILABLE
|
||||
case AUX_FUNC::GPS_DISABLE_EK3:
|
||||
AP::ahrs().gps_disable_ek3(ch_flag == AuxSwitchPos::HIGH);
|
||||
break;
|
||||
#endif
|
||||
|
||||
case AUX_FUNC::GPS_DISABLE_YAW:
|
||||
AP::gps().set_force_disable_yaw(ch_flag == AuxSwitchPos::HIGH);
|
||||
break;
|
||||
|
@ -262,6 +262,8 @@ public:
|
||||
AUTOTUNE_TEST_GAINS = 180, // auto tune tuning switch to test or revert gains
|
||||
|
||||
|
||||
GPS_DISABLE_EK3 = 190, // disable GPS only for EKF3
|
||||
|
||||
// inputs from 200 will eventually used to replace RCMAP
|
||||
ROLL = 201, // roll input
|
||||
PITCH = 202, // pitch input
|
||||
|
Loading…
Reference in New Issue
Block a user