Commit 86a2b147 authored by PX4BuildBot's avatar PX4BuildBot

autogenerated headers for rev...

autogenerated headers for rev https://github.com/mavlink/mavlink/tree/63bc9d0cc63182cb7a63b8d044cff318852894ca
parent ef7df958
This diff is collapsed.
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Sep 25 07:21:28 2015" #define MAVLINK_BUILD_DATE "Tue Oct 6 15:52:01 2015"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
This diff is collapsed.
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Sep 25 07:20:43 2015" #define MAVLINK_BUILD_DATE "Tue Oct 6 15:50:56 2015"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
This diff is collapsed.
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Sep 25 07:20:50 2015" #define MAVLINK_BUILD_DATE "Tue Oct 6 15:51:06 2015"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
This diff is collapsed.
// MESSAGE EXTENDED_SYS_STATE PACKING
#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE 245
typedef struct __mavlink_extended_sys_state_t
{
uint8_t vtol_state; /*< The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.*/
uint8_t landed_state; /*< The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.*/
} mavlink_extended_sys_state_t;
#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN 2
#define MAVLINK_MSG_ID_245_LEN 2
#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC 130
#define MAVLINK_MSG_ID_245_CRC 130
#define MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE { \
"EXTENDED_SYS_STATE", \
2, \
{ { "vtol_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_extended_sys_state_t, vtol_state) }, \
{ "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_extended_sys_state_t, landed_state) }, \
} \
}
/**
* @brief Pack a extended_sys_state 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 vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.
* @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_extended_sys_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t vtol_state, uint8_t landed_state)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN];
_mav_put_uint8_t(buf, 0, vtol_state);
_mav_put_uint8_t(buf, 1, landed_state);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN);
#else
mavlink_extended_sys_state_t packet;
packet.vtol_state = vtol_state;
packet.landed_state = landed_state;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_EXTENDED_SYS_STATE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN);
#endif
}
/**
* @brief Pack a extended_sys_state 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.
* @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_extended_sys_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t vtol_state,uint8_t landed_state)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN];
_mav_put_uint8_t(buf, 0, vtol_state);
_mav_put_uint8_t(buf, 1, landed_state);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN);
#else
mavlink_extended_sys_state_t packet;
packet.vtol_state = vtol_state;
packet.landed_state = landed_state;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_EXTENDED_SYS_STATE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN);
#endif
}
/**
* @brief Encode a extended_sys_state struct
*
* @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 extended_sys_state C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_extended_sys_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_extended_sys_state_t* extended_sys_state)
{
return mavlink_msg_extended_sys_state_pack(system_id, component_id, msg, extended_sys_state->vtol_state, extended_sys_state->landed_state);
}
/**
* @brief Encode a extended_sys_state struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param extended_sys_state C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_extended_sys_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_extended_sys_state_t* extended_sys_state)
{
return mavlink_msg_extended_sys_state_pack_chan(system_id, component_id, chan, msg, extended_sys_state->vtol_state, extended_sys_state->landed_state);
}
/**
* @brief Send a extended_sys_state message
* @param chan MAVLink channel to send the message
*
* @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.
* @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_extended_sys_state_send(mavlink_channel_t chan, uint8_t vtol_state, uint8_t landed_state)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN];
_mav_put_uint8_t(buf, 0, vtol_state);
_mav_put_uint8_t(buf, 1, landed_state);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN);
#endif
#else
mavlink_extended_sys_state_t packet;
packet.vtol_state = vtol_state;
packet.landed_state = landed_state;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)&packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)&packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
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_extended_sys_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t vtol_state, uint8_t landed_state)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, vtol_state);
_mav_put_uint8_t(buf, 1, landed_state);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN);
#endif
#else
mavlink_extended_sys_state_t *packet = (mavlink_extended_sys_state_t *)msgbuf;
packet->vtol_state = vtol_state;
packet->landed_state = landed_state;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE EXTENDED_SYS_STATE UNPACKING
/**
* @brief Get field vtol_state from extended_sys_state message
*
* @return The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.
*/
static inline uint8_t mavlink_msg_extended_sys_state_get_vtol_state(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field landed_state from extended_sys_state message
*
* @return The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
*/
static inline uint8_t mavlink_msg_extended_sys_state_get_landed_state(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Decode a extended_sys_state message into a struct
*
* @param msg The message to decode
* @param extended_sys_state C-struct to decode the message contents into
*/
static inline void mavlink_msg_extended_sys_state_decode(const mavlink_message_t* msg, mavlink_extended_sys_state_t* extended_sys_state)
{
#if MAVLINK_NEED_BYTE_SWAP
extended_sys_state->vtol_state = mavlink_msg_extended_sys_state_get_vtol_state(msg);
extended_sys_state->landed_state = mavlink_msg_extended_sys_state_get_landed_state(msg);
#else
memcpy(extended_sys_state, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN);
#endif
}
// MESSAGE VTOL_STATE PACKING
#define MAVLINK_MSG_ID_VTOL_STATE 245
typedef struct __mavlink_vtol_state_t
{
uint8_t state; /*< The VTOL state the MAV is in*/
} mavlink_vtol_state_t;
#define MAVLINK_MSG_ID_VTOL_STATE_LEN 1
#define MAVLINK_MSG_ID_245_LEN 1
#define MAVLINK_MSG_ID_VTOL_STATE_CRC 83
#define MAVLINK_MSG_ID_245_CRC 83
#define MAVLINK_MESSAGE_INFO_VTOL_STATE { \
"VTOL_STATE", \
1, \
{ { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_vtol_state_t, state) }, \
} \
}
/**
* @brief Pack a vtol_state 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 state The VTOL state the MAV is in
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vtol_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t state)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_VTOL_STATE_LEN];
_mav_put_uint8_t(buf, 0, state);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VTOL_STATE_LEN);
#else
mavlink_vtol_state_t packet;
packet.state = state;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VTOL_STATE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_VTOL_STATE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VTOL_STATE_LEN, MAVLINK_MSG_ID_VTOL_STATE_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VTOL_STATE_LEN);
#endif
}
/**
* @brief Pack a vtol_state 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param state The VTOL state the MAV is in
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vtol_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t state)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_VTOL_STATE_LEN];
_mav_put_uint8_t(buf, 0, state);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VTOL_STATE_LEN);
#else
mavlink_vtol_state_t packet;
packet.state = state;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VTOL_STATE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_VTOL_STATE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VTOL_STATE_LEN, MAVLINK_MSG_ID_VTOL_STATE_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VTOL_STATE_LEN);
#endif
}
/**
* @brief Encode a vtol_state struct
*
* @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 vtol_state C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_vtol_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vtol_state_t* vtol_state)
{
return mavlink_msg_vtol_state_pack(system_id, component_id, msg, vtol_state->state);
}
/**
* @brief Encode a vtol_state struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param vtol_state C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_vtol_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vtol_state_t* vtol_state)
{
return mavlink_msg_vtol_state_pack_chan(system_id, component_id, chan, msg, vtol_state->state);
}
/**
* @brief Send a vtol_state message
* @param chan MAVLink channel to send the message
*
* @param state The VTOL state the MAV is in
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_vtol_state_send(mavlink_channel_t chan, uint8_t state)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_VTOL_STATE_LEN];
_mav_put_uint8_t(buf, 0, state);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VTOL_STATE, buf, MAVLINK_MSG_ID_VTOL_STATE_LEN, MAVLINK_MSG_ID_VTOL_STATE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VTOL_STATE, buf, MAVLINK_MSG_ID_VTOL_STATE_LEN);
#endif
#else
mavlink_vtol_state_t packet;
packet.state = state;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VTOL_STATE, (const char *)&packet, MAVLINK_MSG_ID_VTOL_STATE_LEN, MAVLINK_MSG_ID_VTOL_STATE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VTOL_STATE, (const char *)&packet, MAVLINK_MSG_ID_VTOL_STATE_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_VTOL_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
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_vtol_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t state)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, state);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VTOL_STATE, buf, MAVLINK_MSG_ID_VTOL_STATE_LEN, MAVLINK_MSG_ID_VTOL_STATE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VTOL_STATE, buf, MAVLINK_MSG_ID_VTOL_STATE_LEN);
#endif
#else
mavlink_vtol_state_t *packet = (mavlink_vtol_state_t *)msgbuf;
packet->state = state;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VTOL_STATE, (const char *)packet, MAVLINK_MSG_ID_VTOL_STATE_LEN, MAVLINK_MSG_ID_VTOL_STATE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VTOL_STATE, (const char *)packet, MAVLINK_MSG_ID_VTOL_STATE_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE VTOL_STATE UNPACKING
/**
* @brief Get field state from vtol_state message
*
* @return The VTOL state the MAV is in
*/
static inline uint8_t mavlink_msg_vtol_state_get_state(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Decode a vtol_state message into a struct
*
* @param msg The message to decode
* @param vtol_state C-struct to decode the message contents into
*/
static inline void mavlink_msg_vtol_state_decode(const mavlink_message_t* msg, mavlink_vtol_state_t* vtol_state)
{
#if MAVLINK_NEED_BYTE_SWAP
vtol_state->state = mavlink_msg_vtol_state_get_state(msg);
#else
memcpy(vtol_state, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VTOL_STATE_LEN);
#endif
}
...@@ -5859,33 +5859,34 @@ static void mavlink_test_message_interval(uint8_t system_id, uint8_t component_i ...@@ -5859,33 +5859,34 @@ static void mavlink_test_message_interval(uint8_t system_id, uint8_t component_i
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
} }
static void mavlink_test_vtol_state(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) static void mavlink_test_extended_sys_state(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{ {
mavlink_message_t msg; mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i; uint16_t i;
mavlink_vtol_state_t packet_in = { mavlink_extended_sys_state_t packet_in = {
5 5,72
}; };
mavlink_vtol_state_t packet1, packet2; mavlink_extended_sys_state_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1)); memset(&packet1, 0, sizeof(packet1));
packet1.state = packet_in.state; packet1.vtol_state = packet_in.vtol_state;
packet1.landed_state = packet_in.landed_state;
memset(&packet2, 0, sizeof(packet2)); memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vtol_state_encode(system_id, component_id, &msg, &packet1); mavlink_msg_extended_sys_state_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_vtol_state_decode(&msg, &packet2); mavlink_msg_extended_sys_state_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2)); memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vtol_state_pack(system_id, component_id, &msg , packet1.state ); mavlink_msg_extended_sys_state_pack(system_id, component_id, &msg , packet1.vtol_state , packet1.landed_state );
mavlink_msg_vtol_state_decode(&msg, &packet2); mavlink_msg_extended_sys_state_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2)); memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vtol_state_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.state ); mavlink_msg_extended_sys_state_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.vtol_state , packet1.landed_state );
mavlink_msg_vtol_state_decode(&msg, &packet2); mavlink_msg_extended_sys_state_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2)); memset(&packet2, 0, sizeof(packet2));
...@@ -5893,12 +5894,12 @@ static void mavlink_test_vtol_state(uint8_t system_id, uint8_t component_id, mav ...@@ -5893,12 +5894,12 @@ static void mavlink_test_vtol_state(uint8_t system_id, uint8_t component_id, mav
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) { for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]); comm_send_ch(MAVLINK_COMM_0, buffer[i]);
} }
mavlink_msg_vtol_state_decode(last_msg, &packet2); mavlink_msg_extended_sys_state_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2)); memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vtol_state_send(MAVLINK_COMM_1 , packet1.state ); mavlink_msg_extended_sys_state_send(MAVLINK_COMM_1 , packet1.vtol_state , packet1.landed_state );
mavlink_msg_vtol_state_decode(last_msg, &packet2); mavlink_msg_extended_sys_state_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
} }
...@@ -6341,7 +6342,7 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink ...@@ -6341,7 +6342,7 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
mavlink_test_home_position(system_id, component_id, last_msg); mavlink_test_home_position(system_id, component_id, last_msg);
mavlink_test_set_home_position(system_id, component_id, last_msg); mavlink_test_set_home_position(system_id, component_id, last_msg);
mavlink_test_message_interval(system_id, component_id, last_msg); mavlink_test_message_interval(system_id, component_id, last_msg);
mavlink_test_vtol_state(system_id, component_id, last_msg); mavlink_test_extended_sys_state(system_id, component_id, last_msg);
mavlink_test_v2_extension(system_id, component_id, last_msg); mavlink_test_v2_extension(system_id, component_id, last_msg);
mavlink_test_memory_vect(system_id, component_id, last_msg); mavlink_test_memory_vect(system_id, component_id, last_msg);
mavlink_test_debug_vect(system_id, component_id, last_msg); mavlink_test_debug_vect(system_id, component_id, last_msg);
......
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Sep 25 07:21:40 2015" #define MAVLINK_BUILD_DATE "Tue Oct 6 15:52:19 2015"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
This diff is collapsed.
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Sep 25 07:20:58 2015" #define MAVLINK_BUILD_DATE "Tue Oct 6 15:51:17 2015"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Sep 25 07:21:05 2015" #define MAVLINK_BUILD_DATE "Tue Oct 6 15:51:27 2015"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 9 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 9
......
This diff is collapsed.
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Sep 25 07:21:06 2015" #define MAVLINK_BUILD_DATE "Tue Oct 6 15:51:29 2015"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
This diff is collapsed.
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Sep 25 07:21:13 2015" #define MAVLINK_BUILD_DATE "Tue Oct 6 15:51:40 2015"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Sep 25 07:21:20 2015" #define MAVLINK_BUILD_DATE "Tue Oct 6 15:51:50 2015"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 179 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 179
......
This diff is collapsed.
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Sep 25 07:21:21 2015" #define MAVLINK_BUILD_DATE "Tue Oct 6 15:51:51 2015"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
Markdown is supported
0%
or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment