Skip to content

Commit

Permalink
add some info on Plane nav and altitude control
Browse files Browse the repository at this point in the history
  • Loading branch information
Hwurzburg committed Jan 12, 2025
1 parent 3a12c1e commit 8d5abe2
Show file tree
Hide file tree
Showing 3 changed files with 36 additions and 0 deletions.
1 change: 1 addition & 0 deletions dev/source/docs/learning-the-ardupilot-codebase.rst
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ Tutorial steps
Rover - Adding a new drive mode <rover-adding-a-new-drive-mode>
Rover - L1 navigation controller <rover-L1>
Plane - Architecture overview <plane-architecture>
Plane - Navigation and Altitude Control <plane-navigation-overview>
Adding a new Log message <code-overview-adding-a-new-log-message>
Adding a new MAVLink message <code-overview-adding-a-new-mavlink-message>
Adding a new MAVLink Gimbal <code-overview-adding-support-for-a-new-mavlink-gimbal>
Expand Down
35 changes: 35 additions & 0 deletions dev/source/docs/plane-navigation-overview.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
.. _plane-navigation-overview:

==============================================
Plane Navigation and Altitude Control Overview
==============================================

Navigation
==========
In auto-navigating modes like AUTO and CRUISE, or when responding to MAVLink navigation commands, ArduPlane usually uses two WAYPOINT locations (see `location object <https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_Common/Location.h>`__) and flies a wind compensated path between them:

<<<<<<< Updated upstream
- next_WP: the destination
- prev_WP: the beginning point
=======
- ``next_WP``: the destination
- ``prev_WP``: the beginning point
>>>>>>> Stashed changes

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

<<<<<<< Updated upstream
The code usually uses ``do_xxx`` to setup these waypoints (see `commands logic module <https://github.com/ArduPilot/ardupilot/blob/master/ArduPlane/commands_logic.cpp>`__). Sometimes, rather than having an existing starting point to use as prev_WP, code can use the ``set_next_WP`` method using ``auto_state.next_wp_crosstrack`` variable value to set the prev_WP to either the current waypoint destination (next_WP), or current location. Usually, you want to have the crosstrack false for the first waypoint so you proceed directly from your current position, instead of tracking to the line from a previously set destination. When entering a new mode, the prev_WP is always set to the current location, and crosstracking is initially disabled to assure navigation directly to whatever the new nex_WP is set by the mode.
=======
The code usually uses ``do_xxx`` to setup these waypoints (see `commands logic module <https://github.com/ArduPilot/ardupilot/blob/master/ArduPlane/commands_logic.cpp>`__). Sometimes, rather than having an existing starting point to use as ``prev_WP``, code can use the ``set_``next_WP```` method using ``auto_state.``next_WP``_crosstrack`` variable value to set the ``prev_WP`` to either the current waypoint destination (``next_WP``), or current location. Usually, you want to have the crosstrack false for the first waypoint so you proceed directly from your current position, instead of tracking to the line from a previously set destination. When entering a new mode, the ``prev_WP`` is always set to the current location, and crosstracking is initially disabled to assure navigation directly to whatever the new ``next_WP`` is set by the mode.
>>>>>>> Stashed changes

Auto-navigating modes call their ``navigation method``, usually involving a ``verify_xxx`` command, to determine if the destination has been reached and setup the next destination, if needed. Determining course correction and navigation roll angles is done by the `L1 Controller <https://github.com/ArduPilot/ardupilot/tree/master/libraries/AP_L1_Control>`__ .

`AP_Common:Location.h <https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_Common/Location.h>`__ has many useful methods for manipulation locations.

Altitude Control
================

Altitude control is managed by :ref:`tecs-total-energy-control-system-for-speed-height-tuning-guide` using demanded altitude from the mode, in altitude controlled mode. Modes use the ``update_target_altitude`` to calculate demanded altitude for TECS which will calculate the altitude profile between waypoints or maintain current altitude. Altitude target can be changed by MAVLink command (DO_CHANGE_ALT) or by stick control using ``update_fbwb_speed_height`` method.
Binary file added dev/source/images/waypoint_navigation.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.

0 comments on commit 8d5abe2

Please sign in to comment.