Skip to content

Commit

Permalink
autogenerated headers for rev https://github.com/Dronecode/air-iop-de…
Browse files Browse the repository at this point in the history
  • Loading branch information
DronecodeBot committed May 20, 2023
1 parent c0801c8 commit e9f4a35
Show file tree
Hide file tree
Showing 19 changed files with 1,413 additions and 240 deletions.
27 changes: 6 additions & 21 deletions common/common.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
#error Wrong include order: MAVLINK_COMMON.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
#endif

#define MAVLINK_COMMON_XML_HASH 1730073812041187410
#define MAVLINK_COMMON_XML_HASH -1960458952797604557

#ifdef __cplusplus
extern "C" {
Expand Down Expand Up @@ -727,24 +727,6 @@ typedef enum MAV_ROI
} MAV_ROI;
#endif

/** @brief ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. */
#ifndef HAVE_ENUM_MAV_CMD_ACK
#define HAVE_ENUM_MAV_CMD_ACK
typedef enum MAV_CMD_ACK
{
MAV_CMD_ACK_OK=0, /* Command / mission item is ok. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
MAV_CMD_ACK_ERR_FAIL=1, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
MAV_CMD_ACK_ERR_ACCESS_DENIED=2, /* The system is refusing to accept this command from this source / communication partner. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
MAV_CMD_ACK_ERR_NOT_SUPPORTED=3, /* Command or mission item is not supported, other commands would be accepted. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED=4, /* The coordinate frame of this command / mission item is not supported. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE=5, /* 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. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE=6, /* The X or latitude value is out of range. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE=7, /* The Y or longitude value is out of range. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE=8, /* The Z or altitude value is out of range. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
MAV_CMD_ACK_ENUM_END=9, /* | */
} MAV_CMD_ACK;
#endif

/** @brief Specifies the datatype of a MAVLink parameter. */
#ifndef HAVE_ENUM_MAV_PARAM_TYPE
#define HAVE_ENUM_MAV_PARAM_TYPE
Expand Down Expand Up @@ -796,7 +778,9 @@ typedef enum MAV_RESULT
MAV_RESULT_FAILED=4, /* Command is valid, but execution has failed. This is used to indicate any non-temporary or unexpected problem, i.e. any problem that must be fixed before the command can succeed/be retried. For example, attempting to write a file when out of memory, attempting to arm when sensors are not calibrated, etc. | */
MAV_RESULT_IN_PROGRESS=5, /* 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. | */
MAV_RESULT_CANCELLED=6, /* Command has been cancelled (as a result of receiving a COMMAND_CANCEL message). | */
MAV_RESULT_ENUM_END=7, /* | */
MAV_RESULT_COMMAND_LONG_ONLY=7, /* Command is valid, but it is only accepted when sent as a COMMAND_LONG (as it has float values for params 5 and 6). | */
MAV_RESULT_COMMAND_INT_ONLY=8, /* 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). | */
MAV_RESULT_ENUM_END=9, /* | */
} MAV_RESULT;
#endif

Expand Down Expand Up @@ -1444,7 +1428,8 @@ typedef enum CAMERA_ZOOM_TYPE
ZOOM_TYPE_CONTINUOUS=1, /* Continuous zoom up/down until stopped (-1 for wide, 1 for tele, 0 to stop zooming) | */
ZOOM_TYPE_RANGE=2, /* Zoom value as proportion of full camera range (a percentage value between 0.0 and 100.0) | */
ZOOM_TYPE_FOCAL_LENGTH=3, /* Zoom value/variable focal length in millimetres. Note that there is no message to get the valid zoom range of the camera, so this can type can only be used for cameras where the zoom range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera) | */
CAMERA_ZOOM_TYPE_ENUM_END=4, /* | */
ZOOM_TYPE_HORIZONTAL_FOV=4, /* Zoom value as horizontal field of view in degrees. | */
CAMERA_ZOOM_TYPE_ENUM_END=5, /* | */
} CAMERA_ZOOM_TYPE;
#endif

Expand Down
2 changes: 1 addition & 1 deletion common/mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#ifndef MAVLINK_H
#define MAVLINK_H

#define MAVLINK_PRIMARY_XML_HASH 1730073812041187410
#define MAVLINK_PRIMARY_XML_HASH -1960458952797604557

#ifndef MAVLINK_STX
#define MAVLINK_STX 253
Expand Down
20 changes: 10 additions & 10 deletions common/mavlink_msg_command_ack.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@
typedef struct __mavlink_command_ack_t {
uint16_t command; /*< Command ID (of acknowledged command).*/
uint8_t result; /*< Result of command.*/
uint8_t progress; /*< Also used as result_param1, it can be set with an enum containing the errors reasons of why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS (UINT8_MAX if the progress is unknown).*/
int32_t result_param2; /*< Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.*/
uint8_t progress; /*< [%] The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown.*/
int32_t result_param2; /*< Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown").*/
uint8_t target_system; /*< System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.*/
uint8_t target_component; /*< Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.*/
} mavlink_command_ack_t;
Expand Down Expand Up @@ -58,8 +58,8 @@ typedef struct __mavlink_command_ack_t {
*
* @param command Command ID (of acknowledged command).
* @param result Result of command.
* @param progress Also used as result_param1, it can be set with an enum containing the errors reasons of why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS (UINT8_MAX if the progress is unknown).
* @param result_param2 Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
* @param progress [%] The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown.
* @param result_param2 Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown").
* @param target_system System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
* @param target_component Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
* @return length of the message in bytes (excluding serial stream start sign)
Expand Down Expand Up @@ -101,8 +101,8 @@ static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t c
* @param msg The MAVLink message to compress the data into
* @param command Command ID (of acknowledged command).
* @param result Result of command.
* @param progress Also used as result_param1, it can be set with an enum containing the errors reasons of why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS (UINT8_MAX if the progress is unknown).
* @param result_param2 Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
* @param progress [%] The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown.
* @param result_param2 Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown").
* @param target_system System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
* @param target_component Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
* @return length of the message in bytes (excluding serial stream start sign)
Expand Down Expand Up @@ -170,8 +170,8 @@ static inline uint16_t mavlink_msg_command_ack_encode_chan(uint8_t system_id, ui
*
* @param command Command ID (of acknowledged command).
* @param result Result of command.
* @param progress Also used as result_param1, it can be set with an enum containing the errors reasons of why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS (UINT8_MAX if the progress is unknown).
* @param result_param2 Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
* @param progress [%] The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown.
* @param result_param2 Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown").
* @param target_system System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
* @param target_component Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
*/
Expand Down Expand Up @@ -278,7 +278,7 @@ static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t
/**
* @brief Get field progress from command_ack message
*
* @return Also used as result_param1, it can be set with an enum containing the errors reasons of why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS (UINT8_MAX if the progress is unknown).
* @return [%] The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown.
*/
static inline uint8_t mavlink_msg_command_ack_get_progress(const mavlink_message_t* msg)
{
Expand All @@ -288,7 +288,7 @@ static inline uint8_t mavlink_msg_command_ack_get_progress(const mavlink_message
/**
* @brief Get field result_param2 from command_ack message
*
* @return Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
* @return Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown").
*/
static inline int32_t mavlink_msg_command_ack_get_result_param2(const mavlink_message_t* msg)
{
Expand Down
10 changes: 5 additions & 5 deletions common/mavlink_msg_mission_current.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

typedef struct __mavlink_mission_current_t {
uint16_t seq; /*< Sequence*/
uint16_t total; /*< Total number of mission items. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.*/
uint16_t total; /*< Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.*/
uint8_t mission_state; /*< Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.*/
uint8_t mission_mode; /*< Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode).*/
} mavlink_mission_current_t;
Expand Down Expand Up @@ -51,7 +51,7 @@ typedef struct __mavlink_mission_current_t {
* @param msg The MAVLink message to compress the data into
*
* @param seq Sequence
* @param total Total number of mission items. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.
* @param total Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.
* @param mission_state Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.
* @param mission_mode Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode).
* @return length of the message in bytes (excluding serial stream start sign)
Expand Down Expand Up @@ -88,7 +88,7 @@ static inline uint16_t mavlink_msg_mission_current_pack(uint8_t system_id, uint8
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param seq Sequence
* @param total Total number of mission items. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.
* @param total Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.
* @param mission_state Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.
* @param mission_mode Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode).
* @return length of the message in bytes (excluding serial stream start sign)
Expand Down Expand Up @@ -151,7 +151,7 @@ static inline uint16_t mavlink_msg_mission_current_encode_chan(uint8_t system_id
* @param chan MAVLink channel to send the message
*
* @param seq Sequence
* @param total Total number of mission items. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.
* @param total Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.
* @param mission_state Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.
* @param mission_mode Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode).
*/
Expand Down Expand Up @@ -240,7 +240,7 @@ static inline uint16_t mavlink_msg_mission_current_get_seq(const mavlink_message
/**
* @brief Get field total from mission_current message
*
* @return Total number of mission items. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.
* @return Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.
*/
static inline uint16_t mavlink_msg_mission_current_get_total(const mavlink_message_t* msg)
{
Expand Down
Loading

0 comments on commit e9f4a35

Please sign in to comment.