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
Closed
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
9 changes: 9 additions & 0 deletions ArduPlane/mode_rtl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,15 @@ bool ModeRTL::_enter()
return true;
}

// treat RTL as QLAND if we are armed and idling in a q-mode on the ground
// (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.

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

plane.set_mode(plane.mode_qland, ModeReason::QLAND_INSTEAD_OF_RTL);
return true;
}

// if Q_RTL_MODE is QRTL always, immediately switch to QRTL mode
if (plane.quadplane.rtl_mode == QuadPlane::RTL_MODE::QRTL_ALWAYS) {
plane.set_mode(plane.mode_qrtl, ModeReason::QRTL_INSTEAD_OF_RTL);
Expand Down
Loading