Hotfix: general MAVLink update, including file transfer

This commit is contained in:
Lorenz Meier 2012-12-01 02:13:49 +01:00
parent c7616f89a3
commit 996e363122
17 changed files with 6633 additions and 24 deletions

5268
Tools/mavlink_px4.py Normal file

File diff suppressed because it is too large Load Diff

File diff suppressed because one or more lines are too long

View File

@ -5,8 +5,8 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Oct 18 13:36:48 2012"
#define MAVLINK_BUILD_DATE "Sat Dec 1 02:05:58 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
#endif // MAVLINK_VERSION_H

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,182 @@
// MESSAGE FILE_TRANSFER_DIR_LIST PACKING
#define MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST 111
typedef struct __mavlink_file_transfer_dir_list_t
{
uint64_t transfer_uid; ///< Unique transfer ID
char dir_path[240]; ///< Directory path to list
uint8_t flags; ///< RESERVED
} mavlink_file_transfer_dir_list_t;
#define MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN 249
#define MAVLINK_MSG_ID_111_LEN 249
#define MAVLINK_MSG_FILE_TRANSFER_DIR_LIST_FIELD_DIR_PATH_LEN 240
#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST { \
"FILE_TRANSFER_DIR_LIST", \
3, \
{ { "transfer_uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_file_transfer_dir_list_t, transfer_uid) }, \
{ "dir_path", NULL, MAVLINK_TYPE_CHAR, 240, 8, offsetof(mavlink_file_transfer_dir_list_t, dir_path) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 248, offsetof(mavlink_file_transfer_dir_list_t, flags) }, \
} \
}
/**
* @brief Pack a file_transfer_dir_list message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param transfer_uid Unique transfer ID
* @param dir_path Directory path to list
* @param flags RESERVED
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_file_transfer_dir_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t transfer_uid, const char *dir_path, uint8_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[249];
_mav_put_uint64_t(buf, 0, transfer_uid);
_mav_put_uint8_t(buf, 248, flags);
_mav_put_char_array(buf, 8, dir_path, 240);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 249);
#else
mavlink_file_transfer_dir_list_t packet;
packet.transfer_uid = transfer_uid;
packet.flags = flags;
mav_array_memcpy(packet.dir_path, dir_path, sizeof(char)*240);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 249);
#endif
msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST;
return mavlink_finalize_message(msg, system_id, component_id, 249, 93);
}
/**
* @brief Pack a file_transfer_dir_list message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param transfer_uid Unique transfer ID
* @param dir_path Directory path to list
* @param flags RESERVED
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_file_transfer_dir_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t transfer_uid,const char *dir_path,uint8_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[249];
_mav_put_uint64_t(buf, 0, transfer_uid);
_mav_put_uint8_t(buf, 248, flags);
_mav_put_char_array(buf, 8, dir_path, 240);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 249);
#else
mavlink_file_transfer_dir_list_t packet;
packet.transfer_uid = transfer_uid;
packet.flags = flags;
mav_array_memcpy(packet.dir_path, dir_path, sizeof(char)*240);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 249);
#endif
msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 249, 93);
}
/**
* @brief Encode a file_transfer_dir_list struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param file_transfer_dir_list C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_file_transfer_dir_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_dir_list_t* file_transfer_dir_list)
{
return mavlink_msg_file_transfer_dir_list_pack(system_id, component_id, msg, file_transfer_dir_list->transfer_uid, file_transfer_dir_list->dir_path, file_transfer_dir_list->flags);
}
/**
* @brief Send a file_transfer_dir_list message
* @param chan MAVLink channel to send the message
*
* @param transfer_uid Unique transfer ID
* @param dir_path Directory path to list
* @param flags RESERVED
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_file_transfer_dir_list_send(mavlink_channel_t chan, uint64_t transfer_uid, const char *dir_path, uint8_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[249];
_mav_put_uint64_t(buf, 0, transfer_uid);
_mav_put_uint8_t(buf, 248, flags);
_mav_put_char_array(buf, 8, dir_path, 240);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, buf, 249, 93);
#else
mavlink_file_transfer_dir_list_t packet;
packet.transfer_uid = transfer_uid;
packet.flags = flags;
mav_array_memcpy(packet.dir_path, dir_path, sizeof(char)*240);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, (const char *)&packet, 249, 93);
#endif
}
#endif
// MESSAGE FILE_TRANSFER_DIR_LIST UNPACKING
/**
* @brief Get field transfer_uid from file_transfer_dir_list message
*
* @return Unique transfer ID
*/
static inline uint64_t mavlink_msg_file_transfer_dir_list_get_transfer_uid(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field dir_path from file_transfer_dir_list message
*
* @return Directory path to list
*/
static inline uint16_t mavlink_msg_file_transfer_dir_list_get_dir_path(const mavlink_message_t* msg, char *dir_path)
{
return _MAV_RETURN_char_array(msg, dir_path, 240, 8);
}
/**
* @brief Get field flags from file_transfer_dir_list message
*
* @return RESERVED
*/
static inline uint8_t mavlink_msg_file_transfer_dir_list_get_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 248);
}
/**
* @brief Decode a file_transfer_dir_list message into a struct
*
* @param msg The message to decode
* @param file_transfer_dir_list C-struct to decode the message contents into
*/
static inline void mavlink_msg_file_transfer_dir_list_decode(const mavlink_message_t* msg, mavlink_file_transfer_dir_list_t* file_transfer_dir_list)
{
#if MAVLINK_NEED_BYTE_SWAP
file_transfer_dir_list->transfer_uid = mavlink_msg_file_transfer_dir_list_get_transfer_uid(msg);
mavlink_msg_file_transfer_dir_list_get_dir_path(msg, file_transfer_dir_list->dir_path);
file_transfer_dir_list->flags = mavlink_msg_file_transfer_dir_list_get_flags(msg);
#else
memcpy(file_transfer_dir_list, _MAV_PAYLOAD(msg), 249);
#endif
}

View File

@ -0,0 +1,166 @@
// MESSAGE FILE_TRANSFER_RES PACKING
#define MAVLINK_MSG_ID_FILE_TRANSFER_RES 112
typedef struct __mavlink_file_transfer_res_t
{
uint64_t transfer_uid; ///< Unique transfer ID
uint8_t result; ///< 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device
} mavlink_file_transfer_res_t;
#define MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN 9
#define MAVLINK_MSG_ID_112_LEN 9
#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES { \
"FILE_TRANSFER_RES", \
2, \
{ { "transfer_uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_file_transfer_res_t, transfer_uid) }, \
{ "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_file_transfer_res_t, result) }, \
} \
}
/**
* @brief Pack a file_transfer_res message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param transfer_uid Unique transfer ID
* @param result 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_file_transfer_res_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t transfer_uid, uint8_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint64_t(buf, 0, transfer_uid);
_mav_put_uint8_t(buf, 8, result);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
#else
mavlink_file_transfer_res_t packet;
packet.transfer_uid = transfer_uid;
packet.result = result;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
#endif
msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_RES;
return mavlink_finalize_message(msg, system_id, component_id, 9, 124);
}
/**
* @brief Pack a file_transfer_res message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param transfer_uid Unique transfer ID
* @param result 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_file_transfer_res_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t transfer_uid,uint8_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint64_t(buf, 0, transfer_uid);
_mav_put_uint8_t(buf, 8, result);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
#else
mavlink_file_transfer_res_t packet;
packet.transfer_uid = transfer_uid;
packet.result = result;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
#endif
msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_RES;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 124);
}
/**
* @brief Encode a file_transfer_res struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param file_transfer_res C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_file_transfer_res_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_res_t* file_transfer_res)
{
return mavlink_msg_file_transfer_res_pack(system_id, component_id, msg, file_transfer_res->transfer_uid, file_transfer_res->result);
}
/**
* @brief Send a file_transfer_res message
* @param chan MAVLink channel to send the message
*
* @param transfer_uid Unique transfer ID
* @param result 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_file_transfer_res_send(mavlink_channel_t chan, uint64_t transfer_uid, uint8_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint64_t(buf, 0, transfer_uid);
_mav_put_uint8_t(buf, 8, result);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, buf, 9, 124);
#else
mavlink_file_transfer_res_t packet;
packet.transfer_uid = transfer_uid;
packet.result = result;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, (const char *)&packet, 9, 124);
#endif
}
#endif
// MESSAGE FILE_TRANSFER_RES UNPACKING
/**
* @brief Get field transfer_uid from file_transfer_res message
*
* @return Unique transfer ID
*/
static inline uint64_t mavlink_msg_file_transfer_res_get_transfer_uid(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field result from file_transfer_res message
*
* @return 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device
*/
static inline uint8_t mavlink_msg_file_transfer_res_get_result(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
/**
* @brief Decode a file_transfer_res message into a struct
*
* @param msg The message to decode
* @param file_transfer_res C-struct to decode the message contents into
*/
static inline void mavlink_msg_file_transfer_res_decode(const mavlink_message_t* msg, mavlink_file_transfer_res_t* file_transfer_res)
{
#if MAVLINK_NEED_BYTE_SWAP
file_transfer_res->transfer_uid = mavlink_msg_file_transfer_res_get_transfer_uid(msg);
file_transfer_res->result = mavlink_msg_file_transfer_res_get_result(msg);
#else
memcpy(file_transfer_res, _MAV_PAYLOAD(msg), 9);
#endif
}

View File

@ -0,0 +1,226 @@
// MESSAGE FILE_TRANSFER_START PACKING
#define MAVLINK_MSG_ID_FILE_TRANSFER_START 110
typedef struct __mavlink_file_transfer_start_t
{
uint64_t transfer_uid; ///< Unique transfer ID
uint32_t file_size; ///< File size in bytes
char dest_path[240]; ///< Destination path
uint8_t direction; ///< Transfer direction: 0: from requester, 1: to requester
uint8_t flags; ///< RESERVED
} mavlink_file_transfer_start_t;
#define MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN 254
#define MAVLINK_MSG_ID_110_LEN 254
#define MAVLINK_MSG_FILE_TRANSFER_START_FIELD_DEST_PATH_LEN 240
#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START { \
"FILE_TRANSFER_START", \
5, \
{ { "transfer_uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_file_transfer_start_t, transfer_uid) }, \
{ "file_size", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_file_transfer_start_t, file_size) }, \
{ "dest_path", NULL, MAVLINK_TYPE_CHAR, 240, 12, offsetof(mavlink_file_transfer_start_t, dest_path) }, \
{ "direction", NULL, MAVLINK_TYPE_UINT8_T, 0, 252, offsetof(mavlink_file_transfer_start_t, direction) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 253, offsetof(mavlink_file_transfer_start_t, flags) }, \
} \
}
/**
* @brief Pack a file_transfer_start message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param transfer_uid Unique transfer ID
* @param dest_path Destination path
* @param direction Transfer direction: 0: from requester, 1: to requester
* @param file_size File size in bytes
* @param flags RESERVED
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_file_transfer_start_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t transfer_uid, const char *dest_path, uint8_t direction, uint32_t file_size, uint8_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[254];
_mav_put_uint64_t(buf, 0, transfer_uid);
_mav_put_uint32_t(buf, 8, file_size);
_mav_put_uint8_t(buf, 252, direction);
_mav_put_uint8_t(buf, 253, flags);
_mav_put_char_array(buf, 12, dest_path, 240);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 254);
#else
mavlink_file_transfer_start_t packet;
packet.transfer_uid = transfer_uid;
packet.file_size = file_size;
packet.direction = direction;
packet.flags = flags;
mav_array_memcpy(packet.dest_path, dest_path, sizeof(char)*240);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 254);
#endif
msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_START;
return mavlink_finalize_message(msg, system_id, component_id, 254, 235);
}
/**
* @brief Pack a file_transfer_start message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param transfer_uid Unique transfer ID
* @param dest_path Destination path
* @param direction Transfer direction: 0: from requester, 1: to requester
* @param file_size File size in bytes
* @param flags RESERVED
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_file_transfer_start_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t transfer_uid,const char *dest_path,uint8_t direction,uint32_t file_size,uint8_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[254];
_mav_put_uint64_t(buf, 0, transfer_uid);
_mav_put_uint32_t(buf, 8, file_size);
_mav_put_uint8_t(buf, 252, direction);
_mav_put_uint8_t(buf, 253, flags);
_mav_put_char_array(buf, 12, dest_path, 240);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 254);
#else
mavlink_file_transfer_start_t packet;
packet.transfer_uid = transfer_uid;
packet.file_size = file_size;
packet.direction = direction;
packet.flags = flags;
mav_array_memcpy(packet.dest_path, dest_path, sizeof(char)*240);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 254);
#endif
msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_START;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 254, 235);
}
/**
* @brief Encode a file_transfer_start struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param file_transfer_start C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_file_transfer_start_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_start_t* file_transfer_start)
{
return mavlink_msg_file_transfer_start_pack(system_id, component_id, msg, file_transfer_start->transfer_uid, file_transfer_start->dest_path, file_transfer_start->direction, file_transfer_start->file_size, file_transfer_start->flags);
}
/**
* @brief Send a file_transfer_start message
* @param chan MAVLink channel to send the message
*
* @param transfer_uid Unique transfer ID
* @param dest_path Destination path
* @param direction Transfer direction: 0: from requester, 1: to requester
* @param file_size File size in bytes
* @param flags RESERVED
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_file_transfer_start_send(mavlink_channel_t chan, uint64_t transfer_uid, const char *dest_path, uint8_t direction, uint32_t file_size, uint8_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[254];
_mav_put_uint64_t(buf, 0, transfer_uid);
_mav_put_uint32_t(buf, 8, file_size);
_mav_put_uint8_t(buf, 252, direction);
_mav_put_uint8_t(buf, 253, flags);
_mav_put_char_array(buf, 12, dest_path, 240);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, buf, 254, 235);
#else
mavlink_file_transfer_start_t packet;
packet.transfer_uid = transfer_uid;
packet.file_size = file_size;
packet.direction = direction;
packet.flags = flags;
mav_array_memcpy(packet.dest_path, dest_path, sizeof(char)*240);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, (const char *)&packet, 254, 235);
#endif
}
#endif
// MESSAGE FILE_TRANSFER_START UNPACKING
/**
* @brief Get field transfer_uid from file_transfer_start message
*
* @return Unique transfer ID
*/
static inline uint64_t mavlink_msg_file_transfer_start_get_transfer_uid(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field dest_path from file_transfer_start message
*
* @return Destination path
*/
static inline uint16_t mavlink_msg_file_transfer_start_get_dest_path(const mavlink_message_t* msg, char *dest_path)
{
return _MAV_RETURN_char_array(msg, dest_path, 240, 12);
}
/**
* @brief Get field direction from file_transfer_start message
*
* @return Transfer direction: 0: from requester, 1: to requester
*/
static inline uint8_t mavlink_msg_file_transfer_start_get_direction(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 252);
}
/**
* @brief Get field file_size from file_transfer_start message
*
* @return File size in bytes
*/
static inline uint32_t mavlink_msg_file_transfer_start_get_file_size(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 8);
}
/**
* @brief Get field flags from file_transfer_start message
*
* @return RESERVED
*/
static inline uint8_t mavlink_msg_file_transfer_start_get_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 253);
}
/**
* @brief Decode a file_transfer_start message into a struct
*
* @param msg The message to decode
* @param file_transfer_start C-struct to decode the message contents into
*/
static inline void mavlink_msg_file_transfer_start_decode(const mavlink_message_t* msg, mavlink_file_transfer_start_t* file_transfer_start)
{
#if MAVLINK_NEED_BYTE_SWAP
file_transfer_start->transfer_uid = mavlink_msg_file_transfer_start_get_transfer_uid(msg);
file_transfer_start->file_size = mavlink_msg_file_transfer_start_get_file_size(msg);
mavlink_msg_file_transfer_start_get_dest_path(msg, file_transfer_start->dest_path);
file_transfer_start->direction = mavlink_msg_file_transfer_start_get_direction(msg);
file_transfer_start->flags = mavlink_msg_file_transfer_start_get_flags(msg);
#else
memcpy(file_transfer_start, _MAV_PAYLOAD(msg), 254);
#endif
}

View File

@ -0,0 +1,276 @@
// MESSAGE MANUAL_SETPOINT PACKING
#define MAVLINK_MSG_ID_MANUAL_SETPOINT 81
typedef struct __mavlink_manual_setpoint_t
{
uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot
float roll; ///< Desired roll rate in radians per second
float pitch; ///< Desired pitch rate in radians per second
float yaw; ///< Desired yaw rate in radians per second
float thrust; ///< Collective thrust, normalized to 0 .. 1
uint8_t mode_switch; ///< Flight mode switch position, 0.. 255
uint8_t manual_override_switch; ///< Override mode switch position, 0.. 255
} mavlink_manual_setpoint_t;
#define MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN 22
#define MAVLINK_MSG_ID_81_LEN 22
#define MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT { \
"MANUAL_SETPOINT", \
7, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_manual_setpoint_t, time_boot_ms) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_setpoint_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_setpoint_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_setpoint_t, yaw) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_manual_setpoint_t, thrust) }, \
{ "mode_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_setpoint_t, mode_switch) }, \
{ "manual_override_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_manual_setpoint_t, manual_override_switch) }, \
} \
}
/**
* @brief Pack a manual_setpoint message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll Desired roll rate in radians per second
* @param pitch Desired pitch rate in radians per second
* @param yaw Desired yaw rate in radians per second
* @param thrust Collective thrust, normalized to 0 .. 1
* @param mode_switch Flight mode switch position, 0.. 255
* @param manual_override_switch Override mode switch position, 0.. 255
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_manual_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[22];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll);
_mav_put_float(buf, 8, pitch);
_mav_put_float(buf, 12, yaw);
_mav_put_float(buf, 16, thrust);
_mav_put_uint8_t(buf, 20, mode_switch);
_mav_put_uint8_t(buf, 21, manual_override_switch);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22);
#else
mavlink_manual_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
packet.mode_switch = mode_switch;
packet.manual_override_switch = manual_override_switch;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22);
#endif
msg->msgid = MAVLINK_MSG_ID_MANUAL_SETPOINT;
return mavlink_finalize_message(msg, system_id, component_id, 22, 106);
}
/**
* @brief Pack a manual_setpoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll Desired roll rate in radians per second
* @param pitch Desired pitch rate in radians per second
* @param yaw Desired yaw rate in radians per second
* @param thrust Collective thrust, normalized to 0 .. 1
* @param mode_switch Flight mode switch position, 0.. 255
* @param manual_override_switch Override mode switch position, 0.. 255
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_manual_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,float roll,float pitch,float yaw,float thrust,uint8_t mode_switch,uint8_t manual_override_switch)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[22];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll);
_mav_put_float(buf, 8, pitch);
_mav_put_float(buf, 12, yaw);
_mav_put_float(buf, 16, thrust);
_mav_put_uint8_t(buf, 20, mode_switch);
_mav_put_uint8_t(buf, 21, manual_override_switch);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22);
#else
mavlink_manual_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
packet.mode_switch = mode_switch;
packet.manual_override_switch = manual_override_switch;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22);
#endif
msg->msgid = MAVLINK_MSG_ID_MANUAL_SETPOINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 106);
}
/**
* @brief Encode a manual_setpoint struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param manual_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_manual_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_setpoint_t* manual_setpoint)
{
return mavlink_msg_manual_setpoint_pack(system_id, component_id, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch);
}
/**
* @brief Send a manual_setpoint message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll Desired roll rate in radians per second
* @param pitch Desired pitch rate in radians per second
* @param yaw Desired yaw rate in radians per second
* @param thrust Collective thrust, normalized to 0 .. 1
* @param mode_switch Flight mode switch position, 0.. 255
* @param manual_override_switch Override mode switch position, 0.. 255
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_manual_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[22];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll);
_mav_put_float(buf, 8, pitch);
_mav_put_float(buf, 12, yaw);
_mav_put_float(buf, 16, thrust);
_mav_put_uint8_t(buf, 20, mode_switch);
_mav_put_uint8_t(buf, 21, manual_override_switch);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, 22, 106);
#else
mavlink_manual_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
packet.mode_switch = mode_switch;
packet.manual_override_switch = manual_override_switch;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)&packet, 22, 106);
#endif
}
#endif
// MESSAGE MANUAL_SETPOINT UNPACKING
/**
* @brief Get field time_boot_ms from manual_setpoint message
*
* @return Timestamp in milliseconds since system boot
*/
static inline uint32_t mavlink_msg_manual_setpoint_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field roll from manual_setpoint message
*
* @return Desired roll rate in radians per second
*/
static inline float mavlink_msg_manual_setpoint_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field pitch from manual_setpoint message
*
* @return Desired pitch rate in radians per second
*/
static inline float mavlink_msg_manual_setpoint_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field yaw from manual_setpoint message
*
* @return Desired yaw rate in radians per second
*/
static inline float mavlink_msg_manual_setpoint_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field thrust from manual_setpoint message
*
* @return Collective thrust, normalized to 0 .. 1
*/
static inline float mavlink_msg_manual_setpoint_get_thrust(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field mode_switch from manual_setpoint message
*
* @return Flight mode switch position, 0.. 255
*/
static inline uint8_t mavlink_msg_manual_setpoint_get_mode_switch(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 20);
}
/**
* @brief Get field manual_override_switch from manual_setpoint message
*
* @return Override mode switch position, 0.. 255
*/
static inline uint8_t mavlink_msg_manual_setpoint_get_manual_override_switch(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 21);
}
/**
* @brief Decode a manual_setpoint message into a struct
*
* @param msg The message to decode
* @param manual_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_manual_setpoint_decode(const mavlink_message_t* msg, mavlink_manual_setpoint_t* manual_setpoint)
{
#if MAVLINK_NEED_BYTE_SWAP
manual_setpoint->time_boot_ms = mavlink_msg_manual_setpoint_get_time_boot_ms(msg);
manual_setpoint->roll = mavlink_msg_manual_setpoint_get_roll(msg);
manual_setpoint->pitch = mavlink_msg_manual_setpoint_get_pitch(msg);
manual_setpoint->yaw = mavlink_msg_manual_setpoint_get_yaw(msg);
manual_setpoint->thrust = mavlink_msg_manual_setpoint_get_thrust(msg);
manual_setpoint->mode_switch = mavlink_msg_manual_setpoint_get_mode_switch(msg);
manual_setpoint->manual_override_switch = mavlink_msg_manual_setpoint_get_manual_override_switch(msg);
#else
memcpy(manual_setpoint, _MAV_PAYLOAD(msg), 22);
#endif
}

View File

@ -0,0 +1,232 @@
// MESSAGE ROLL_PITCH_YAW_RATES_THRUST_SETPOINT PACKING
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT 80
typedef struct __mavlink_roll_pitch_yaw_rates_thrust_setpoint_t
{
uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot
float roll_rate; ///< Desired roll rate in radians per second
float pitch_rate; ///< Desired pitch rate in radians per second
float yaw_rate; ///< Desired yaw rate in radians per second
float thrust; ///< Collective thrust, normalized to 0 .. 1
} mavlink_roll_pitch_yaw_rates_thrust_setpoint_t;
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN 20
#define MAVLINK_MSG_ID_80_LEN 20
#define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT { \
"ROLL_PITCH_YAW_RATES_THRUST_SETPOINT", \
5, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, time_boot_ms) }, \
{ "roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, roll_rate) }, \
{ "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, pitch_rate) }, \
{ "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, yaw_rate) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, thrust) }, \
} \
}
/**
* @brief Pack a roll_pitch_yaw_rates_thrust_setpoint message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll_rate Desired roll rate in radians per second
* @param pitch_rate Desired pitch rate in radians per second
* @param yaw_rate Desired yaw rate in radians per second
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, float roll_rate, float pitch_rate, float yaw_rate, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll_rate);
_mav_put_float(buf, 8, pitch_rate);
_mav_put_float(buf, 12, yaw_rate);
_mav_put_float(buf, 16, thrust);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll_rate = roll_rate;
packet.pitch_rate = pitch_rate;
packet.yaw_rate = yaw_rate;
packet.thrust = thrust;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT;
return mavlink_finalize_message(msg, system_id, component_id, 20, 127);
}
/**
* @brief Pack a roll_pitch_yaw_rates_thrust_setpoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll_rate Desired roll rate in radians per second
* @param pitch_rate Desired pitch rate in radians per second
* @param yaw_rate Desired yaw rate in radians per second
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,float roll_rate,float pitch_rate,float yaw_rate,float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll_rate);
_mav_put_float(buf, 8, pitch_rate);
_mav_put_float(buf, 12, yaw_rate);
_mav_put_float(buf, 16, thrust);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll_rate = roll_rate;
packet.pitch_rate = pitch_rate;
packet.yaw_rate = yaw_rate;
packet.thrust = thrust;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 127);
}
/**
* @brief Encode a roll_pitch_yaw_rates_thrust_setpoint struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param roll_pitch_yaw_rates_thrust_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_rates_thrust_setpoint_t* roll_pitch_yaw_rates_thrust_setpoint)
{
return mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_rates_thrust_setpoint->time_boot_ms, roll_pitch_yaw_rates_thrust_setpoint->roll_rate, roll_pitch_yaw_rates_thrust_setpoint->pitch_rate, roll_pitch_yaw_rates_thrust_setpoint->yaw_rate, roll_pitch_yaw_rates_thrust_setpoint->thrust);
}
/**
* @brief Send a roll_pitch_yaw_rates_thrust_setpoint message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll_rate Desired roll rate in radians per second
* @param pitch_rate Desired pitch rate in radians per second
* @param yaw_rate Desired yaw rate in radians per second
* @param thrust Collective thrust, normalized to 0 .. 1
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll_rate, float pitch_rate, float yaw_rate, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll_rate);
_mav_put_float(buf, 8, pitch_rate);
_mav_put_float(buf, 12, yaw_rate);
_mav_put_float(buf, 16, thrust);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, buf, 20, 127);
#else
mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll_rate = roll_rate;
packet.pitch_rate = pitch_rate;
packet.yaw_rate = yaw_rate;
packet.thrust = thrust;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, (const char *)&packet, 20, 127);
#endif
}
#endif
// MESSAGE ROLL_PITCH_YAW_RATES_THRUST_SETPOINT UNPACKING
/**
* @brief Get field time_boot_ms from roll_pitch_yaw_rates_thrust_setpoint message
*
* @return Timestamp in milliseconds since system boot
*/
static inline uint32_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field roll_rate from roll_pitch_yaw_rates_thrust_setpoint message
*
* @return Desired roll rate in radians per second
*/
static inline float mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_roll_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field pitch_rate from roll_pitch_yaw_rates_thrust_setpoint message
*
* @return Desired pitch rate in radians per second
*/
static inline float mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_pitch_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field yaw_rate from roll_pitch_yaw_rates_thrust_setpoint message
*
* @return Desired yaw rate in radians per second
*/
static inline float mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_yaw_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field thrust from roll_pitch_yaw_rates_thrust_setpoint message
*
* @return Collective thrust, normalized to 0 .. 1
*/
static inline float mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_thrust(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Decode a roll_pitch_yaw_rates_thrust_setpoint message into a struct
*
* @param msg The message to decode
* @param roll_pitch_yaw_rates_thrust_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_rates_thrust_setpoint_t* roll_pitch_yaw_rates_thrust_setpoint)
{
#if MAVLINK_NEED_BYTE_SWAP
roll_pitch_yaw_rates_thrust_setpoint->time_boot_ms = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_time_boot_ms(msg);
roll_pitch_yaw_rates_thrust_setpoint->roll_rate = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_roll_rate(msg);
roll_pitch_yaw_rates_thrust_setpoint->pitch_rate = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_pitch_rate(msg);
roll_pitch_yaw_rates_thrust_setpoint->yaw_rate = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_yaw_rate(msg);
roll_pitch_yaw_rates_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_thrust(msg);
#else
memcpy(roll_pitch_yaw_rates_thrust_setpoint, _MAV_PAYLOAD(msg), 20);
#endif
}

View File

@ -3178,6 +3178,112 @@ static void mavlink_test_command_ack(uint8_t system_id, uint8_t component_id, ma
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_roll_pitch_yaw_rates_thrust_setpoint(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet_in = {
963497464,
45.0,
73.0,
101.0,
129.0,
};
mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.roll_rate = packet_in.roll_rate;
packet1.pitch_rate = packet_in.pitch_rate;
packet1.yaw_rate = packet_in.yaw_rate;
packet1.thrust = packet_in.thrust;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.roll_rate , packet1.pitch_rate , packet1.yaw_rate , packet1.thrust );
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.roll_rate , packet1.pitch_rate , packet1.yaw_rate , packet1.thrust );
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.roll_rate , packet1.pitch_rate , packet1.yaw_rate , packet1.thrust );
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_manual_setpoint(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_manual_setpoint_t packet_in = {
963497464,
45.0,
73.0,
101.0,
129.0,
65,
132,
};
mavlink_manual_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
packet1.thrust = packet_in.thrust;
packet1.mode_switch = packet_in.mode_switch;
packet1.manual_override_switch = packet_in.manual_override_switch;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_manual_setpoint_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_manual_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_manual_setpoint_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.mode_switch , packet1.manual_override_switch );
mavlink_msg_manual_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_manual_setpoint_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.mode_switch , packet1.manual_override_switch );
mavlink_msg_manual_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_manual_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_manual_setpoint_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.mode_switch , packet1.manual_override_switch );
mavlink_msg_manual_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_local_position_ned_system_global_offset(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
@ -3780,6 +3886,149 @@ static void mavlink_test_highres_imu(uint8_t system_id, uint8_t component_id, ma
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_file_transfer_start(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_file_transfer_start_t packet_in = {
93372036854775807ULL,
963497880,
"MNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQ",
249,
60,
};
mavlink_file_transfer_start_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.transfer_uid = packet_in.transfer_uid;
packet1.file_size = packet_in.file_size;
packet1.direction = packet_in.direction;
packet1.flags = packet_in.flags;
mav_array_memcpy(packet1.dest_path, packet_in.dest_path, sizeof(char)*240);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_file_transfer_start_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_file_transfer_start_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_file_transfer_start_pack(system_id, component_id, &msg , packet1.transfer_uid , packet1.dest_path , packet1.direction , packet1.file_size , packet1.flags );
mavlink_msg_file_transfer_start_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_file_transfer_start_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.transfer_uid , packet1.dest_path , packet1.direction , packet1.file_size , packet1.flags );
mavlink_msg_file_transfer_start_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_file_transfer_start_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_file_transfer_start_send(MAVLINK_COMM_1 , packet1.transfer_uid , packet1.dest_path , packet1.direction , packet1.file_size , packet1.flags );
mavlink_msg_file_transfer_start_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_file_transfer_dir_list(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_file_transfer_dir_list_t packet_in = {
93372036854775807ULL,
"IJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLM",
237,
};
mavlink_file_transfer_dir_list_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.transfer_uid = packet_in.transfer_uid;
packet1.flags = packet_in.flags;
mav_array_memcpy(packet1.dir_path, packet_in.dir_path, sizeof(char)*240);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_file_transfer_dir_list_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_file_transfer_dir_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_file_transfer_dir_list_pack(system_id, component_id, &msg , packet1.transfer_uid , packet1.dir_path , packet1.flags );
mavlink_msg_file_transfer_dir_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_file_transfer_dir_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.transfer_uid , packet1.dir_path , packet1.flags );
mavlink_msg_file_transfer_dir_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_file_transfer_dir_list_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_file_transfer_dir_list_send(MAVLINK_COMM_1 , packet1.transfer_uid , packet1.dir_path , packet1.flags );
mavlink_msg_file_transfer_dir_list_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_file_transfer_res(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_file_transfer_res_t packet_in = {
93372036854775807ULL,
29,
};
mavlink_file_transfer_res_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.transfer_uid = packet_in.transfer_uid;
packet1.result = packet_in.result;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_file_transfer_res_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_file_transfer_res_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_file_transfer_res_pack(system_id, component_id, &msg , packet1.transfer_uid , packet1.result );
mavlink_msg_file_transfer_res_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_file_transfer_res_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.transfer_uid , packet1.result );
mavlink_msg_file_transfer_res_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_file_transfer_res_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_file_transfer_res_send(MAVLINK_COMM_1 , packet1.transfer_uid , packet1.result );
mavlink_msg_file_transfer_res_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_battery_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
@ -4301,6 +4550,8 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
mavlink_test_vfr_hud(system_id, component_id, last_msg);
mavlink_test_command_long(system_id, component_id, last_msg);
mavlink_test_command_ack(system_id, component_id, last_msg);
mavlink_test_roll_pitch_yaw_rates_thrust_setpoint(system_id, component_id, last_msg);
mavlink_test_manual_setpoint(system_id, component_id, last_msg);
mavlink_test_local_position_ned_system_global_offset(system_id, component_id, last_msg);
mavlink_test_hil_state(system_id, component_id, last_msg);
mavlink_test_hil_controls(system_id, component_id, last_msg);
@ -4311,6 +4562,9 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
mavlink_test_vision_speed_estimate(system_id, component_id, last_msg);
mavlink_test_vicon_position_estimate(system_id, component_id, last_msg);
mavlink_test_highres_imu(system_id, component_id, last_msg);
mavlink_test_file_transfer_start(system_id, component_id, last_msg);
mavlink_test_file_transfer_dir_list(system_id, component_id, last_msg);
mavlink_test_file_transfer_res(system_id, component_id, last_msg);
mavlink_test_battery_status(system_id, component_id, last_msg);
mavlink_test_setpoint_8dof(system_id, component_id, last_msg);
mavlink_test_setpoint_6dof(system_id, component_id, last_msg);

View File

@ -5,8 +5,8 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Oct 18 13:37:22 2012"
#define MAVLINK_BUILD_DATE "Sat Dec 1 02:07:06 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
#endif // MAVLINK_VERSION_H

File diff suppressed because one or more lines are too long

View File

@ -5,8 +5,8 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Oct 18 13:37:22 2012"
#define MAVLINK_BUILD_DATE "Sat Dec 1 02:06:23 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
#endif // MAVLINK_VERSION_H

File diff suppressed because one or more lines are too long

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Oct 18 13:37:02 2012"
#define MAVLINK_BUILD_DATE "Sat Dec 1 02:06:36 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255

File diff suppressed because one or more lines are too long

View File

@ -5,8 +5,8 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Oct 18 13:37:13 2012"
#define MAVLINK_BUILD_DATE "Sat Dec 1 02:07:06 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
#endif // MAVLINK_VERSION_H