diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml index 67d19a46735..9bb59ba9f7f 100644 --- a/message_definitions/v1.0/common.xml +++ b/message_definitions/v1.0/common.xml @@ -1053,7 +1053,12 @@ Empty - Changes the home location either to the current location or a specified location. + + Sets the home position to either to the current position or a specified position. + The home position is the default position that the system will return to and land on. + The position is set automatically by the system during the takeoff (and may also be set using this command). + Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242). + Use current location (MAV_BOOL_FALSE: use specified location). Values not equal to 0 or 1 are invalid. Empty Empty