From 0982e5cdac306a3d0491fe794904f315cc548e29 Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Thu, 11 May 2023 10:35:33 +1000 Subject: [PATCH 1/2] common.xml: Add MAV_RESULT_COMMAND_LONG_ONLY and MAV_RESULT_COMMAND_INT_ONLY to MAV_RESULT (#1982) * common.xml: Add MAV_RESULT_COMMAND_LONG_ONLY value to MAV_RESULT enum * common.xml: Add MAV_RESULT_COMMAND_INT_ONLY value to MAV_RESULT enum --- message_definitions/v1.0/common.xml | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml index 2e0fefc6f0..7fc13b9deb 100644 --- a/message_definitions/v1.0/common.xml +++ b/message_definitions/v1.0/common.xml @@ -2278,6 +2278,12 @@ Command is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation. There is no need for the sender to retry the command, but if done during execution, the component will return MAV_RESULT_IN_PROGRESS with an updated progress. + + Command is valid, but it is only accepted when sent as a COMMAND_LONG (as it has float values for params 5 and 6). + + + Command is valid, but it is only accepted when sent as a COMMAND_INT (as it encodes a location in params 5, 6 and 7, and hence requires a reference MAV_FRAME). + Result of mission operation (in a MISSION_ACK message). From cb2ed9f2c4de1374ac58d5d3416b91680a90ec84 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Nov 2023 10:56:05 +1100 Subject: [PATCH 2/2] common.xml: remove validity requirement for COMMAND_INT_ONLY (#2059) ... and COMMAND_LONG_ONLY It doesn't really matter why the command is being rejected, just that it is. Adding constraints about why an autopilot might send the message reduces the usefulness of this. --- message_definitions/v1.0/common.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml index 7fc13b9deb..ffb8e4e375 100644 --- a/message_definitions/v1.0/common.xml +++ b/message_definitions/v1.0/common.xml @@ -2279,10 +2279,10 @@ Command is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation. There is no need for the sender to retry the command, but if done during execution, the component will return MAV_RESULT_IN_PROGRESS with an updated progress. - Command is valid, but it is only accepted when sent as a COMMAND_LONG (as it has float values for params 5 and 6). + Command is only accepted when sent as a COMMAND_LONG. - Command is valid, but it is only accepted when sent as a COMMAND_INT (as it encodes a location in params 5, 6 and 7, and hence requires a reference MAV_FRAME). + Command is only accepted when sent as a COMMAND_INT.