Skip to content

Commit f5eeecf

Browse files
MattKearpeterbarker
authored andcommitted
Development.xml: Add WP_ARC command
1 parent a24e276 commit f5eeecf

File tree

1 file changed

+11
-0
lines changed

1 file changed

+11
-0
lines changed

message_definitions/v1.0/development.xml

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -128,6 +128,17 @@
128128
<!-- * the data payload of mavlink commands (as used in the COMMAND_INT and COMMAND_LONG messages) -->
129129
<!-- ALL the entries in the MAV_CMD enum have a maximum of 7 parameters -->
130130
<enum name="MAV_CMD">
131+
<entry value="36" name="MAV_CMD_NAV_ARC_WAYPOINT" hasLocation="true" isDestination="true">
132+
<!-- This message is work-in-progress it can therefore change, and should NOT be used in stable production environments -->
133+
<description>Circular arc path waypoint.
134+
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).
135+
The resulting path is a circular arc in the NE frame, with the difference in height being defined by the difference in waypoint altitudes.
136+
</description>
137+
<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>
138+
<param index="5" label="Latitude">Latitude</param>
139+
<param index="6" label="Longitude">Longitude</param>
140+
<param index="7" label="Altitude" units="m">Altitude</param>
141+
</entry>
131142
<entry value="610" name="MAV_CMD_DO_SET_SYS_CMP_ID" hasLocation="false" isDestination="false">
132143
<description>
133144
Set system and component id.

0 commit comments

Comments
 (0)