From 3d6f08ec738743a4de38ec41b0956197c0b2f184 Mon Sep 17 00:00:00 2001 From: Hunter McClelland Date: Tue, 31 Mar 2026 23:23:41 -0400 Subject: [PATCH] common(add): MAV_CMD_NAV_ARC_WAYPOINT (36) promoted from development (#2444) --- message_definitions/v1.0/common.xml | 10 ++++++++++ message_definitions/v1.0/development.xml | 12 ------------ 2 files changed, 10 insertions(+), 12 deletions(-) diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml index e2c7e98a..dd1af9a1 100644 --- a/message_definitions/v1.0/common.xml +++ b/message_definitions/v1.0/common.xml @@ -1299,6 +1299,16 @@ 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. + + 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. + + 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. + Latitude + Longitude + Altitude + 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. diff --git a/message_definitions/v1.0/development.xml b/message_definitions/v1.0/development.xml index 000a1e15..7aaa8ace 100644 --- a/message_definitions/v1.0/development.xml +++ b/message_definitions/v1.0/development.xml @@ -117,18 +117,6 @@ 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 - - - - 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. - - 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. - Latitude - Longitude - Altitude - 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.