AP_OSD: don't go via RCMap singleton to get RPTY RC channels

This commit is contained in:
Peter Barker 2024-09-12 14:17:54 +10:00 committed by Peter Barker
parent e3f76591fc
commit 8b50f3b54b
2 changed files with 8 additions and 12 deletions

View File

@ -503,7 +503,7 @@ private:
#if AP_RC_CHANNEL_ENABLED
Event map_rc_input_to_event() const;
RC_Channel::AuxSwitchPos get_channel_pos(uint8_t rcmapchan) const;
RC_Channel::AuxSwitchPos get_channel_pos(const class RC_Channel &chan) const;
#endif
uint8_t _selected_param = 1;

View File

@ -26,7 +26,6 @@
#include <AP_HAL/Util.h>
#include <limits.h>
#include <ctype.h>
#include <AP_RCMapper/AP_RCMapper.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <AP_Arming/AP_Arming.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
@ -390,14 +389,11 @@ void AP_OSD_ParamScreen::modify_configured_parameter(uint8_t number, Event ev)
}
// return radio values as LOW, MIDDLE, HIGH
// this function uses different threshold values to RC_Chanel::get_channel_pos()
// this function uses different threshold values to RC_Chanel::get_aux_switch_pos()
// to avoid glitching on the stick travel
RC_Channel::AuxSwitchPos AP_OSD_ParamScreen::get_channel_pos(uint8_t rcmapchan) const
RC_Channel::AuxSwitchPos AP_OSD_ParamScreen::get_channel_pos(const RC_Channel &chanref) const
{
const RC_Channel* chan = rc().channel(rcmapchan-1);
if (chan == nullptr) {
return RC_Channel::AuxSwitchPos::LOW;
}
const auto *chan = &chanref;
const uint16_t in = chan->get_radio_in();
if (in <= 900 || in >= 2200) {
@ -419,10 +415,10 @@ RC_Channel::AuxSwitchPos AP_OSD_ParamScreen::get_channel_pos(uint8_t rcmapchan)
// map rc input to an event
AP_OSD_ParamScreen::Event AP_OSD_ParamScreen::map_rc_input_to_event() const
{
const RC_Channel::AuxSwitchPos throttle = get_channel_pos(AP::rcmap()->throttle());
const RC_Channel::AuxSwitchPos yaw = get_channel_pos(AP::rcmap()->yaw());
const RC_Channel::AuxSwitchPos roll = get_channel_pos(AP::rcmap()->roll());
const RC_Channel::AuxSwitchPos pitch = get_channel_pos(AP::rcmap()->pitch());
const RC_Channel::AuxSwitchPos throttle = get_channel_pos(rc().get_throttle_channel());
const RC_Channel::AuxSwitchPos yaw = get_channel_pos(rc().get_yaw_channel());
const RC_Channel::AuxSwitchPos roll = get_channel_pos(rc().get_roll_channel());
const RC_Channel::AuxSwitchPos pitch = get_channel_pos(rc().get_pitch_channel());
Event result = Event::NONE;