Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fetch RPTY channels directly from AP::rc() rather than asking RCMap first #28089

Closed
wants to merge 3 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 4 additions & 4 deletions libraries/AP_Camera/AP_RunCam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -451,10 +451,10 @@ void AP_RunCam::handle_in_menu(Event ev)
// map rc input to an event
AP_RunCam::Event AP_RunCam::map_rc_input_to_event() const
{
const RC_Channel::AuxSwitchPos throttle = rc().get_channel_pos(AP::rcmap()->throttle());
const RC_Channel::AuxSwitchPos yaw = rc().get_channel_pos(AP::rcmap()->yaw());
const RC_Channel::AuxSwitchPos roll = rc().get_channel_pos(AP::rcmap()->roll());
const RC_Channel::AuxSwitchPos pitch = rc().get_channel_pos(AP::rcmap()->pitch());
const RC_Channel::AuxSwitchPos throttle = rc().get_throttle_channel().get_aux_switch_pos();
const RC_Channel::AuxSwitchPos yaw = rc().get_yaw_channel().get_aux_switch_pos();
const RC_Channel::AuxSwitchPos roll = rc().get_roll_channel().get_aux_switch_pos();
const RC_Channel::AuxSwitchPos pitch = rc().get_pitch_channel().get_aux_switch_pos();

Event result = Event::NONE;

Expand Down
1 change: 0 additions & 1 deletion libraries/AP_Camera/AP_RunCam.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@

#include <AP_Param/AP_Param.h>
#include <RC_Channel/RC_Channel.h>
#include <AP_RCMapper/AP_RCMapper.h>
#include <AP_Arming/AP_Arming.h>
#include <AP_OSD/AP_OSD.h>

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_OSD/AP_OSD.h
Original file line number Diff line number Diff line change
Expand Up @@ -503,7 +503,7 @@ class AP_OSD_ParamScreen : public AP_OSD_AbstractScreen

#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;
Expand Down
18 changes: 7 additions & 11 deletions libraries/AP_OSD/AP_OSD_ParamScreen.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down Expand Up @@ -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) {
Expand All @@ -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;

Expand Down
8 changes: 0 additions & 8 deletions libraries/RC_Channel/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1921,14 +1921,6 @@ RC_Channel::AuxSwitchPos RC_Channel::get_aux_switch_pos() const
return position;
}

// return switch position value as LOW, MIDDLE, HIGH
// if reading the switch fails then it returns LOW
RC_Channel::AuxSwitchPos RC_Channels::get_channel_pos(const uint8_t rcmapchan) const
{
const RC_Channel* chan = rc().channel(rcmapchan-1);
return chan != nullptr ? chan->get_aux_switch_pos() : RC_Channel::AuxSwitchPos::LOW;
}

RC_Channel *RC_Channels::find_channel_for_option(const RC_Channel::AUX_FUNC option)
{
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
Expand Down
1 change: 0 additions & 1 deletion libraries/RC_Channel/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -498,7 +498,6 @@ class RC_Channels {

class RC_Channel *find_channel_for_option(const RC_Channel::AUX_FUNC option);
bool duplicate_options_exist();
RC_Channel::AuxSwitchPos get_channel_pos(const uint8_t rcmapchan) const;
void convert_options(const RC_Channel::AUX_FUNC old_option, const RC_Channel::AUX_FUNC new_option);

void init_aux_all();
Expand Down
Loading