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

update to AUTOLAND improvements #6549

Merged
merged 1 commit into from
Jan 21, 2025
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
Binary file modified images/autoland_mode.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
17 changes: 11 additions & 6 deletions plane/source/docs/mode_autoland.rst
Original file line number Diff line number Diff line change
Expand Up @@ -6,26 +6,31 @@ AUTOLAND Mode

AUTOLAND mode provides a fully automatic fixed wing landing which can also be used as an RC failsafe action.

In Mode Takeoff or during a NAV_TAKEOFF in AUTO, the takeoff direction will be captured from the GPS ground course once a GPS ground speed of 5m/s is obtained. This usually occurs early in the takeoff run of a rolling takeoff or almost immediately during a hand or bungee launch.
In TAKEOFF, FBWA, MANUAL, TRAINING, ACRO, STABILIZE modes, and during a NAV_TAKEOFF in AUTO, the takeoff direction will be captured from the GPS ground course once a GPS ground speed of 5m/s is obtained. This usually occurs early in the takeoff run of a rolling takeoff or almost immediately during a hand or bungee launch.

It will setup a parameterized base leg and final approach waypoint/altitude, based on the takeoff direction, and proceed to it and switch to an automatic landing at home. It can also be selected as a :ref:`FS_LONG_ACTN<FS_LONG_ACTN>` for RC failsafes.
It will setup a parameterized LOITER-TO-ALT base waypoint and final approach waypoint/altitude, based on the takeoff direction, and proceed to then and then switch to an automatic landing at home. It can also be selected as a :ref:`FS_LONG_ACTN<FS_LONG_ACTN>` for RC failsafes.

This is useful when programming a mission with a ``DO_LAND_START`` landing sequence is not convenient since it requires a GCS on a laptop or phone, such as traveling with impromptu stops to fly FPV or photograph. Simply use Mode TAKEOFF or a simple loaded before travel with a ``NAV_TAKEOFF`` waypoint. It is also useful for fields which have varying wind directions, which would prevent using a single home-loaded autolanding mission or require using the MissionSelector LUA script to slect from several missions with different approaches.
This is useful when programming a mission with a ``DO_LAND_START`` landing sequence is not convenient since it requires a GCS on a laptop or phone, such as traveling with impromptu stops to fly FPV or photograph. Simply takeoff in one of the previously mentioned modes and the AUTOLAND will be setup. It is also useful for fields which have varying wind directions, which would prevent using a single home-loaded autolanding mission or require using the MissionSelector LUA script to slect from several missions with different approaches.

Operation
=========
To use simply make an automatic takeoff and at any point later switch into AUTOLAND. A final approach waypoint will be created behind the HOME landing target at :ref:`AUTOLAND_WP_DIST<AUTOLAND_WP_DIST>` (400m by default) at :ref:`AUTOLAND_WP_ALT<AUTOLAND_WP_ALT>` (55m by default)using the takeoff direction plus :ref:`AUTOLAND_DIR_OFF<AUTOLAND_DIR_OFF>` ("0" default) and land using all the parametrics of a normal autolanding. A base leg to the final approach waypoint is also created at the same altitude and 1/3 :ref:`AUTOLAND_WP_DIST<AUTOLAND_WP_DIST>` from the final approach waypoint as shown below:
To use simply make a takeoff and at any point later switch into AUTOLAND. A final approach waypoint will be created behind the HOME landing target at :ref:`AUTOLAND_WP_DIST<AUTOLAND_WP_DIST>` (400m by default) at :ref:`AUTOLAND_WP_ALT<AUTOLAND_WP_ALT>` (55m by default)using the takeoff direction plus :ref:`AUTOLAND_DIR_OFF<AUTOLAND_DIR_OFF>` ("0" default) and land using all the parametrics of a normal autolanding. A loiter to alt waypoint tangential to the final approach waypoint is also created at the same altitude and at 1/3 :ref:`AUTOLAND_WP_DIST<AUTOLAND_WP_DIST>` or :ref:`WP_LOITER_RAD<WP_LOITER_RAD>`, whichever is smaller, from the final approach waypoint as shown below:

.. image:: ../../../images/autoland_mode.png
:target: ../_images/autoland_mode.png

``LAND`` parameter defaults are usually acceptable for most planes in the 1-2m wingspan, <2kg class) and should yeild a safe, if not optimally tuned, autolanding. ``LAND`` parameters can be optimized with test flights (See :ref:`automatic-landing`).

Options
=======

The :ref:`AUTOLAND_OPTIONS <AUTOLAND_OPTIONS>` bitmask provides optional behavior. Currently, if bit 0 is set, then instead of capturing takeoff direction( and therefore autolanding direction), the landing direction will be captured immediately at arming if a compass is being used. This allows the direction to be set "manually" by orienting the plane at homw in the desired landing direction and arming. The :ref:`AUTOLAND_DIR_OFF<AUTOLAND_DIR_OFF>` parameter is ignored in this case.

Notes:
======

- Switching out of AUTOLAND to another mode aborts the landing and returns control to that new mode.
- Throttle aborts of the final landing sequence are not supported. (:ref:`LAND_ABORT_THR<LAND_ABORT_THR>`)
- If the plane has taken off not using either Mode Takeoff or NAV_LAND, the mode cannot be entered since the takeoff direction has not been captured. If it is selected as a long failsafe action ("5"), :ref:`FS_LONG_ACTN<FS_LONG_ACTN>`, it will switch to normal RTL instead of AUTOLAND on failsafe, in this case.
- If the plane has taken off not using the aforementioned modes, the mode cannot be entered since the takeoff direction has not been captured. In these cases, if it is selected as a long failsafe action ("5"), :ref:`FS_LONG_ACTN<FS_LONG_ACTN>`, it will switch to normal RTL instead of AUTOLAND on failsafe.
- The mode co-exists with any mission autolanding sequence, which can be used in AUTO mode, or with :ref:`RTL_AUTOLAND<RTL_AUTOLAND>`.
- QuadPlanes cannot use this mode unless :ref:`Q_OPTIONS<Q_OPTIONS>` bit 2 (ALLOW_FW_LAND) is set and a Mode Takeoff or AUTO NAV_TAKEOFF has been used.
- QuadPlanes cannot use this mode.