mirror of
https://github.com/mavlink/mavlink.git
synced 2026-06-19 07:35:34 +00:00
common(add): MAV_CMD_NAV_ARC_WAYPOINT (36) promoted from development (#2444)
This commit is contained in:
committed by
GitHub
parent
e01fd51a62
commit
3d6f08ec73
@@ -1299,6 +1299,16 @@
|
||||
<param index="7" label="Altitude/Z">Center point altitude MSL/Z coordinate according to MAV_FRAME. If no MAV_FRAME specified, MAV_FRAME_GLOBAL is assumed.
|
||||
INT32_MAX or NaN: Use current vehicle altitude.</param>
|
||||
</entry>
|
||||
<entry value="36" name="MAV_CMD_NAV_ARC_WAYPOINT" hasLocation="true" isDestination="true">
|
||||
<description>Circular arc path waypoint.
|
||||
This defines the end/exit point and angle (param1) of an arc path from the previous waypoint. A position is required before this command to define the start of the arc (e.g. current position, a MAV_CMD_NAV_WAYPOINT, or a MAV_CMD_NAV_ARC_WAYPOINT).
|
||||
The resulting path is a circular arc in the NE frame, with the difference in height being defined by the difference in waypoint altitudes.
|
||||
</description>
|
||||
<param index="1" label="Arc Angle" units="deg" minValue="-359" maxValue="359" increment="1">The angle in degrees from the starting position to the exit position of the arc in the NE frame. Positive values are CW arcs and negative values are CCW arcs.</param>
|
||||
<param index="5" label="Latitude">Latitude</param>
|
||||
<param index="6" label="Longitude">Longitude</param>
|
||||
<param index="7" label="Altitude" units="m">Altitude</param>
|
||||
</entry>
|
||||
<entry value="80" name="MAV_CMD_NAV_ROI" hasLocation="true" isDestination="false">
|
||||
<superseded since="2018-01" replaced_by="`MAV_CMD_DO_SET_ROI_*`"/>
|
||||
<description>Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras.</description>
|
||||
|
||||
@@ -117,18 +117,6 @@
|
||||
<!-- ALL the entries in the MAV_CMD enum have a maximum of 7 parameters -->
|
||||
<enum name="MAV_CMD">
|
||||
<description>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</description>
|
||||
<entry value="36" name="MAV_CMD_NAV_ARC_WAYPOINT" hasLocation="true" isDestination="true">
|
||||
<wip/>
|
||||
<!-- This message is work-in-progress it can therefore change, and should NOT be used in stable production environments -->
|
||||
<description>Circular arc path waypoint.
|
||||
This defines the end/exit point and angle (param1) of an arc path from the previous waypoint. A position is required before this command to define the start of the arc (e.g. current position, a MAV_CMD_NAV_WAYPOINT, or a MAV_CMD_NAV_ARC_WAYPOINT).
|
||||
The resulting path is a circular arc in the NE frame, with the difference in height being defined by the difference in waypoint altitudes.
|
||||
</description>
|
||||
<param index="1" label="Arc Angle" units="deg" minValue="-359" maxValue="359" increment="1">The angle in degrees from the starting position to the exit position of the arc in the NE frame. Positive values are CW arcs and negative values are CCW arcs.</param>
|
||||
<param index="5" label="Latitude">Latitude</param>
|
||||
<param index="6" label="Longitude">Longitude</param>
|
||||
<param index="7" label="Altitude" units="m">Altitude</param>
|
||||
</entry>
|
||||
<entry value="247" name="MAV_CMD_DO_UPGRADE" hasLocation="false" isDestination="false">
|
||||
<description>Request a target system to start an upgrade of one (or all) of its components.
|
||||
For example, the command might be sent to a companion computer to cause it to upgrade a connected flight controller.
|
||||
|
||||
Reference in New Issue
Block a user