AP_Camera: allow roll right to also enter menu

This commit is contained in:
Andy Piper 2019-12-23 15:24:41 +00:00 committed by Andrew Tridgell
parent afcbc5ffdb
commit 318a23537d
2 changed files with 21 additions and 16 deletions

View File

@ -64,10 +64,10 @@ const AP_Param::GroupInfo AP_RunCam::var_info[] = {
// @Param: CONTROL // @Param: CONTROL
// @DisplayName: RunCam control option // @DisplayName: RunCam control option
// @Description: Specifies the allowed actions required to enter the OSD menu. // @Description: Specifies the allowed actions required to enter the OSD menu
// @Bitmask: 0:Stick yaw right, 1:3-way switch, 2: 2-way switch // @Bitmask: 0:Stick yaw right,1:Stick roll right,2:3-position switch,3:2-position switch
// @User: Advanced // @User: Advanced
AP_GROUPINFO("CONTROL", 6, AP_RunCam, _cam_control_option, uint8_t(ControlOption::STICK_YAW_RIGHT) | uint8_t(ControlOption::TWO_POS_SWITCH)), AP_GROUPINFO("CONTROL", 6, AP_RunCam, _cam_control_option, uint8_t(ControlOption::STICK_ROLL_RIGHT) | uint8_t(ControlOption::TWO_POS_SWITCH)),
AP_GROUPEND AP_GROUPEND
}; };
@ -334,9 +334,12 @@ void AP_RunCam::handle_ready(Event ev)
{ {
switch (ev) { switch (ev) {
case Event::ENTER_MENU: case Event::ENTER_MENU:
_top_menu_pos = -1; case Event::IN_MENU_ENTER:
_sub_menu_pos = 0; if (ev == Event::ENTER_MENU || _cam_control_option & uint8_t(ControlOption::STICK_ROLL_RIGHT)) {
_state = State::ENTERING_MENU; _top_menu_pos = -1;
_sub_menu_pos = 0;
_state = State::ENTERING_MENU;
}
break; break;
case Event::START_RECORDING: case Event::START_RECORDING:
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_START_RECORDING); simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_START_RECORDING);
@ -345,7 +348,6 @@ void AP_RunCam::handle_ready(Event ev)
break; break;
case Event::NONE: case Event::NONE:
case Event::EXIT_MENU: case Event::EXIT_MENU:
case Event::IN_MENU_ENTER:
case Event::IN_MENU_RIGHT: case Event::IN_MENU_RIGHT:
case Event::IN_MENU_UP: case Event::IN_MENU_UP:
case Event::IN_MENU_DOWN: case Event::IN_MENU_DOWN:
@ -361,11 +363,14 @@ void AP_RunCam::handle_recording(Event ev)
{ {
switch (ev) { switch (ev) {
case Event::ENTER_MENU: case Event::ENTER_MENU:
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_STOP_RECORDING); case Event::IN_MENU_ENTER:
set_mode_change_timeout(); if (ev == Event::ENTER_MENU || _cam_control_option & uint8_t(ControlOption::STICK_ROLL_RIGHT)) {
_sub_menu_pos = 0; simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_STOP_RECORDING);
_top_menu_pos = -1; set_mode_change_timeout();
_state = State::ENTERING_MENU; _top_menu_pos = -1;
_sub_menu_pos = 0;
_state = State::ENTERING_MENU;
}
break; break;
case Event::STOP_RECORDING: case Event::STOP_RECORDING:
simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_STOP_RECORDING); simulate_camera_button(ControlOperation::RCDEVICE_PROTOCOL_CHANGE_STOP_RECORDING);
@ -374,7 +379,6 @@ void AP_RunCam::handle_recording(Event ev)
break; break;
case Event::NONE: case Event::NONE:
case Event::EXIT_MENU: case Event::EXIT_MENU:
case Event::IN_MENU_ENTER:
case Event::IN_MENU_RIGHT: case Event::IN_MENU_RIGHT:
case Event::IN_MENU_UP: case Event::IN_MENU_UP:
case Event::IN_MENU_DOWN: case Event::IN_MENU_DOWN:
@ -422,7 +426,7 @@ AP_RunCam::Event AP_RunCam::map_rc_input_to_event() const
result = Event::ENTER_MENU; result = Event::ENTER_MENU;
} else if (roll == RC_Channel::LOW) { } else if (roll == RC_Channel::LOW) {
result = Event::IN_MENU_EXIT; result = Event::IN_MENU_EXIT;
} else if (roll == RC_Channel::HIGH) { } else if (yaw == RC_Channel::MIDDLE && pitch == RC_Channel::MIDDLE && roll == RC_Channel::HIGH) {
result = Event::IN_MENU_ENTER; result = Event::IN_MENU_ENTER;
} else if (pitch == RC_Channel::HIGH) { } else if (pitch == RC_Channel::HIGH) {
result = Event::IN_MENU_UP; result = Event::IN_MENU_UP;

View File

@ -68,8 +68,9 @@ public:
// control for OSD menu entry // control for OSD menu entry
enum class ControlOption { enum class ControlOption {
STICK_YAW_RIGHT = (1 << 0), STICK_YAW_RIGHT = (1 << 0),
THREE_POS_SWITCH = (1 << 1), STICK_ROLL_RIGHT = (1 << 1),
TWO_POS_SWITCH = (1 << 2) THREE_POS_SWITCH = (1 << 2),
TWO_POS_SWITCH = (1 << 3)
}; };
// initialize the RunCam driver // initialize the RunCam driver