mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: move aux pos string to function, print RC channel number with aux fun
This commit is contained in:
parent
917878de76
commit
6a4280429a
|
@ -606,7 +606,7 @@ const RC_Channel::LookupTable RC_Channel::lookuptable[] = {
|
|||
};
|
||||
|
||||
/* lookup the announcement for switch change */
|
||||
const char *RC_Channel::string_for_aux_function(AUX_FUNC function) const
|
||||
const char *RC_Channel::string_for_aux_function(AUX_FUNC function) const
|
||||
{
|
||||
for (const struct LookupTable &entry : lookuptable) {
|
||||
if (entry.option == function) {
|
||||
|
@ -616,6 +616,20 @@ const char *RC_Channel::string_for_aux_function(AUX_FUNC function) const
|
|||
return nullptr;
|
||||
}
|
||||
|
||||
/* find string for postion */
|
||||
const char *RC_Channel::string_for_aux_pos(AuxSwitchPos pos) const
|
||||
{
|
||||
switch (pos) {
|
||||
case AuxSwitchPos::HIGH:
|
||||
return "HIGH";
|
||||
case AuxSwitchPos::MIDDLE:
|
||||
return "MIDDLE";
|
||||
case AuxSwitchPos::LOW:
|
||||
return "LOW";
|
||||
}
|
||||
return "";
|
||||
}
|
||||
|
||||
#endif // AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED
|
||||
|
||||
/*
|
||||
|
@ -650,19 +664,7 @@ bool RC_Channel::read_aux()
|
|||
// announce the change to the GCS:
|
||||
const char *aux_string = string_for_aux_function(_option);
|
||||
if (aux_string != nullptr) {
|
||||
const char *temp = nullptr;
|
||||
switch (new_position) {
|
||||
case AuxSwitchPos::HIGH:
|
||||
temp = "HIGH";
|
||||
break;
|
||||
case AuxSwitchPos::MIDDLE:
|
||||
temp = "MIDDLE";
|
||||
break;
|
||||
case AuxSwitchPos::LOW:
|
||||
temp = "LOW";
|
||||
break;
|
||||
}
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "%s %s", aux_string, temp);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "RC%i: %s %s", ch_in+1, aux_string, string_for_aux_pos(new_position));
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -298,6 +298,7 @@ public:
|
|||
|
||||
#if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED
|
||||
const char *string_for_aux_function(AUX_FUNC function) const;
|
||||
const char *string_for_aux_pos(AuxSwitchPos pos) const;
|
||||
#endif
|
||||
// pwm value under which we consider that Radio value is invalid
|
||||
static const uint16_t RC_MIN_LIMIT_PWM = 800;
|
||||
|
|
Loading…
Reference in New Issue