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

Plane: instantly switch from RTL to QRTL if within radius #16466

Merged
merged 1 commit into from
Feb 3, 2021
Merged
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
5 changes: 5 additions & 0 deletions ArduPlane/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -281,6 +281,11 @@ class ModeRTL : public Mode
protected:

bool _enter() override;

private:

// Switch to QRTL if enabled and within radius
bool switch_QRTL();
Copy link
Contributor

Choose a reason for hiding this comment

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

This needs a better name.

Suggested change
bool switch_QRTL();
bool switch_to_qrtl_if_enabled_and_within_radius();

};

class ModeStabilize : public Mode
Expand Down
45 changes: 30 additions & 15 deletions ArduPlane/mode_rtl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@ bool ModeRTL::_enter()
plane.do_RTL(plane.get_RTL_altitude());
plane.rtl.done_climb = false;

switch_QRTL();

return true;
}

Expand All @@ -33,22 +35,8 @@ void ModeRTL::update()

void ModeRTL::navigate()
{
uint16_t qrtl_radius = abs(plane.g.rtl_radius);
if (qrtl_radius == 0) {
qrtl_radius = abs(plane.aparm.loiter_radius);
}

if (plane.quadplane.available() && plane.quadplane.rtl_mode == 1 &&
(plane.nav_controller->reached_loiter_target() ||
plane.current_loc.past_interval_finish_line(plane.prev_WP_loc, plane.next_WP_loc) ||
plane.auto_state.wp_distance < MAX(qrtl_radius, plane.quadplane.stopping_distance())) &&
AP_HAL::millis() - plane.last_mode_change_ms > 1000) {
/*
for a quadplane in RTL mode we switch to QRTL when we
are within the maximum of the stopping distance and the
RTL_RADIUS
*/
plane.set_mode(plane.mode_qrtl, ModeReason::RTL_COMPLETE_SWITCHING_TO_VTOL_LAND_RTL);
if ((AP_HAL::millis() - plane.last_mode_change_ms > 1000) && switch_QRTL()) {
return;
}

Expand Down Expand Up @@ -88,3 +76,30 @@ void ModeRTL::navigate()
plane.update_loiter(radius);
}


// Switch to QRTL if enabled and within radius
bool ModeRTL::switch_QRTL()
{
if (!plane.quadplane.available() || (plane.quadplane.rtl_mode != 1)) {
return false;
}

uint16_t qrtl_radius = abs(plane.g.rtl_radius);
if (qrtl_radius == 0) {
qrtl_radius = abs(plane.aparm.loiter_radius);
}

if (plane.nav_controller->reached_loiter_target() ||
plane.current_loc.past_interval_finish_line(plane.prev_WP_loc, plane.next_WP_loc) ||
plane.auto_state.wp_distance < MAX(qrtl_radius, plane.quadplane.stopping_distance())) {
/*
for a quadplane in RTL mode we switch to QRTL when we
are within the maximum of the stopping distance and the
RTL_RADIUS
*/
plane.set_mode(plane.mode_qrtl, ModeReason::RTL_COMPLETE_SWITCHING_TO_VTOL_LAND_RTL);
return true;
}

return false;
}