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

RC_Channel: add RC_OPTIONS bit to clear RC override by RC input change #19844

Open
wants to merge 1 commit into
base: master
Choose a base branch
from

Conversation

tatsuy
Copy link
Contributor

@tatsuy tatsuy commented Jan 21, 2022

This PR introduces a new option to clear the RC override, allowing the pilot to regain control by operating roll, pitch, throttle, or yaw during an RC override situation. While this functionality was previously possible using RCx_OPTION(46), the new option provides a more direct and safer method for pilots to cancel overrides using basic RC inputs.

The following settings are required
RC_OPTIONS=16384 // it allows to clear overrides by Roll/Pitch/Throttle/Yaw
RCx_OPTION=46 // (RC Override Enable) Re-enable RC overrides

I tested this on copter SITL.

@muramura
Copy link
Contributor

muramura commented Jan 22, 2022

It is NG for the FC to not get permission from the CC.
It is also not for the FC to take control of the CC without permission.
When the FC cannot get a heartbeat from the CC, it is OK.
If the CC is the primary, the FC is the limbs.
When the CC is connected, the FC is a limb.

FC and CC should have a handshake procedure of "YOU HAVE" and "I HAVE".

PX4 has handshake in FC and MC.
PX4 has an OFFBOARD mode.
The ArduPilot needs to implement this OFFBOARD mode equivalent.

@tatsuy
Copy link
Contributor Author

tatsuy commented Jan 23, 2022

@muramura
In this PR, the AP's permission to clear Override can be set in RC_OPTIONS.

@rmackay9
Copy link
Contributor

rmackay9 commented Feb 3, 2022

Txs for this. In general I think it is good practice for the pilot holding an RC to be able to take control away from a companion computer easily. It makes sense to make it easy for a pilot to do that by simply moving the sticks.

@tatsuy
Copy link
Contributor Author

tatsuy commented Feb 3, 2022

@rmackay9 Thank you for your reviews.
I've added a commit to make the changes easier to understand, but I'm going to squash it eventually.

@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Feb 3, 2022
@tatsuy tatsuy changed the title RC_Channel: add RC_OPTION bit to clear RC override by RC input change RC_Channel: add RC_OPTIONS bit to clear RC override by RC input change Feb 4, 2022
@tatsuy
Copy link
Contributor Author

tatsuy commented Nov 8, 2022

@rmackay9
I have used this with real rover.
It works well and it's useful.
Can you check this again?

@peterbarker
Copy link
Contributor

This sounds like a good idea to me.

@tatsuy did you want to rebase this?

@tatsuy tatsuy force-pushed the pr-clear-override-by-rc branch 2 times, most recently from 16207cd to 722a833 Compare July 30, 2024 06:29
@tatsuy
Copy link
Contributor Author

tatsuy commented Jul 30, 2024

@peterbarker Thank you for your feedback. I have rebased.

libraries/RC_Channel/RC_Channel.cpp Outdated Show resolved Hide resolved
libraries/RC_Channel/RC_Channel.h Outdated Show resolved Hide resolved
libraries/RC_Channel/RC_Channel.h Outdated Show resolved Hide resolved
libraries/RC_Channel/RC_Channels.cpp Outdated Show resolved Hide resolved
libraries/RC_Channel/RC_Channels.cpp Show resolved Hide resolved
@@ -89,6 +90,20 @@ bool RC_Channels::read_input(void)
success |= channel(i)->update();
}

// check if clear overrides by RC is allowed by RC_OPTIONS and any change in RC input during RC overrides
if (rc().clear_overrides_by_rc() && has_active_overrides() &&
(channel(AP::rcmap()->roll() - 1)->rc_in_changed ||
Copy link
Contributor

Choose a reason for hiding this comment

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

Why don't we just check to see if any of them are outside their deadzones - with the exception of throttle, which we eithre don't check or do check for a change...

... and maybe just have a uint16_t last_throttle rather than the rc_in_changed infrastructure.

We should probably also very that RC input is actually valid before checking any channel value!

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I've modified the logic so that channels other than throttle are simply checked for being outside their deadzones.
For throttle, the value when the override is activated is stored in override_start_throttle, and any change beyond the deadzone is now checked.

@tatsuy
Copy link
Contributor Author

tatsuy commented Sep 24, 2024

@peterbarker Thank you for the review.
I have made the necessary changes based on your feedback.
I also confirmed the changes through SITL testing. Could you please review the updates again?

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

Successfully merging this pull request may close these issues.

5 participants