mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-19 06:15:14 +03:00
MAVLink V2 library (auto-generated)
This commit is contained in:
parent
f58ef63cb4
commit
c644fdf9ea
132 changed files with 36223 additions and 1470 deletions
|
@ -7,11 +7,15 @@
|
|||
typedef struct __mavlink_command_ack_t {
|
||||
uint16_t command; /*< Command ID (of acknowledged command).*/
|
||||
uint8_t result; /*< Result of command.*/
|
||||
uint8_t progress; /*< WIP: 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 (255 if the progress is unknown).*/
|
||||
int32_t result_param2; /*< WIP: Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.*/
|
||||
uint8_t target_system; /*< WIP: 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; /*< WIP: 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;
|
||||
|
||||
#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3
|
||||
#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 10
|
||||
#define MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN 3
|
||||
#define MAVLINK_MSG_ID_77_LEN 3
|
||||
#define MAVLINK_MSG_ID_77_LEN 10
|
||||
#define MAVLINK_MSG_ID_77_MIN_LEN 3
|
||||
|
||||
#define MAVLINK_MSG_ID_COMMAND_ACK_CRC 143
|
||||
|
@ -23,17 +27,25 @@ typedef struct __mavlink_command_ack_t {
|
|||
#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \
|
||||
77, \
|
||||
"COMMAND_ACK", \
|
||||
2, \
|
||||
6, \
|
||||
{ { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \
|
||||
{ "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \
|
||||
{ "progress", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_command_ack_t, progress) }, \
|
||||
{ "result_param2", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_command_ack_t, result_param2) }, \
|
||||
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_command_ack_t, target_system) }, \
|
||||
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_command_ack_t, target_component) }, \
|
||||
} \
|
||||
}
|
||||
#else
|
||||
#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \
|
||||
"COMMAND_ACK", \
|
||||
2, \
|
||||
6, \
|
||||
{ { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \
|
||||
{ "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \
|
||||
{ "progress", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_command_ack_t, progress) }, \
|
||||
{ "result_param2", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_command_ack_t, result_param2) }, \
|
||||
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_command_ack_t, target_system) }, \
|
||||
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_command_ack_t, target_component) }, \
|
||||
} \
|
||||
}
|
||||
#endif
|
||||
|
@ -46,21 +58,33 @@ typedef struct __mavlink_command_ack_t {
|
|||
*
|
||||
* @param command Command ID (of acknowledged command).
|
||||
* @param result Result of command.
|
||||
* @param progress WIP: 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 (255 if the progress is unknown).
|
||||
* @param result_param2 WIP: Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
|
||||
* @param target_system WIP: 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 WIP: 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)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
uint16_t command, uint8_t result)
|
||||
uint16_t command, uint8_t result, uint8_t progress, int32_t result_param2, uint8_t target_system, uint8_t target_component)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN];
|
||||
_mav_put_uint16_t(buf, 0, command);
|
||||
_mav_put_uint8_t(buf, 2, result);
|
||||
_mav_put_uint8_t(buf, 3, progress);
|
||||
_mav_put_int32_t(buf, 4, result_param2);
|
||||
_mav_put_uint8_t(buf, 8, target_system);
|
||||
_mav_put_uint8_t(buf, 9, target_component);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
|
||||
#else
|
||||
mavlink_command_ack_t packet;
|
||||
packet.command = command;
|
||||
packet.result = result;
|
||||
packet.progress = progress;
|
||||
packet.result_param2 = result_param2;
|
||||
packet.target_system = target_system;
|
||||
packet.target_component = target_component;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
|
||||
#endif
|
||||
|
@ -77,22 +101,34 @@ 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 WIP: 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 (255 if the progress is unknown).
|
||||
* @param result_param2 WIP: Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
|
||||
* @param target_system WIP: 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 WIP: 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)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
uint16_t command,uint8_t result)
|
||||
uint16_t command,uint8_t result,uint8_t progress,int32_t result_param2,uint8_t target_system,uint8_t target_component)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN];
|
||||
_mav_put_uint16_t(buf, 0, command);
|
||||
_mav_put_uint8_t(buf, 2, result);
|
||||
_mav_put_uint8_t(buf, 3, progress);
|
||||
_mav_put_int32_t(buf, 4, result_param2);
|
||||
_mav_put_uint8_t(buf, 8, target_system);
|
||||
_mav_put_uint8_t(buf, 9, target_component);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
|
||||
#else
|
||||
mavlink_command_ack_t packet;
|
||||
packet.command = command;
|
||||
packet.result = result;
|
||||
packet.progress = progress;
|
||||
packet.result_param2 = result_param2;
|
||||
packet.target_system = target_system;
|
||||
packet.target_component = target_component;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
|
||||
#endif
|
||||
|
@ -111,7 +147,7 @@ static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint
|
|||
*/
|
||||
static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack)
|
||||
{
|
||||
return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result);
|
||||
return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result, command_ack->progress, command_ack->result_param2, command_ack->target_system, command_ack->target_component);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -125,7 +161,7 @@ static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t
|
|||
*/
|
||||
static inline uint16_t mavlink_msg_command_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack)
|
||||
{
|
||||
return mavlink_msg_command_ack_pack_chan(system_id, component_id, chan, msg, command_ack->command, command_ack->result);
|
||||
return mavlink_msg_command_ack_pack_chan(system_id, component_id, chan, msg, command_ack->command, command_ack->result, command_ack->progress, command_ack->result_param2, command_ack->target_system, command_ack->target_component);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -134,21 +170,33 @@ 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 WIP: 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 (255 if the progress is unknown).
|
||||
* @param result_param2 WIP: Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
|
||||
* @param target_system WIP: 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 WIP: 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.
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t command, uint8_t result)
|
||||
static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t command, uint8_t result, uint8_t progress, int32_t result_param2, uint8_t target_system, uint8_t target_component)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN];
|
||||
_mav_put_uint16_t(buf, 0, command);
|
||||
_mav_put_uint8_t(buf, 2, result);
|
||||
_mav_put_uint8_t(buf, 3, progress);
|
||||
_mav_put_int32_t(buf, 4, result_param2);
|
||||
_mav_put_uint8_t(buf, 8, target_system);
|
||||
_mav_put_uint8_t(buf, 9, target_component);
|
||||
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
|
||||
#else
|
||||
mavlink_command_ack_t packet;
|
||||
packet.command = command;
|
||||
packet.result = result;
|
||||
packet.progress = progress;
|
||||
packet.result_param2 = result_param2;
|
||||
packet.target_system = target_system;
|
||||
packet.target_component = target_component;
|
||||
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
|
||||
#endif
|
||||
|
@ -162,7 +210,7 @@ static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t
|
|||
static inline void mavlink_msg_command_ack_send_struct(mavlink_channel_t chan, const mavlink_command_ack_t* command_ack)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
mavlink_msg_command_ack_send(chan, command_ack->command, command_ack->result);
|
||||
mavlink_msg_command_ack_send(chan, command_ack->command, command_ack->result, command_ack->progress, command_ack->result_param2, command_ack->target_system, command_ack->target_component);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)command_ack, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
|
||||
#endif
|
||||
|
@ -176,18 +224,26 @@ static inline void mavlink_msg_command_ack_send_struct(mavlink_channel_t chan, c
|
|||
is usually the receive buffer for the channel, and allows a reply to an
|
||||
incoming message with minimum stack space usage.
|
||||
*/
|
||||
static inline void mavlink_msg_command_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t command, uint8_t result)
|
||||
static inline void mavlink_msg_command_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t command, uint8_t result, uint8_t progress, int32_t result_param2, uint8_t target_system, uint8_t target_component)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char *buf = (char *)msgbuf;
|
||||
_mav_put_uint16_t(buf, 0, command);
|
||||
_mav_put_uint8_t(buf, 2, result);
|
||||
_mav_put_uint8_t(buf, 3, progress);
|
||||
_mav_put_int32_t(buf, 4, result_param2);
|
||||
_mav_put_uint8_t(buf, 8, target_system);
|
||||
_mav_put_uint8_t(buf, 9, target_component);
|
||||
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
|
||||
#else
|
||||
mavlink_command_ack_t *packet = (mavlink_command_ack_t *)msgbuf;
|
||||
packet->command = command;
|
||||
packet->result = result;
|
||||
packet->progress = progress;
|
||||
packet->result_param2 = result_param2;
|
||||
packet->target_system = target_system;
|
||||
packet->target_component = target_component;
|
||||
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
|
||||
#endif
|
||||
|
@ -219,6 +275,46 @@ static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t
|
|||
return _MAV_RETURN_uint8_t(msg, 2);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field progress from command_ack message
|
||||
*
|
||||
* @return WIP: 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 (255 if the progress is unknown).
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_command_ack_get_progress(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 3);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field result_param2 from command_ack message
|
||||
*
|
||||
* @return WIP: Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
|
||||
*/
|
||||
static inline int32_t mavlink_msg_command_ack_get_result_param2(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_int32_t(msg, 4);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field target_system from command_ack message
|
||||
*
|
||||
* @return WIP: 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.
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_command_ack_get_target_system(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 8);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field target_component from command_ack message
|
||||
*
|
||||
* @return WIP: 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.
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_command_ack_get_target_component(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 9);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a command_ack message into a struct
|
||||
*
|
||||
|
@ -230,6 +326,10 @@ static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg,
|
|||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
command_ack->command = mavlink_msg_command_ack_get_command(msg);
|
||||
command_ack->result = mavlink_msg_command_ack_get_result(msg);
|
||||
command_ack->progress = mavlink_msg_command_ack_get_progress(msg);
|
||||
command_ack->result_param2 = mavlink_msg_command_ack_get_result_param2(msg);
|
||||
command_ack->target_system = mavlink_msg_command_ack_get_target_system(msg);
|
||||
command_ack->target_component = mavlink_msg_command_ack_get_target_component(msg);
|
||||
#else
|
||||
uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_ACK_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_ACK_LEN;
|
||||
memset(command_ack, 0, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue