From fdef5cc0fc80d51aa29c5b318c2b299a362863a9 Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Wed, 3 May 2023 14:03:38 +1000 Subject: [PATCH] common.xml: Prefer COMMAND_INT when command includes altitude field (#1983) --- message_definitions/v1.0/common.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml index f3c984e591..0bceaacb02 100644 --- a/message_definitions/v1.0/common.xml +++ b/message_definitions/v1.0/common.xml @@ -5531,7 +5531,7 @@ Current climb rate. - Send a command with up to seven parameters to the MAV, where params 5 and 6 are integers and the other values are floats. This is preferred over COMMAND_LONG when sending positional data in params 5 and 6, as it allows for greater precision when sending latitudes/longitudes. Param 5 and 6 encode positional data as scaled integers, where the scaling depends on the actual command value. NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). The command microservice is documented at https://mavlink.io/en/services/command.html + Send a command with up to seven parameters to the MAV, where params 5 and 6 are integers and the other values are floats. This is preferred over COMMAND_LONG as it allows the MAV_FRAME to be specified for interpreting positional information, such as altitude. COMMAND_INT is also preferred when sending latitude and longitude data in params 5 and 6, as it allows for greater precision. Param 5 and 6 encode positional data as scaled integers, where the scaling depends on the actual command value. NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). The command microservice is documented at https://mavlink.io/en/services/command.html System ID Component ID The coordinate system of the COMMAND. @@ -5547,7 +5547,7 @@ PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame). - Send a command with up to seven parameters to the MAV. COMMAND_INT is generally preferred when sending MAV_CMD commands where param 5 and param 6 contain latitude/longitude data, as sending these in floats can result in a significant loss of precision. COMMAND_LONG is required for commands that mandate float values in params 5 and 6. The command microservice is documented at https://mavlink.io/en/services/command.html + Send a command with up to seven parameters to the MAV. COMMAND_INT is generally preferred when sending MAV_CMD commands that include positional information; it offers higher precision and allows the MAV_FRAME to be specified (which may otherwise be ambiguous, particularly for altitude). The command microservice is documented at https://mavlink.io/en/services/command.html System which should execute the command Component which should execute the command, 0 for all components Command ID (of command to send).