You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
wiki: document AHRS origin persistence for non-GPS flight
Add documentation for new AHRS_OPTIONS bits 3 (RecordOrigin) and 4
(UseRecordedOriginForNonGPS), and the new AHRS_ORIGIN_LAT/LON/ALT
parameters that allow saving and restoring the EKF origin across
power cycles for indoor/non-GPS flight.
Update the non-GPS navigation landing page with a new section on
persistent origin storage, and update the indoor flying page to
reference the new capability.
Relates to ArduPilot PR #31177.
Copy file name to clipboardExpand all lines: common/source/docs/common-non-gps-navigation-landing-page.rst
+24Lines changed: 24 additions & 0 deletions
Display the source diff
Display the rich diff
Original file line number
Diff line number
Diff line change
@@ -43,6 +43,30 @@ These are the available options that allow a vehicle to estimate its position wi
43
43
44
44
.. image:: ../../../images/setorigin.jpg
45
45
46
+
Persistent Origin Storage
47
+
=========================
48
+
49
+
In ArduPilot 4.7 and later, the EKF origin can be automatically saved and restored across power cycles using the following parameters:
50
+
51
+
- :ref:`AHRS_OPTIONS<AHRS_OPTIONS>` bit 3 (RecordOrigin): When enabled, the current EKF origin is automatically saved to parameters whenever it becomes valid (e.g. after GPS lock or manual origin set). The saved origin is stored in:
52
+
53
+
- :ref:`AHRS_ORIGIN_LAT<AHRS_ORIGIN_LAT>` - Last known origin latitude (degrees)
54
+
- :ref:`AHRS_ORIGIN_LON<AHRS_ORIGIN_LON>` - Last known origin longitude (degrees)
55
+
- :ref:`AHRS_ORIGIN_ALT<AHRS_ORIGIN_ALT>` - Last known origin altitude (meters)
56
+
57
+
- :ref:`AHRS_OPTIONS<AHRS_OPTIONS>` bit 4 (UseRecordedOriginForNonGPS): When enabled, the AHRS will automatically restore the saved origin on boot when GPS is not being used. This allows position-controlled flight modes (Loiter, Auto, Guided, etc.) to work indoors without GPS after the origin has been recorded from a previous flight.
58
+
59
+
This eliminates the need to manually set the origin via GCS or Lua script on every power cycle when flying indoors with non-GPS position sources.
60
+
61
+
**Typical setup for indoor flight with optical flow or external navigation:**
62
+
63
+
1. Enable :ref:`AHRS_OPTIONS<AHRS_OPTIONS>` bit 3 to auto-record the origin
64
+
2. Fly outdoors first (or manually set :ref:`AHRS_ORIGIN_LAT<AHRS_ORIGIN_LAT>`, :ref:`AHRS_ORIGIN_LON<AHRS_ORIGIN_LON>`, :ref:`AHRS_ORIGIN_ALT<AHRS_ORIGIN_ALT>`) to establish a valid origin
65
+
3. Enable :ref:`AHRS_OPTIONS<AHRS_OPTIONS>` bit 4 to auto-restore the origin for non-GPS flights
66
+
4. On subsequent indoor flights, the origin will be automatically restored from the saved parameters
67
+
68
+
.. note:: ArduSub enables bit 4 (UseRecordedOriginForNonGPS) by default since underwater vehicles typically operate without GPS.
69
+
46
70
.. note::
47
71
The low cost IMUs (accelerometers, gyros, compass) used in most autopilots drift too quickly to allow position estimation without an external velocity or position source. In other words, low-cost IMUs on their own are not sufficient for estimating position.
\* Autonomous and semi-autonomous modes require a position estimate. This can come from GPS or from :ref:`Non-GPS Navigation <common-non-gps-navigation-landing-page>` sources such as optical flow, external navigation, or motion capture systems. In ArduPilot 4.7 and later, the EKF origin can be automatically saved and restored across power cycles — see :ref:`Persistent Origin Storage <common-non-gps-navigation-landing-page>` for details.
66
66
67
67
\*\* Non-autonomous modes include :ref:`Stabilize <stabilize-mode>` and :ref:`AltHold <altholdmode>`
0 commit comments