Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add osd switching via stick inputs in disarm state #27877

Open
wants to merge 4 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions libraries/AP_Camera/AP_RunCam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -244,7 +244,7 @@ bool AP_RunCam::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len)
}

// currently in the OSD menu, do not allow arming
if (is_arming_prevented()) {
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

please don't change these - it makes it less clear. I don't think this is what @peterbarker was proposing, he suggested having two functions and I think that would be fine.

if (in_menu()) {
hal.util->snprintf(failure_msg, failure_msg_len, "In OSD menu");
return false;
}
Expand Down Expand Up @@ -468,11 +468,11 @@ AP_RunCam::Event AP_RunCam::map_rc_input_to_event() const
&& pitch == RC_Channel::AuxSwitchPos::MIDDLE && roll == RC_Channel::AuxSwitchPos::MIDDLE
// don't allow an action close to arming unless the user had configured it or arming is not possible
// but don't prevent the 5-Key control actually working
&& (_cam_control_option & uint8_t(ControlOption::STICK_YAW_RIGHT) || is_arming_prevented())) {
&& (_cam_control_option & uint8_t(ControlOption::STICK_YAW_RIGHT) || in_menu())) {
result = Event::EXIT_MENU;
} else if (throttle == RC_Channel::AuxSwitchPos::MIDDLE && yaw == RC_Channel::AuxSwitchPos::HIGH
&& pitch == RC_Channel::AuxSwitchPos::MIDDLE && roll == RC_Channel::AuxSwitchPos::MIDDLE
&& (_cam_control_option & uint8_t(ControlOption::STICK_YAW_RIGHT) || is_arming_prevented())) {
&& (_cam_control_option & uint8_t(ControlOption::STICK_YAW_RIGHT) || in_menu())) {
result = Event::ENTER_MENU;
} else if (roll == RC_Channel::AuxSwitchPos::LOW) {
result = Event::IN_MENU_EXIT;
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Camera/AP_RunCam.h
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,8 @@ class AP_RunCam
void update();
// Check whether arming is allowed
bool pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const;
// whether or not we can arm
bool in_menu() const { return _in_menu > _menu_enter_level; }

static const struct AP_Param::GroupInfo var_info[];

Expand Down Expand Up @@ -421,8 +423,6 @@ class AP_RunCam
return !has_2_key_OSD() && has_feature(Feature::RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE);
}

// whether or not we can arm
bool is_arming_prevented() const { return _in_menu > _menu_enter_level; }
// error handler for OSD simulation
void simulation_OSD_cable_failed(const Request& request);
// process pending request, retrying as necessary
Expand Down
45 changes: 39 additions & 6 deletions libraries/AP_OSD/AP_OSD.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
#include <AP_Terrain/AP_Terrain.h>
#include <AP_RSSI/AP_RSSI.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Camera/AP_RunCam.h>

// macro for easy use of var_info2
#define AP_SUBGROUPINFO2(element, name, idx, thisclazz, elclazz) { name, AP_VAROFFSET(thisclazz, element), { group_info : elclazz::var_info2 }, AP_PARAM_FLAG_NESTED_OFFSET, idx, AP_PARAM_GROUP }
Expand Down Expand Up @@ -78,7 +79,7 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
// @Param: _SW_METHOD
// @DisplayName: Screen switch method
// @Description: This sets the method used to switch different OSD screens.
// @Values: 0: switch to next screen if channel value was changed, 1: select screen based on pwm ranges specified for each screen, 2: switch to next screen after low to high transition and every 1s while channel value is high
// @Values: 0: switch to next screen if channel value was changed, 1: select screen based on pwm ranges specified for each screen, 2: switch to next screen after low to high transition and every 1s while channel value is high, 3: switches to next screen if the sticks in the next position: roll - middle, pitch - high, throttle - middle, yaw - left. Keeps toggling to next screen every 1s while sticks in mentioned positions
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this causes a CI metadata failure

Suggested change
// @Values: 0: switch to next screen if channel value was changed, 1: select screen based on pwm ranges specified for each screen, 2: switch to next screen after low to high transition and every 1s while channel value is high, 3: switches to next screen if the sticks in the next position: roll - middle, pitch - high, throttle - middle, yaw - left. Keeps toggling to next screen every 1s while sticks in mentioned positions
// @Values: 0: switch to next screen if channel value was changed, 1: select screen based on pwm ranges specified for each screen, 2: switch to next screen after low to high transition and every 1s while channel value is high, 3: switches to next screen if the sticks are held roll-middle pitch-high throttle-middle and yaw-left. Keeps toggling to the next screen every 1s while sticks are in the mentioned positions

// @User: Standard
AP_GROUPINFO("_SW_METHOD", 7, AP_OSD, sw_method, AP_OSD::TOGGLE),

Expand Down Expand Up @@ -541,17 +542,23 @@ void AP_OSD::update_current_screen()
was_failsafe = false;
}

if (rc_channel == 0) {
if (rc_channel == 0 && sw_method != STICKS_INPUT) {
return;
}

#if AP_RC_CHANNEL_ENABLED
RC_Channel *channel = RC_Channels::rc_channel(rc_channel-1);
if (channel == nullptr) {
return;
int16_t channel_value = 0;
RC_Channel *channel = nullptr;

if (sw_method != STICKS_INPUT) {
channel = RC_Channels::rc_channel(rc_channel-1);
if (channel == nullptr) {
return;
}

channel_value = channel->get_radio_in();
}

int16_t channel_value = channel->get_radio_in();
switch (sw_method) {
//switch to next screen if channel value was changed
default:
Expand Down Expand Up @@ -599,6 +606,32 @@ void AP_OSD::update_current_screen()
last_switch_ms = 0;
}
break;
case STICKS_INPUT:
if (!AP_Notify::flags.armed && !AP::runcam()->in_menu()) {
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You don't need to check for armed here. You can't be in menu and armed

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

... also the wrong way to check if you're armed; you ask the arming library directly if you're armed.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You don't need to check for armed here. You can't be in menu and armed

Disagree. We should not pre-suppose the inner-workings of AP_RunCam here.

We should both check we are not armed and that we aren't going to screw over AP_RunCam somehow.

Suggested change
if (!AP_Notify::flags.armed && !AP::runcam()->in_menu()) {
if (!AP::arming().is_armed() && !AP::runcam()->in_menu()) {

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

... actually, you will need to add #ifs around the call to the runcam singleton here, or we'll end up with compilations failures when runcam isn't compiled in

auto &rc_channels = rc();
auto &roll = rc_channels.get_roll_channel();
auto &pitch = rc_channels.get_pitch_channel();
auto &yaw = rc_channels.get_yaw_channel();
auto &throttle = rc_channels.get_throttle_channel();
if (roll.get_aux_switch_pos() == RC_Channel::AuxSwitchPos::MIDDLE &&
pitch.get_aux_switch_pos() == RC_Channel::AuxSwitchPos::HIGH &&
yaw.get_aux_switch_pos() == RC_Channel::AuxSwitchPos::LOW &&
throttle.get_aux_switch_pos() == RC_Channel::AuxSwitchPos::MIDDLE) {
if (switch_debouncer) {
uint32_t now = AP_HAL::millis();
if (now - last_switch_ms > 1000) {
next_screen();
last_switch_ms = now;
}
} else {
switch_debouncer = true;
return;
}
} else {
last_switch_ms = 0;
}
}
break;
}
switch_debouncer = false;
#endif // AP_RC_CHANNEL_ENABLED
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_OSD/AP_OSD.h
Original file line number Diff line number Diff line change
Expand Up @@ -562,6 +562,7 @@ class AP_OSD
TOGGLE=0,
PWM_RANGE=1,
AUTO_SWITCH=2,
STICKS_INPUT=3,
};

AP_Int8 osd_type;
Expand Down
Loading