mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 16:33:58 -04:00
AP_Camera: use get_stick_gesture_pos() for RunCam menus
This commit is contained in:
parent
01a6676e4b
commit
9329872cb1
@ -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_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;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user