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

Conversation

prosolvo4th
Copy link

Sticks inputs: roll mid && pitch high && yaw low && throttle mid

@prosolvo4th prosolvo4th force-pushed the osd_sticks_input_switch branch 2 times, most recently from fd74178 to cdc4255 Compare August 20, 2024 20:32
Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

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

The new option would need to be documented in the relevant parameter description in AP_OSD.cpp

Not sure why we haven't supported this before. Seems odd.

libraries/AP_OSD/AP_OSD.cpp Outdated Show resolved Hide resolved
libraries/AP_OSD/AP_OSD.cpp Outdated Show resolved Hide resolved
@Hwurzburg
Copy link
Collaborator

needs Andy's approval that this does not interfere with his param change code

@andyp1per
Copy link
Collaborator

Pretty sure this is going to interact very badly with the param stuff and runcam menus. I think probably at a minimum you need to check that you are not in the runcam osd menus and disable this behaviour if you are. The param stuff is the same I think - you need to check you are not in these menus when enabling this stuff.

Copy link
Collaborator

@andyp1per andyp1per left a comment

Choose a reason for hiding this comment

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

Need to check whether you are in runcam or osd parameter menus

@prosolvo4th
Copy link
Author

prosolvo4th commented Sep 14, 2024

Need to check whether you are in runcam or OSD parameter menus

Hi!
I added checking for the runcam menu state (kind of).
But I don't want to add a check on Screen5 or Screen6. I use this functionality to go to Screen5 to adjust the VTX.

For now, there is no interference between the param menu and the used stick combination.
For the param menu throttle (left stick in mode2) must be in the lower position, in the proposed PR for switching between OSD screens throttle must be in the center.

@andyp1per
Copy link
Collaborator

Need to check whether you are in runcam or OSD parameter menus

Hi! I added checking for runcam menu state (kind of). But I don't want to add a check on Screen5 or Screen6. I use this functionality to go to Screen5 to adjust the VTX.

Does it work ok? I mean if its working well with the parameter menus then that's great.

@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Sep 14, 2024
@prosolvo4th
Copy link
Author

Need to check whether you are in runcam or OSD parameter menus

Hi! I added checking for runcam menu state (kind of). But I don't want to add a check on Screen5 or Screen6. I use this functionality to go to Screen5 to adjust the VTX.

Does it work ok? I mean if its working well with the parameter menus then that's great.

yep, so far so good

Sticks inputs: roll mid && pitch high && yaw low && throttle mid

Signed-off-by: 4th <[email protected]>
@prosolvo4th
Copy link
Author

@Hwurzburg
Here are changes in the wiki:
ArduPilot/ardupilot_wiki#6278

libraries/AP_OSD/AP_OSD.cpp Outdated Show resolved Hide resolved
@prosolvo4th prosolvo4th force-pushed the osd_sticks_input_switch branch 2 times, most recently from cebfc34 to d241686 Compare September 14, 2024 17:19
Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

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

We don't care if RunCam is preventing arming.

We care that we're in the RunCam menus.

So use an appropriately-named method.

libraries/AP_Camera/AP_RunCam.h Outdated Show resolved Hide resolved
@peterbarker
Copy link
Contributor

Byte-cost for this feature:

Board                    AP_Periph  blimp  bootloader  copter  heli  iofirmware  plane  rover  sub
CubeOrange-periph-heavy  *                                                                     
Durandal                            *      *           272     272               272    272    *
Hitec-Airspeed           *                                                                     
KakuteH7-bdshot                     *      *           120     120               120    112    *
MatekF405                           *      *           112     112               120    112    *
Pixhawk1-1M-bdshot                  *                  *       *                 *      *      *
f103-QiotekPeriph        *                                                                     
f303-Universal           *                                                                     
iomcu                                                                *                         
revo-mini                           *      *           120     112               120    112    *
skyviper-v2450                                         *                                       

@peterbarker
Copy link
Contributor

... also has to pass CI

@prosolvo4th
Copy link
Author

... also has to pass CI

This can be quite difficult.
For some reason sometimes tests can fail for no reason.
I created a simple change and PR with this change in my fork, and CI failed in 2 checks.
I am afraid, I am not able to get a CI 100% pass...

Mr4th added 3 commits September 15, 2024 20:49
@@ -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

@@ -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.

Copy link
Collaborator

@andyp1per andyp1per left a comment

Choose a reason for hiding this comment

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

You will also need to squash the commits

@andyp1per
Copy link
Collaborator

We don't care if RunCam is preventing arming.

We care that we're in the RunCam menus.

So use an appropriately-named method.

We do internally. I object to this rename internally, but fine for it to be used externally.

@@ -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

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
WikiNeeded needs wiki update
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants