From e579ec5a1474cd54a4e7b3f235a0e1689c38a86e Mon Sep 17 00:00:00 2001 From: TSC21 Date: Tue, 20 Oct 2020 15:14:59 +0200 Subject: [PATCH 1/2] common: add MAV_CMD_CUSTOM_ACTION to define a new way of triggering a custom action on a waypoint --- message_definitions/v1.0/common.xml | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml index 7bcb70dc10..05420792c8 100644 --- a/message_definitions/v1.0/common.xml +++ b/message_definitions/v1.0/common.xml @@ -1867,6 +1867,16 @@ Empty Empty + + Custom action to execute at this specific waypoint. The definition of the action, or set of actions, to execute, as well as the associated metadata is stored in the system that is going to process the action. + Number of the custom action that will be executed. The metadata associated with this action is stored on the system that is going to process this command. + Control when the Vehicle moves to the next waypoint. 0: Use ACK from component responsible for executing the action, to move to the next Waypoint. Otherwise, move when timeout (param 3) is reached; 1: Waits for an amount of time (param 3) before moving to the next waypoint, even if the ACK is received from the component responsible for executing the action; 2: Wait for the ACK component responsible for executing the action and blocks the navigation (just moves when an ACK is received). + Used by the navigation module to set the timeout for the receiving feedback of successful execution, or to set the time of execution before moving to the next waypoint. + + + + + Create a panorama at the current position Viewing angle horizontal of the panorama (+- 0.5 the total angle) From ce4dfb39483135ac3fce38f301d15da7a0ccf720 Mon Sep 17 00:00:00 2001 From: TSC21 Date: Wed, 21 Oct 2020 11:23:47 +0200 Subject: [PATCH 2/2] common: MAV_CMD_CUSTOM_ACTION: add wip tag --- message_definitions/v1.0/common.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml index 05420792c8..a50b2dd46a 100644 --- a/message_definitions/v1.0/common.xml +++ b/message_definitions/v1.0/common.xml @@ -1868,6 +1868,7 @@ Empty + Custom action to execute at this specific waypoint. The definition of the action, or set of actions, to execute, as well as the associated metadata is stored in the system that is going to process the action. Number of the custom action that will be executed. The metadata associated with this action is stored on the system that is going to process this command. Control when the Vehicle moves to the next waypoint. 0: Use ACK from component responsible for executing the action, to move to the next Waypoint. Otherwise, move when timeout (param 3) is reached; 1: Waits for an amount of time (param 3) before moving to the next waypoint, even if the ACK is received from the component responsible for executing the action; 2: Wait for the ACK component responsible for executing the action and blocks the navigation (just moves when an ACK is received).