From 49a5abf70103526074538cecdd733b34b1aacc59 Mon Sep 17 00:00:00 2001
From: olliw42 <6089567+olliw42@users.noreply.github.com>
Date: Thu, 25 Feb 2021 02:18:41 +0100
Subject: [PATCH] specify enum values explicitely, yet again (#1592)
---
message_definitions/v1.0/common.xml | 30 ++++++++++++++---------------
1 file changed, 15 insertions(+), 15 deletions(-)
diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml
index 8fa18a5e17..b778cad67c 100644
--- a/message_definitions/v1.0/common.xml
+++ b/message_definitions/v1.0/common.xml
@@ -293,22 +293,22 @@
-
+
-
+
-
+
-
+
-
+
-
+
@@ -2300,31 +2300,31 @@
ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission.
-
+
Command / mission item is ok.
-
+
Generic error message if none of the other reasons fails or if no detailed error reporting is implemented.
-
+
The system is refusing to accept this command from this source / communication partner.
-
+
Command or mission item is not supported, other commands would be accepted.
-
+
The coordinate frame of this command / mission item is not supported.
-
+
The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible.
-
+
The X or latitude value is out of range.
-
+
The Y or longitude value is out of range.
-
+
The Z or altitude value is out of range.