Setting Home and/or EKF origin

This page explains how MAVLink can be used by a ground station or companion computer to get or set the home or EKF origin.

Home vs EKF Origin

The vehicles “Home” position is the location (specified as a latitude, longitude and altitude above sea level) that the vehicle will return to in RTL mode. For most vehicles this location is set to the vehicle’s current location each time the vehicle is armed but it may also be moved at any time. Moving home can be useful in situations where the user wishes RTL mode to return the vehicle to a different location than it took off from.

The “EKF origin” is the location that the EKF (aka AHRS) uses for internal calculations. This location is normally set to the vehicle’s location soon after the GPS provides a good quality location. Once set the EKF origin cannot be moved. Users are not normally aware of the EKF origin’s location unless they are using Non-GPS navigation on a vehicle with no GPS attached (without a GPS, the user must specify the EKF origin using the ground station).

Whenever the Home or EKF origin is updated the vehicle will send a HOME_POSITION or GPS_GLOBAL_ORIGIN message (respectively) on all active mavlink channels.

The home will also be sent in response to a MAV_CMD_GET_HOME_POSITION sent within a COMMAND_LONG message.

SET_HOME_POSITION

Sets the location that the vehicle will return to and land on when in RTL mode. The location is normally set automatically each time the vehicle is armed if it has not already been explicitly set by the operator.

The message definition can be found here

Command Field Type Description
target_system uint8_t System ID
latitude int32_t Latitude * 1e7
longitude int32_t Longitude * 1e7
altitude int32_t Altitude above sea level in millimeters (i.e. meters * 1000)
x float Local X position of this position in the local coordinate frame.
y float Local Y position of this position in the local coordinate frame
z float Local Z position of this position in the local coordinate frame
q float[4] World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground.
approach_x float Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
approach_y float Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
approach_z float Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.

SET_GPS_GLOBAL_ORIGIN

Sets the location used by the EKF/AHRS for internal calculations. This location is normally automatically set soon after the GPS first returns a good location. The operator may be required to set this manually if Non-GPS navigation is used. Once set the EKF origin cannot be moved.

The message definition can be found here

Command Field Type Description
target_system uint8_t System ID
latitude int32_t Latitude * 1e7
longitude int32_t Longitude * 1e7
altitude int32_t Altitude above sea level in millimeters (i.e. meters * 1000)
time_usec uint64_t Timestamp (UNIX Epoch time or time since system boot) in microseconds (us)

Example

The example command below can be copy-pasted into MAVProxy (aka SITL) to test this command. Before running these commands enter, “module load message”

  • module load message
  • param set EK3_SRC1_POSXY 0
  • param set EK3_SRC1_VELXY 0
  • param set EK3_SRC1_VELZ 0
Example MAVProxy/SITL Command Description
message SET_GPS_GLOBAL_ORIGIN 0 -353621474 1491651746 600000 0 set EKF origin to lat,lon of -35.36,149.16 and 600m above sea level