From b48fed229bd0f3bb76bd867bb4733204b45ec8c0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 12 Sep 2024 14:00:55 +1000 Subject: [PATCH] AP_Camera: RunCam: get rpty channels directly using convenience functions --- libraries/AP_Camera/AP_RunCam.cpp | 8 ++++---- libraries/AP_Camera/AP_RunCam.h | 1 - 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Camera/AP_RunCam.cpp b/libraries/AP_Camera/AP_RunCam.cpp index 86e7dee57c6af..2fdef89c99745 100644 --- a/libraries/AP_Camera/AP_RunCam.cpp +++ b/libraries/AP_Camera/AP_RunCam.cpp @@ -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; diff --git a/libraries/AP_Camera/AP_RunCam.h b/libraries/AP_Camera/AP_RunCam.h index 673dba0ff6e73..9eb6299923664 100644 --- a/libraries/AP_Camera/AP_RunCam.h +++ b/libraries/AP_Camera/AP_RunCam.h @@ -27,7 +27,6 @@ #include #include -#include #include #include