AP_Camera: RunCam: get rpty channels directly using convenience functions

This commit is contained in:
Peter Barker 2024-09-12 14:00:55 +10:00 committed by Peter Barker
parent 70c277b759
commit f0900bd119
2 changed files with 4 additions and 5 deletions

View File

@ -451,10 +451,10 @@ void AP_RunCam::handle_in_menu(Event ev)
// map rc input to an event // map rc input to an event
AP_RunCam::Event AP_RunCam::map_rc_input_to_event() const 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 throttle = rc().get_throttle_channel().get_aux_switch_pos();
const RC_Channel::AuxSwitchPos yaw = rc().get_channel_pos(AP::rcmap()->yaw()); const RC_Channel::AuxSwitchPos yaw = rc().get_yaw_channel().get_aux_switch_pos();
const RC_Channel::AuxSwitchPos roll = rc().get_channel_pos(AP::rcmap()->roll()); const RC_Channel::AuxSwitchPos roll = rc().get_roll_channel().get_aux_switch_pos();
const RC_Channel::AuxSwitchPos pitch = rc().get_channel_pos(AP::rcmap()->pitch()); const RC_Channel::AuxSwitchPos pitch = rc().get_pitch_channel().get_aux_switch_pos();
Event result = Event::NONE; Event result = Event::NONE;

View File

@ -27,7 +27,6 @@
#include <AP_Param/AP_Param.h> #include <AP_Param/AP_Param.h>
#include <RC_Channel/RC_Channel.h> #include <RC_Channel/RC_Channel.h>
#include <AP_RCMapper/AP_RCMapper.h>
#include <AP_Arming/AP_Arming.h> #include <AP_Arming/AP_Arming.h>
#include <AP_OSD/AP_OSD.h> #include <AP_OSD/AP_OSD.h>