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 or COMMAND_INT message.

MAV_CMD_DO_SET_HOME within COMMAND_INT

Set the home location by sending a COMMAND_INT with the command and parameter fields set as specified for the MAV_CMD_DO_SET_HOME command.

Command Field Type Description
target_system uint8_t System ID
target_component uint8_t Component ID of flight controller or just 0
frame uint8_t MAV_FRAME_GLOBAL=0
command uint16_t MAV_CMD_DO_SET_HOME=179
current uint8_t 0 (not used)
autocontinue uint8_t 0 (not used)
param1 float 1=use current location, 0=use specified location
param2 float not used
param3 float not used
param4 float not used
param5 int32_t Latitude in degrees * 10^7
param6 int32_t Longitude in degrees * 10^7
param7 float Altitude in meters

Examples

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

Example MAVProxy/SITL Command

Description

message COMMAND_INT 0 0 0 179 0 0 1 0 0 0 0 0 0

set home to the vehicle’s current location

message COMMAND_INT 0 0 0 179 0 0 0 0 0 0 -353630000 1491650000 575

set home to the specified location

MAV_CMD_DO_SET_HOME within COMMAND_LONG

Set the home location by sending a COMMAND_LONG with the command and parameter fields set as specified for the MAV_CMD_DO_SET_HOME command. Note that this method sets the home position with less accuracy than the COMMAND_INT method from above.

Command Field Type Description
target_system uint8_t System ID
target_component uint8_t Component ID of flight controller or just 0
command uint16_t MAV_CMD_DO_SET_HOME=179
confirmation uint8_t 0
param1 float 1=use current location, 0=use specified location
param2 float not used
param3 float not used
param4 float not used
param5 float Latitude in degrees
param6 float Longitude in degrees
param7 float Altitude in meters

Examples

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

Example MAVProxy/SITL Command

Description

message COMMAND_LONG 0 0 179 0 1 0 0 0 0 0 0

set home to the vehicle’s current location

message COMMAND_LONG 0 0 179 0 0 0 0 0 -35.363 149.165 575

set home to the specified location

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 the following

  • 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