Non-GPS Position Estimation¶
This page explains how MAVLink can be used to send in external position and velocity estimates to ArduPilot’s EKF allowing it to maintain a position estimate and thus control itself without a GPS
This is also called “External Navigation” although to be more precise it involves estimation rather than navigation or control.
Note
The user wiki pages for Non-GPS navigation is here and GPS/Non-GPS transitions is here
Any of the following messages should be sent in at 4hz or higher:
ODOMETRY (the preferred method)
VISION_POSITION_ESTIMATE and optionally VISION_SPEED_ESTIMATE
GLOBAL_VISION_POSITION_ESTIMATE (not recommended)
GPS_INPUT (not recommended)
ArduPilot’s parameters should be setup as if a ModalAI VOXL is used which includes:
Set VISO_TYPE = 3 (VOXL)
Set VISO_POS_X, VISO_POS_Y, VISO_POS_Z to the camera’s position on the vehicle
Set EK3_SRC1_POSXY = 6 (ExternalNav)
Set EK3_SRC1_VELXY = 6 (ExternalNav) or 0 (None)
Set EK3_SRC1_POSZ = 6 (ExternalNav) or 1 (Baro)
Set EK3_SRC1_VELZ = 6 (ExternalNav) or 0 (None)
Set EK3_SRC1_YAW = 6 (ExternalNav) or 1 (Compass)
In addition it may be useful to setup GPS/Non-GPS transitions to allow switching between GPS and External Navigation
If no GPS is attached to the autopilot then the EKF origin must be set before the EKF can start estimating its position. If the vehicle will always be flown at the same location the ahrs-set-origin.lua script may be used
ODOMETRY message¶
The preferred method is to send an ODOMETRY with the fields populated as described below:
Field Name | Type | Description |
---|---|---|
time_usec | uint64_t | Timestamp since system boot. This does not need to be syncronised with the autopilot's time |
frame_id | uint8_t | MAV_FRAME_BODY_FRD (12) or MAV_FRAME_LOCAL_FRD (20) |
child_frame_id | uint8_t | MAV_FRAME_BODY_FRD (12) or MAV_FRAME_LOCAL_FRD (20) |
x | float | X position in meters |
y | float | Y position in meters |
z | float | Z position in meters (positive is down) |
q | float[4] | Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) |
vx | float | X axis linear speed in m/s |
vy | float | Y axis linear speed in m/s |
vz | float | Z axis linear speed in m/s (positive is down) |
rollspeed | float | Roll angular speed in rad/s (backwards is positive) |
pitchspeed | float | Pitch angular speed in rad/s (forward is positive) |
yawspeed | float | Yaw angular speed in rad/s (clockwise is positive) |
pos_covariance | float[21] | not used |
velocity_covariance | float[21] | not used |
reset_counter | uint8_t | External estimator reset counter. This should be incremented when the estimate resets position, velocity, attitude or angular speed |
estimator_type | uint8_t | not used |
quality | uint8_t | quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality |