mirror of
https://github.com/mavlink/mavlink.git
synced 2026-06-19 07:35:34 +00:00
common.xml: Prefer COMMAND_INT when command includes altitude field (#1983)
This commit is contained in:
@@ -5531,7 +5531,7 @@
|
||||
<field type="float" name="climb" units="m/s">Current climb rate.</field>
|
||||
</message>
|
||||
<message id="75" name="COMMAND_INT">
|
||||
<description>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</description>
|
||||
<description>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</description>
|
||||
<field type="uint8_t" name="target_system">System ID</field>
|
||||
<field type="uint8_t" name="target_component">Component ID</field>
|
||||
<field type="uint8_t" name="frame" enum="MAV_FRAME">The coordinate system of the COMMAND.</field>
|
||||
@@ -5547,7 +5547,7 @@
|
||||
<field type="float" name="z" invalid="NaN">PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).</field>
|
||||
</message>
|
||||
<message id="76" name="COMMAND_LONG">
|
||||
<description>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</description>
|
||||
<description>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</description>
|
||||
<field type="uint8_t" name="target_system">System which should execute the command</field>
|
||||
<field type="uint8_t" name="target_component">Component which should execute the command, 0 for all components</field>
|
||||
<field type="uint16_t" name="command" enum="MAV_CMD">Command ID (of command to send).</field>
|
||||
|
||||
Reference in New Issue
Block a user