Skip to content

Commit

Permalink
AP_Camera: use get_stick_gesture_pos() for RunCam menus
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per authored and peterbarker committed Jan 15, 2025
1 parent 17bfe4e commit 7805477
Showing 1 changed file with 4 additions and 4 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 @@ -462,10 +462,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_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();
const RC_Channel::AuxSwitchPos throttle = rc().get_throttle_channel().get_stick_gesture_pos();
const RC_Channel::AuxSwitchPos yaw = rc().get_yaw_channel().get_stick_gesture_pos();
const RC_Channel::AuxSwitchPos roll = rc().get_roll_channel().get_stick_gesture_pos();
const RC_Channel::AuxSwitchPos pitch = rc().get_pitch_channel().get_stick_gesture_pos();

Event result = Event::NONE;

Expand Down

0 comments on commit 7805477

Please sign in to comment.