Skip to content

Commit

Permalink
AP_Camera: RunCam: get rpty channels directly using convenience funct…
Browse files Browse the repository at this point in the history
…ions
  • Loading branch information
peterbarker committed Sep 13, 2024
1 parent 09286e6 commit b48fed2
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 5 deletions.
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

0 comments on commit b48fed2

Please sign in to comment.