From 9ccf420ae86e0cd9d3c5a29251f88e2dddc1f12f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Matej=20Fran=C4=8De=C5=A1kin?= Date: Wed, 11 Dec 2024 09:19:54 +0100 Subject: [PATCH] auterion: move param transaction protocol to auterion --- message_definitions/v1.0/auterion.xml | 38 ++++++++++++++++++++++++ message_definitions/v1.0/common.xml | 8 ++--- message_definitions/v1.0/development.xml | 38 ------------------------ 3 files changed, 41 insertions(+), 43 deletions(-) diff --git a/message_definitions/v1.0/auterion.xml b/message_definitions/v1.0/auterion.xml index fbfc155207..02883bf697 100644 --- a/message_definitions/v1.0/auterion.xml +++ b/message_definitions/v1.0/auterion.xml @@ -7,6 +7,12 @@ 0 + + Request to start or end a parameter transaction. Multiple kinds of transport layers can be used to exchange parameters in the transaction (param, param_ext and mavftp). The command response can either be a success/failure or an in progress in case the receiving side takes some time to apply the parameters. + Action to be performed (start, commit, cancel, etc.) + Possible transport layers to set and get parameters via mavlink during a parameter transaction. + Identifier for a specific transaction. + @@ -88,8 +94,40 @@ Decision to deny the handoff request and keep control ownership. + + + Possible transport layers to set and get parameters via mavlink during a parameter transaction. + + Transaction over param transport. + + + Transaction over param_ext transport. + + + + Possible parameter transaction actions. + + Commit the current parameter transaction. + + + Commit the current parameter transaction. + + + Cancel the current parameter transaction. + + + + + Response from a PARAM_SET message when it is used in a transaction. + Id of system that sent PARAM_SET message. + Id of system that sent PARAM_SET message. + Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + Parameter value (new value if PARAM_ACCEPTED, current value otherwise) + Parameter type. + Result code. + Position of and distance to a Beacon. diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml index e32d0f3cd7..7691703aab 100644 --- a/message_definitions/v1.0/common.xml +++ b/message_definitions/v1.0/common.xml @@ -2154,7 +2154,6 @@ Target tag to jump to. Repeat count. - Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. Pitch angle (positive to pitch up, relative to vehicle for FOLLOW mode, relative to world horizon for LOCK mode). @@ -3925,7 +3924,7 @@ - Result from PARAM_EXT_SET message (or a PARAM_SET within a transaction). + Result from PARAM_EXT_SET message. Parameter value ACCEPTED and SET @@ -3936,7 +3935,7 @@ Parameter failed to set - Parameter value received but not yet set/accepted. A subsequent PARAM_ACK_TRANSACTION or PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating that the the parameter was received and does not need to be resent. + Parameter value received but not yet set/accepted. A subsequent PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating that the the parameter was received and does not need to be resent. @@ -5179,7 +5178,6 @@ The new autopilot-specific mode. This field can be ignored by an autopilot. - Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also https://mavlink.io/en/services/parameter.html for a full documentation of QGroundControl and IMU code. System ID @@ -5203,7 +5201,7 @@ Set a parameter value (write new value to permanent storage). The receiving component should acknowledge the new parameter value by broadcasting a PARAM_VALUE message (broadcasting ensures that multiple GCS all have an up-to-date list of all parameters). If the sending GCS did not receive a PARAM_VALUE within its timeout time, it should re-send the PARAM_SET message. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html. - PARAM_SET may also be called within the context of a transaction (started with MAV_CMD_PARAM_TRANSACTION). Within a transaction the receiving component should respond with PARAM_ACK_TRANSACTION to the setter component (instead of broadcasting PARAM_VALUE), and PARAM_SET should be re-sent if this is ACK not received. + System ID Component ID Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string diff --git a/message_definitions/v1.0/development.xml b/message_definitions/v1.0/development.xml index 3aa45b5cb5..39b49f5db3 100644 --- a/message_definitions/v1.0/development.xml +++ b/message_definitions/v1.0/development.xml @@ -35,28 +35,6 @@ True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control. - - - Possible transport layers to set and get parameters via mavlink during a parameter transaction. - - Transaction over param transport. - - - Transaction over param_ext transport. - - - - Possible parameter transaction actions. - - Commit the current parameter transaction. - - - Commit the current parameter transaction. - - - Cancel the current parameter transaction. - - Standard modes with a well understood meaning across flight stacks and vehicle types. For example, most flight stack have the concept of a "return" or "RTL" mode that takes a vehicle to safety, even though the precise mechanics of this mode may differ. @@ -292,12 +270,6 @@ 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. - - Request to start or end a parameter transaction. Multiple kinds of transport layers can be used to exchange parameters in the transaction (param, param_ext and mavftp). The command response can either be a success/failure or an in progress in case the receiving side takes some time to apply the parameters. - Action to be performed (start, commit, cancel, etc.) - Possible transport layers to set and get parameters via mavlink during a parameter transaction. - Identifier for a specific transaction. - 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. @@ -522,16 +494,6 @@ - - - Response from a PARAM_SET message when it is used in a transaction. - Id of system that sent PARAM_SET message. - Id of system that sent PARAM_SET message. - Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Parameter value (new value if PARAM_ACCEPTED, current value otherwise) - Parameter type. - Result code. - Airspeed information from a sensor. Sensor ID.