RC_Channel: allow customisation of position text in aux switch announcement
this means that we get "EKFPosSource 1" rather than "EKFPosSource LOW"
This commit is contained in:
parent
2d5e6a5f98
commit
8a478abce9
@ -753,7 +753,6 @@ const RC_Channel::LookupTable RC_Channel::lookuptable[] = {
|
|||||||
{ AUX_FUNC::RUNCAM_OSD_CONTROL,"RunCamOSDControl"},
|
{ AUX_FUNC::RUNCAM_OSD_CONTROL,"RunCamOSDControl"},
|
||||||
{ AUX_FUNC::VISODOM_ALIGN,"VisOdomAlign"},
|
{ AUX_FUNC::VISODOM_ALIGN,"VisOdomAlign"},
|
||||||
{ AUX_FUNC::AIRMODE, "AirMode"},
|
{ AUX_FUNC::AIRMODE, "AirMode"},
|
||||||
{ AUX_FUNC::EKF_POS_SOURCE,"EKFPosSource"},
|
|
||||||
{ AUX_FUNC::CAM_MODE_TOGGLE,"CamModeToggle"},
|
{ AUX_FUNC::CAM_MODE_TOGGLE,"CamModeToggle"},
|
||||||
{ AUX_FUNC::GENERATOR,"Generator"},
|
{ AUX_FUNC::GENERATOR,"Generator"},
|
||||||
{ AUX_FUNC::BATTERY_MPPT_ENABLE,"Battery MPPT Enable"},
|
{ AUX_FUNC::BATTERY_MPPT_ENABLE,"Battery MPPT Enable"},
|
||||||
@ -1434,22 +1433,26 @@ 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_POS_SOURCE: {
|
||||||
|
uint8_t source_set = 0;
|
||||||
switch (ch_flag) {
|
switch (ch_flag) {
|
||||||
case AuxSwitchPos::LOW:
|
case AuxSwitchPos::LOW:
|
||||||
// low switches to primary source
|
// low switches to primary source
|
||||||
AP::ahrs().set_posvelyaw_source_set(0);
|
source_set = 0;
|
||||||
break;
|
break;
|
||||||
case AuxSwitchPos::MIDDLE:
|
case AuxSwitchPos::MIDDLE:
|
||||||
// middle switches to secondary source
|
// middle switches to secondary source
|
||||||
AP::ahrs().set_posvelyaw_source_set(1);
|
source_set = 1;
|
||||||
break;
|
break;
|
||||||
case AuxSwitchPos::HIGH:
|
case AuxSwitchPos::HIGH:
|
||||||
// high switches to tertiary source
|
// high switches to tertiary source
|
||||||
AP::ahrs().set_posvelyaw_source_set(2);
|
source_set = 2;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
AP::ahrs().set_posvelyaw_source_set(source_set);
|
||||||
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Using EKF Source Set %u", source_set+1);
|
||||||
break;
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
#if AP_OPTICALFLOW_CALIBRATOR_ENABLED
|
#if AP_OPTICALFLOW_CALIBRATOR_ENABLED
|
||||||
case AUX_FUNC::OPTFLOW_CAL: {
|
case AUX_FUNC::OPTFLOW_CAL: {
|
||||||
|
Loading…
Reference in New Issue
Block a user