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

quadplane: mode_rtl: don't RTL during ground-idle #25553

Closed

Conversation

robertlong13
Copy link
Collaborator

@robertlong13 robertlong13 commented Nov 16, 2023

Similar to how we handle guided waiting for takeoff, we should treat RTL as QLand when the autopilot is confident that it is not flying. This is common when on the ground in QHover or QLoiter waiting to visually confirm all props are spinning. We don't want an errant switch flip to trigger a transition to forward flight.

Original description of this PR below:

Similar to how we handle guided waiting for takeoff, we should treat RTL as QLand when the desired spool state is GROUND_IDLE. This should only occur on the ground. This is common when on the ground in QHover or QLoiter waiting to visually confirm all props are spinning. We don't want an errant switch flip to trigger a transition to forward flight.

This can also happen in QStabilize when airmode is disabled and the stick is all the way down, but that shouldn't really happen in flight, and if it does, it is brief enough that it would be unlikely to be happening during an RTL trigger. Even if it does, QLand is not the worst thing in the world for that edge-case.

@IamPete1
Copy link
Member

This does make me a little nervous, I think its fine now, but this is the sort of thing that might catch us out in the future.

Maybe you could check that the previous mode is a VTOL one as well?

@robertlong13
Copy link
Collaborator Author

Yeah, I think you're right.

Alternatively, should this just be an on_ground or on_ground_maybe check instead of spool state?

@robertlong13
Copy link
Collaborator Author

I've just changed this to check plane.is_flying() instead. I think that's a lot better than what I was doing and makes the intention clear.

@@ -18,6 +18,13 @@ bool ModeRTL::_enter()
return true;
}

// treat RTL as QLAND if we are armed but not flying
// (when disarmed, allow RTL mode, so pilots can test switches)
if (plane.arming.is_armed() && !plane.is_flying()) {
Copy link
Contributor

Choose a reason for hiding this comment

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

to make this tighter, it could be in a Q mode, and throttle is idle?

Copy link
Contributor

Choose a reason for hiding this comment

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

@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Dec 12, 2023
// (when disarmed, allow RTL mode, so pilots can test switches)
if (plane.arming.is_armed() &&
plane.control_mode->is_vtol_mode() &&
plane.quadplane.motors->get_desired_spool_state() == AP_Motors::DesiredSpoolState::GROUND_IDLE) {
Copy link
Member

Choose a reason for hiding this comment

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

It would be nice to have a !plane.is_flying() in here too if it would still work in your use case. I wonder what Qland actually does in this case? One would hope it would just disarm, if it does I wonder if we would be better to just disarm in RTL and not change mode.

@robertlong13
Copy link
Collaborator Author

Actually, this new approach is fundamentally flawed (sorry for not getting around to basic testing before I put it up for the call):

  1. The plane.control_mode gets set to RTL before this check, so it'll never show as a q-mode. I'm not sure there's a clean way to get what mode we came from to confirm it's a q-mode.
  2. Mission Planner tries two different ways to send RTL when it sends RTL (say, user hits the wrong button on a gamepad, misclicks a button on the Actions tab, or hits "space" accidentally when a button is invisibly selected as active [another problem for me to fix]), so even if this logic I proposed worked, the second time the RTL gets commanded the desired spool state won't be ground idle.

I'm considering just closing this PR, but I'll leave it as a dev call topic in case someone has a great idea. I do think it would be nice to reduce the chance of RTL causing a takeoff while ground idling, but I don't think there's a great way to achieve it.

@tridge
Copy link
Contributor

tridge commented May 6, 2024

@robertlong13 do you have a log of the issue?

// (when disarmed, allow RTL mode, so pilots can test switches)
if (plane.arming.is_armed() &&
plane.control_mode->is_vtol_mode() &&
plane.quadplane.motors->get_desired_spool_state() == AP_Motors::DesiredSpoolState::GROUND_IDLE) {
Copy link
Contributor

Choose a reason for hiding this comment

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

this looks like it would fail in QRTL during the approach phase

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

Successfully merging this pull request may close these issues.

6 participants