diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml index 162b1a1d77..ba8a746afe 100644 --- a/message_definitions/v1.0/common.xml +++ b/message_definitions/v1.0/common.xml @@ -1082,7 +1082,7 @@ Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current yaw or latitude rather than a specific value). See https://mavlink.io/en/guide/xml_schema.html#MAV_CMD for information about the structure of the MAV_CMD entries - Navigate to waypoint. + Navigate to waypoint. This is intended for use in missions (for guided commands outside of missions use MAV_CMD_DO_REPOSITION). Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing) Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached) 0 to pass through the WP, if > 0 radius to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control. @@ -1544,7 +1544,7 @@ Empty - Reposition the vehicle to a specific WGS84 global position. + Reposition the vehicle to a specific WGS84 global position. This command is intended for guided commands (for missions use MAV_CMD_NAV_WAYPOINT instead). Ground speed, less than 0 (-1) for default Bitmask of option flags. Loiter radius for planes. Positive values only, direction is controlled by Yaw value. A value of zero or NaN is ignored.