diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml index f657bf8e33..713c76ffa3 100644 --- a/message_definitions/v1.0/common.xml +++ b/message_definitions/v1.0/common.xml @@ -314,20 +314,30 @@ + Actions following geofence breach. - Disable fenced mode + Disable fenced mode. If used in a plan this would mean the next fence is disabled. - Switched to guided mode to return point (fence point 0) + Fly to geofence MAV_CMD_NAV_FENCE_RETURN_POINT in GUIDED mode. Note: This action is only supported by ArduPlane, and may not be supported in all versions. Report fence breach, but don't take action - Switched to guided mode to return point (fence point 0) with manual throttle control + Fly to geofence MAV_CMD_NAV_FENCE_RETURN_POINT with manual throttle control in GUIDED mode. Note: This action is only supported by ArduPlane, and may not be supported in all versions. - Switch to RTL (return to launch) mode and head for the return point. + Return/RTL mode. + + + Hold at current location. + + + Termination failsafe. Motors are shut down (some flight stacks may trigger other failsafe actions). + + + Land at current location. @@ -2027,6 +2037,7 @@ Longitude Reserved + Rally point. You can have multiple rally points defined. diff --git a/message_definitions/v1.0/development.xml b/message_definitions/v1.0/development.xml index 3413568f57..9380b0751b 100644 --- a/message_definitions/v1.0/development.xml +++ b/message_definitions/v1.0/development.xml @@ -44,6 +44,25 @@ Synthetic/calculated airspeed. + + + + + + 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 + + + + Sets the action on geofence breach. + If sent using the command protocol this sets the system-default geofence action. + As part of a mission protocol plan it sets the fence action for the next complete geofence definition *after* the command. + Note: A fence action defined in a plan will override the default system setting (even if the system-default is `FENCE_ACTION_NONE`). + Note: Every geofence in a plan can have its own action; if no fence action is defined for a particular fence the system-default will be used. + Note: The flight stack should reject a plan or command that uses a geofence action that it does not support and send a STATUSTEXT with the reason. + + Fence action on breach. + +