aboutsummaryrefslogtreecommitdiff
path: root/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9
diff options
context:
space:
mode:
Diffstat (limited to 'mavlink/share/pyshared/pymavlink/generator/C/include_v0.9')
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/checksum.h89
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_helpers.h488
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_types.h300
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/protocol.h319
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/mavlink.h27
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/mavlink_msg_test_types.h610
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/test.h53
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/testsuite.h120
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/version.h12
9 files changed, 2018 insertions, 0 deletions
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/checksum.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/checksum.h
new file mode 100644
index 000000000..b70991f5a
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/checksum.h
@@ -0,0 +1,89 @@
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#ifndef _CHECKSUM_H_
+#define _CHECKSUM_H_
+
+
+/**
+ *
+ * CALCULATE THE CHECKSUM
+ *
+ */
+
+#define X25_INIT_CRC 0xffff
+#define X25_VALIDATE_CRC 0xf0b8
+
+/**
+ * @brief Accumulate the X.25 CRC by adding one char at a time.
+ *
+ * The checksum function adds the hash of one char at a time to the
+ * 16 bit checksum (uint16_t).
+ *
+ * @param data new char to hash
+ * @param crcAccum the already accumulated checksum
+ **/
+static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
+{
+ /*Accumulate one byte of data into the CRC*/
+ uint8_t tmp;
+
+ tmp = data ^ (uint8_t)(*crcAccum &0xff);
+ tmp ^= (tmp<<4);
+ *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4);
+}
+
+/**
+ * @brief Initiliaze the buffer for the X.25 CRC
+ *
+ * @param crcAccum the 16 bit X.25 CRC
+ */
+static inline void crc_init(uint16_t* crcAccum)
+{
+ *crcAccum = X25_INIT_CRC;
+}
+
+
+/**
+ * @brief Calculates the X.25 checksum on a byte buffer
+ *
+ * @param pBuffer buffer containing the byte array to hash
+ * @param length length of the byte array
+ * @return the checksum over the buffer bytes
+ **/
+static inline uint16_t crc_calculate(uint8_t* pBuffer, uint16_t length)
+{
+ uint16_t crcTmp;
+ crc_init(&crcTmp);
+ while (length--) {
+ crc_accumulate(*pBuffer++, &crcTmp);
+ }
+ return crcTmp;
+}
+
+/**
+ * @brief Accumulate the X.25 CRC by adding an array of bytes
+ *
+ * The checksum function adds the hash of one char at a time to the
+ * 16 bit checksum (uint16_t).
+ *
+ * @param data new bytes to hash
+ * @param crcAccum the already accumulated checksum
+ **/
+static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_t length)
+{
+ const uint8_t *p = (const uint8_t *)pBuffer;
+ while (length--) {
+ crc_accumulate(*p++, crcAccum);
+ }
+}
+
+
+
+
+#endif /* _CHECKSUM_H_ */
+
+#ifdef __cplusplus
+}
+#endif
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_helpers.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_helpers.h
new file mode 100644
index 000000000..98250e1ac
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_helpers.h
@@ -0,0 +1,488 @@
+#ifndef _MAVLINK_HELPERS_H_
+#define _MAVLINK_HELPERS_H_
+
+#include "string.h"
+#include "checksum.h"
+#include "mavlink_types.h"
+
+#ifndef MAVLINK_HELPER
+#define MAVLINK_HELPER
+#endif
+
+/*
+ internal function to give access to the channel status for each channel
+ */
+MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
+{
+ static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
+ return &m_mavlink_status[chan];
+}
+
+/**
+ * @brief Finalize a MAVLink message with channel assignment
+ *
+ * This function calculates the checksum and sets length and aircraft id correctly.
+ * It assumes that the message id and the payload are already correctly set. This function
+ * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack
+ * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead.
+ *
+ * @param msg Message to finalize
+ * @param system_id Id of the sending (this) system, 1-127
+ * @param length Message length
+ */
+#if MAVLINK_CRC_EXTRA
+MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+ uint8_t chan, uint8_t length, uint8_t crc_extra)
+#else
+MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+ uint8_t chan, uint8_t length)
+#endif
+{
+ // This code part is the same for all messages;
+ uint16_t checksum;
+ msg->magic = MAVLINK_STX;
+ msg->len = length;
+ msg->sysid = system_id;
+ msg->compid = component_id;
+ // One sequence number per component
+ msg->seq = mavlink_get_channel_status(chan)->current_tx_seq;
+ mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1;
+ checksum = crc_calculate((uint8_t*)&msg->len, length + MAVLINK_CORE_HEADER_LEN);
+#if MAVLINK_CRC_EXTRA
+ crc_accumulate(crc_extra, &checksum);
+#endif
+ mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF);
+ mavlink_ck_b(msg) = (uint8_t)(checksum >> 8);
+
+ return length + MAVLINK_NUM_NON_PAYLOAD_BYTES;
+}
+
+
+/**
+ * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel
+ */
+#if MAVLINK_CRC_EXTRA
+MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+ uint8_t length, uint8_t crc_extra)
+{
+ return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length, crc_extra);
+}
+#else
+MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+ uint8_t length)
+{
+ return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length);
+}
+#endif
+
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
+
+/**
+ * @brief Finalize a MAVLink message with channel assignment and send
+ */
+#if MAVLINK_CRC_EXTRA
+MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
+ uint8_t length, uint8_t crc_extra)
+#else
+MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length)
+#endif
+{
+ uint16_t checksum;
+ uint8_t buf[MAVLINK_NUM_HEADER_BYTES];
+ uint8_t ck[2];
+ mavlink_status_t *status = mavlink_get_channel_status(chan);
+ buf[0] = MAVLINK_STX;
+ buf[1] = length;
+ buf[2] = status->current_tx_seq;
+ buf[3] = mavlink_system.sysid;
+ buf[4] = mavlink_system.compid;
+ buf[5] = msgid;
+ status->current_tx_seq++;
+ checksum = crc_calculate((uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN);
+ crc_accumulate_buffer(&checksum, packet, length);
+#if MAVLINK_CRC_EXTRA
+ crc_accumulate(crc_extra, &checksum);
+#endif
+ ck[0] = (uint8_t)(checksum & 0xFF);
+ ck[1] = (uint8_t)(checksum >> 8);
+
+ MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
+ _mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES);
+ _mavlink_send_uart(chan, packet, length);
+ _mavlink_send_uart(chan, (const char *)ck, 2);
+ MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
+}
+#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+/**
+ * @brief Pack a message to send it over a serial byte stream
+ */
+MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg)
+{
+ memcpy(buffer, (uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len);
+ return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len;
+}
+
+union __mavlink_bitfield {
+ uint8_t uint8;
+ int8_t int8;
+ uint16_t uint16;
+ int16_t int16;
+ uint32_t uint32;
+ int32_t int32;
+};
+
+
+MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg)
+{
+ crc_init(&msg->checksum);
+}
+
+MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
+{
+ crc_accumulate(c, &msg->checksum);
+}
+
+/**
+ * This is a convenience function which handles the complete MAVLink parsing.
+ * the function will parse one byte at a time and return the complete packet once
+ * it could be successfully decoded. Checksum and other failures will be silently
+ * ignored.
+ *
+ * @param chan ID of the current channel. This allows to parse different channels with this function.
+ * a channel is not a physical message channel like a serial port, but a logic partition of
+ * the communication streams in this case. COMM_NB is the limit for the number of channels
+ * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows
+ * @param c The char to barse
+ *
+ * @param returnMsg NULL if no message could be decoded, the message data else
+ * @return 0 if no message could be decoded, 1 else
+ *
+ * A typical use scenario of this function call is:
+ *
+ * @code
+ * #include <inttypes.h> // For fixed-width uint8_t type
+ *
+ * mavlink_message_t msg;
+ * int chan = 0;
+ *
+ *
+ * while(serial.bytesAvailable > 0)
+ * {
+ * uint8_t byte = serial.getNextByte();
+ * if (mavlink_parse_char(chan, byte, &msg))
+ * {
+ * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
+ * }
+ * }
+ *
+ *
+ * @endcode
+ */
+MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
+{
+ static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS];
+
+ /*
+ default message crc function. You can override this per-system to
+ put this data in a different memory segment
+ */
+#if MAVLINK_CRC_EXTRA
+#ifndef MAVLINK_MESSAGE_CRC
+ static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS;
+#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid]
+#endif
+#endif
+
+ mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message
+ mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status
+ int bufferIndex = 0;
+
+ status->msg_received = 0;
+
+ switch (status->parse_state)
+ {
+ case MAVLINK_PARSE_STATE_UNINIT:
+ case MAVLINK_PARSE_STATE_IDLE:
+ if (c == MAVLINK_STX)
+ {
+ status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
+ rxmsg->len = 0;
+ mavlink_start_checksum(rxmsg);
+ }
+ break;
+
+ case MAVLINK_PARSE_STATE_GOT_STX:
+ if (status->msg_received
+ /* Support shorter buffers than the
+ default maximum packet size */
+#if (MAVLINK_MAX_PAYLOAD_LEN < 255)
+ || c > MAVLINK_MAX_PAYLOAD_LEN
+#endif
+ )
+ {
+ status->buffer_overrun++;
+ status->parse_error++;
+ status->msg_received = 0;
+ status->parse_state = MAVLINK_PARSE_STATE_IDLE;
+ }
+ else
+ {
+ // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2
+ rxmsg->len = c;
+ status->packet_idx = 0;
+ mavlink_update_checksum(rxmsg, c);
+ status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH;
+ }
+ break;
+
+ case MAVLINK_PARSE_STATE_GOT_LENGTH:
+ rxmsg->seq = c;
+ mavlink_update_checksum(rxmsg, c);
+ status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ;
+ break;
+
+ case MAVLINK_PARSE_STATE_GOT_SEQ:
+ rxmsg->sysid = c;
+ mavlink_update_checksum(rxmsg, c);
+ status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID;
+ break;
+
+ case MAVLINK_PARSE_STATE_GOT_SYSID:
+ rxmsg->compid = c;
+ mavlink_update_checksum(rxmsg, c);
+ status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID;
+ break;
+
+ case MAVLINK_PARSE_STATE_GOT_COMPID:
+ rxmsg->msgid = c;
+ mavlink_update_checksum(rxmsg, c);
+ if (rxmsg->len == 0)
+ {
+ status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
+ }
+ else
+ {
+ status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID;
+ }
+ break;
+
+ case MAVLINK_PARSE_STATE_GOT_MSGID:
+ _MAV_PAYLOAD(rxmsg)[status->packet_idx++] = (char)c;
+ mavlink_update_checksum(rxmsg, c);
+ if (status->packet_idx == rxmsg->len)
+ {
+ status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
+ }
+ break;
+
+ case MAVLINK_PARSE_STATE_GOT_PAYLOAD:
+#if MAVLINK_CRC_EXTRA
+ mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid));
+#endif
+ if (c != (rxmsg->checksum & 0xFF)) {
+ // Check first checksum byte
+ status->parse_error++;
+ status->msg_received = 0;
+ status->parse_state = MAVLINK_PARSE_STATE_IDLE;
+ if (c == MAVLINK_STX)
+ {
+ status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
+ rxmsg->len = 0;
+ mavlink_start_checksum(rxmsg);
+ }
+ }
+ else
+ {
+ status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;
+ }
+ break;
+
+ case MAVLINK_PARSE_STATE_GOT_CRC1:
+ if (c != (rxmsg->checksum >> 8)) {
+ // Check second checksum byte
+ status->parse_error++;
+ status->msg_received = 0;
+ status->parse_state = MAVLINK_PARSE_STATE_IDLE;
+ if (c == MAVLINK_STX)
+ {
+ status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
+ rxmsg->len = 0;
+ mavlink_start_checksum(rxmsg);
+ }
+ }
+ else
+ {
+ // Successfully got message
+ status->msg_received = 1;
+ status->parse_state = MAVLINK_PARSE_STATE_IDLE;
+ memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
+ }
+ break;
+ }
+
+ bufferIndex++;
+ // If a message has been sucessfully decoded, check index
+ if (status->msg_received == 1)
+ {
+ //while(status->current_seq != rxmsg->seq)
+ //{
+ // status->packet_rx_drop_count++;
+ // status->current_seq++;
+ //}
+ status->current_rx_seq = rxmsg->seq;
+ // Initial condition: If no packet has been received so far, drop count is undefined
+ if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0;
+ // Count this packet as received
+ status->packet_rx_success_count++;
+ }
+
+ r_mavlink_status->current_rx_seq = status->current_rx_seq+1;
+ r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count;
+ r_mavlink_status->packet_rx_drop_count = status->parse_error;
+ status->parse_error = 0;
+ return status->msg_received;
+}
+
+/**
+ * @brief Put a bitfield of length 1-32 bit into the buffer
+ *
+ * @param b the value to add, will be encoded in the bitfield
+ * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc.
+ * @param packet_index the position in the packet (the index of the first byte to use)
+ * @param bit_index the position in the byte (the index of the first bit to use)
+ * @param buffer packet buffer to write into
+ * @return new position of the last used byte in the buffer
+ */
+MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer)
+{
+ uint16_t bits_remain = bits;
+ // Transform number into network order
+ int32_t v;
+ uint8_t i_bit_index, i_byte_index, curr_bits_n;
+#if MAVLINK_NEED_BYTE_SWAP
+ union {
+ int32_t i;
+ uint8_t b[4];
+ } bin, bout;
+ bin.i = b;
+ bout.b[0] = bin.b[3];
+ bout.b[1] = bin.b[2];
+ bout.b[2] = bin.b[1];
+ bout.b[3] = bin.b[0];
+ v = bout.i;
+#else
+ v = b;
+#endif
+
+ // buffer in
+ // 01100000 01000000 00000000 11110001
+ // buffer out
+ // 11110001 00000000 01000000 01100000
+
+ // Existing partly filled byte (four free slots)
+ // 0111xxxx
+
+ // Mask n free bits
+ // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1
+ // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1
+
+ // Shift n bits into the right position
+ // out = in >> n;
+
+ // Mask and shift bytes
+ i_bit_index = bit_index;
+ i_byte_index = packet_index;
+ if (bit_index > 0)
+ {
+ // If bits were available at start, they were available
+ // in the byte before the current index
+ i_byte_index--;
+ }
+
+ // While bits have not been packed yet
+ while (bits_remain > 0)
+ {
+ // Bits still have to be packed
+ // there can be more than 8 bits, so
+ // we might have to pack them into more than one byte
+
+ // First pack everything we can into the current 'open' byte
+ //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8
+ //FIXME
+ if (bits_remain <= (uint8_t)(8 - i_bit_index))
+ {
+ // Enough space
+ curr_bits_n = (uint8_t)bits_remain;
+ }
+ else
+ {
+ curr_bits_n = (8 - i_bit_index);
+ }
+
+ // Pack these n bits into the current byte
+ // Mask out whatever was at that position with ones (xxx11111)
+ buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n));
+ // Put content to this position, by masking out the non-used part
+ buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v);
+
+ // Increment the bit index
+ i_bit_index += curr_bits_n;
+
+ // Now proceed to the next byte, if necessary
+ bits_remain -= curr_bits_n;
+ if (bits_remain > 0)
+ {
+ // Offer another 8 bits / one byte
+ i_byte_index++;
+ i_bit_index = 0;
+ }
+ }
+
+ *r_bit_index = i_bit_index;
+ // If a partly filled byte is present, mark this as consumed
+ if (i_bit_index != 7) i_byte_index++;
+ return i_byte_index - packet_index;
+}
+
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+// To make MAVLink work on your MCU, define comm_send_ch() if you wish
+// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a
+// whole packet at a time
+
+/*
+
+#include "mavlink_types.h"
+
+void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
+{
+ if (chan == MAVLINK_COMM_0)
+ {
+ uart0_transmit(ch);
+ }
+ if (chan == MAVLINK_COMM_1)
+ {
+ uart1_transmit(ch);
+ }
+}
+ */
+
+MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len)
+{
+#ifdef MAVLINK_SEND_UART_BYTES
+ /* this is the more efficient approach, if the platform
+ defines it */
+ MAVLINK_SEND_UART_BYTES(chan, (uint8_t *)buf, len);
+#else
+ /* fallback to one byte at a time */
+ uint16_t i;
+ for (i = 0; i < len; i++) {
+ comm_send_ch(chan, (uint8_t)buf[i]);
+ }
+#endif
+}
+#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+#endif /* _MAVLINK_HELPERS_H_ */
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_types.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_types.h
new file mode 100644
index 000000000..630cb84b7
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_types.h
@@ -0,0 +1,300 @@
+#ifndef MAVLINK_TYPES_H_
+#define MAVLINK_TYPES_H_
+
+#include "inttypes.h"
+
+enum MAV_CLASS
+{
+ MAV_CLASS_GENERIC = 0, ///< Generic autopilot, full support for everything
+ MAV_CLASS_PIXHAWK = 1, ///< PIXHAWK autopilot, http://pixhawk.ethz.ch
+ MAV_CLASS_SLUGS = 2, ///< SLUGS autopilot, http://slugsuav.soe.ucsc.edu
+ MAV_CLASS_ARDUPILOTMEGA = 3, ///< ArduPilotMega / ArduCopter, http://diydrones.com
+ MAV_CLASS_OPENPILOT = 4, ///< OpenPilot, http://openpilot.org
+ MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5, ///< Generic autopilot only supporting simple waypoints
+ MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, ///< Generic autopilot supporting waypoints and other simple navigation commands
+ MAV_CLASS_GENERIC_MISSION_FULL = 7, ///< Generic autopilot supporting the full mission command set
+ MAV_CLASS_NONE = 8, ///< No valid autopilot
+ MAV_CLASS_NB ///< Number of autopilot classes
+};
+
+enum MAV_ACTION
+{
+ MAV_ACTION_HOLD = 0,
+ MAV_ACTION_MOTORS_START = 1,
+ MAV_ACTION_LAUNCH = 2,
+ MAV_ACTION_RETURN = 3,
+ MAV_ACTION_EMCY_LAND = 4,
+ MAV_ACTION_EMCY_KILL = 5,
+ MAV_ACTION_CONFIRM_KILL = 6,
+ MAV_ACTION_CONTINUE = 7,
+ MAV_ACTION_MOTORS_STOP = 8,
+ MAV_ACTION_HALT = 9,
+ MAV_ACTION_SHUTDOWN = 10,
+ MAV_ACTION_REBOOT = 11,
+ MAV_ACTION_SET_MANUAL = 12,
+ MAV_ACTION_SET_AUTO = 13,
+ MAV_ACTION_STORAGE_READ = 14,
+ MAV_ACTION_STORAGE_WRITE = 15,
+ MAV_ACTION_CALIBRATE_RC = 16,
+ MAV_ACTION_CALIBRATE_GYRO = 17,
+ MAV_ACTION_CALIBRATE_MAG = 18,
+ MAV_ACTION_CALIBRATE_ACC = 19,
+ MAV_ACTION_CALIBRATE_PRESSURE = 20,
+ MAV_ACTION_REC_START = 21,
+ MAV_ACTION_REC_PAUSE = 22,
+ MAV_ACTION_REC_STOP = 23,
+ MAV_ACTION_TAKEOFF = 24,
+ MAV_ACTION_NAVIGATE = 25,
+ MAV_ACTION_LAND = 26,
+ MAV_ACTION_LOITER = 27,
+ MAV_ACTION_SET_ORIGIN = 28,
+ MAV_ACTION_RELAY_ON = 29,
+ MAV_ACTION_RELAY_OFF = 30,
+ MAV_ACTION_GET_IMAGE = 31,
+ MAV_ACTION_VIDEO_START = 32,
+ MAV_ACTION_VIDEO_STOP = 33,
+ MAV_ACTION_RESET_MAP = 34,
+ MAV_ACTION_RESET_PLAN = 35,
+ MAV_ACTION_DELAY_BEFORE_COMMAND = 36,
+ MAV_ACTION_ASCEND_AT_RATE = 37,
+ MAV_ACTION_CHANGE_MODE = 38,
+ MAV_ACTION_LOITER_MAX_TURNS = 39,
+ MAV_ACTION_LOITER_MAX_TIME = 40,
+ MAV_ACTION_START_HILSIM = 41,
+ MAV_ACTION_STOP_HILSIM = 42,
+ MAV_ACTION_NB ///< Number of MAV actions
+};
+
+enum MAV_MODE
+{
+ MAV_MODE_UNINIT = 0, ///< System is in undefined state
+ MAV_MODE_LOCKED = 1, ///< Motors are blocked, system is safe
+ MAV_MODE_MANUAL = 2, ///< System is allowed to be active, under manual (RC) control
+ MAV_MODE_GUIDED = 3, ///< System is allowed to be active, under autonomous control, manual setpoint
+ MAV_MODE_AUTO = 4, ///< System is allowed to be active, under autonomous control and navigation
+ MAV_MODE_TEST1 = 5, ///< Generic test mode, for custom use
+ MAV_MODE_TEST2 = 6, ///< Generic test mode, for custom use
+ MAV_MODE_TEST3 = 7, ///< Generic test mode, for custom use
+ MAV_MODE_READY = 8, ///< System is ready, motors are unblocked, but controllers are inactive
+ MAV_MODE_RC_TRAINING = 9 ///< System is blocked, only RC valued are read and reported back
+};
+
+enum MAV_STATE
+{
+ MAV_STATE_UNINIT = 0,
+ MAV_STATE_BOOT,
+ MAV_STATE_CALIBRATING,
+ MAV_STATE_STANDBY,
+ MAV_STATE_ACTIVE,
+ MAV_STATE_CRITICAL,
+ MAV_STATE_EMERGENCY,
+ MAV_STATE_HILSIM,
+ MAV_STATE_POWEROFF
+};
+
+enum MAV_NAV
+{
+ MAV_NAV_GROUNDED = 0,
+ MAV_NAV_LIFTOFF,
+ MAV_NAV_HOLD,
+ MAV_NAV_WAYPOINT,
+ MAV_NAV_VECTOR,
+ MAV_NAV_RETURNING,
+ MAV_NAV_LANDING,
+ MAV_NAV_LOST,
+ MAV_NAV_LOITER,
+ MAV_NAV_FREE_DRIFT
+};
+
+enum MAV_TYPE
+{
+ MAV_GENERIC = 0,
+ MAV_FIXED_WING = 1,
+ MAV_QUADROTOR = 2,
+ MAV_COAXIAL = 3,
+ MAV_HELICOPTER = 4,
+ MAV_GROUND = 5,
+ OCU = 6,
+ MAV_AIRSHIP = 7,
+ MAV_FREE_BALLOON = 8,
+ MAV_ROCKET = 9,
+ UGV_GROUND_ROVER = 10,
+ UGV_SURFACE_SHIP = 11
+};
+
+enum MAV_AUTOPILOT_TYPE
+{
+ MAV_AUTOPILOT_GENERIC = 0,
+ MAV_AUTOPILOT_PIXHAWK = 1,
+ MAV_AUTOPILOT_SLUGS = 2,
+ MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
+ MAV_AUTOPILOT_NONE = 4
+};
+
+enum MAV_COMPONENT
+{
+ MAV_COMP_ID_GPS,
+ MAV_COMP_ID_WAYPOINTPLANNER,
+ MAV_COMP_ID_BLOBTRACKER,
+ MAV_COMP_ID_PATHPLANNER,
+ MAV_COMP_ID_AIRSLAM,
+ MAV_COMP_ID_MAPPER,
+ MAV_COMP_ID_CAMERA,
+ MAV_COMP_ID_RADIO = 68,
+ MAV_COMP_ID_IMU = 200,
+ MAV_COMP_ID_IMU_2 = 201,
+ MAV_COMP_ID_IMU_3 = 202,
+ MAV_COMP_ID_UDP_BRIDGE = 240,
+ MAV_COMP_ID_UART_BRIDGE = 241,
+ MAV_COMP_ID_SYSTEM_CONTROL = 250
+};
+
+enum MAV_FRAME
+{
+ MAV_FRAME_GLOBAL = 0,
+ MAV_FRAME_LOCAL = 1,
+ MAV_FRAME_MISSION = 2,
+ MAV_FRAME_GLOBAL_RELATIVE_ALT = 3,
+ MAV_FRAME_LOCAL_ENU = 4
+};
+
+enum MAVLINK_DATA_STREAM_TYPE
+{
+ MAVLINK_DATA_STREAM_IMG_JPEG,
+ MAVLINK_DATA_STREAM_IMG_BMP,
+ MAVLINK_DATA_STREAM_IMG_RAW8U,
+ MAVLINK_DATA_STREAM_IMG_RAW32U,
+ MAVLINK_DATA_STREAM_IMG_PGM,
+ MAVLINK_DATA_STREAM_IMG_PNG
+};
+
+#ifndef MAVLINK_MAX_PAYLOAD_LEN
+// it is possible to override this, but be careful!
+#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
+#endif
+
+#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte)
+#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum
+#define MAVLINK_NUM_CHECKSUM_BYTES 2
+#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES)
+
+#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length
+
+typedef struct param_union {
+ union {
+ float param_float;
+ int32_t param_int32;
+ uint32_t param_uint32;
+ };
+ uint8_t type;
+} mavlink_param_union_t;
+
+typedef struct __mavlink_system {
+ uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function
+ uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function
+ uint8_t type; ///< Unused, can be used by user to store the system's type
+ uint8_t state; ///< Unused, can be used by user to store the system's state
+ uint8_t mode; ///< Unused, can be used by user to store the system's mode
+ uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode
+} mavlink_system_t;
+
+typedef struct __mavlink_message {
+ uint16_t checksum; /// sent at end of packet
+ uint8_t magic; ///< protocol magic marker
+ uint8_t len; ///< Length of payload
+ uint8_t seq; ///< Sequence of packet
+ uint8_t sysid; ///< ID of message sender system/aircraft
+ uint8_t compid; ///< ID of the message sender component
+ uint8_t msgid; ///< ID of message in payload
+ uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
+} mavlink_message_t;
+
+typedef enum {
+ MAVLINK_TYPE_CHAR = 0,
+ MAVLINK_TYPE_UINT8_T = 1,
+ MAVLINK_TYPE_INT8_T = 2,
+ MAVLINK_TYPE_UINT16_T = 3,
+ MAVLINK_TYPE_INT16_T = 4,
+ MAVLINK_TYPE_UINT32_T = 5,
+ MAVLINK_TYPE_INT32_T = 6,
+ MAVLINK_TYPE_UINT64_T = 7,
+ MAVLINK_TYPE_INT64_T = 8,
+ MAVLINK_TYPE_FLOAT = 9,
+ MAVLINK_TYPE_DOUBLE = 10
+} mavlink_message_type_t;
+
+#define MAVLINK_MAX_FIELDS 64
+
+typedef struct __mavlink_field_info {
+ const char *name; // name of this field
+ const char *print_format; // printing format hint, or NULL
+ mavlink_message_type_t type; // type of this field
+ unsigned array_length; // if non-zero, field is an array
+ unsigned wire_offset; // offset of each field in the payload
+ unsigned structure_offset; // offset in a C structure
+} mavlink_field_info_t;
+
+// note that in this structure the order of fields is the order
+// in the XML file, not necessary the wire order
+typedef struct __mavlink_message_info {
+ const char *name; // name of the message
+ unsigned num_fields; // how many fields in this message
+ mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information
+} mavlink_message_info_t;
+
+#define _MAV_PAYLOAD(msg) ((char *)(&(msg)->payload64[0]))
+#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0])))
+
+// checksum is immediately after the payload bytes
+#define mavlink_ck_a(msg) *(msg->len + (uint8_t *)_MAV_PAYLOAD(msg))
+#define mavlink_ck_b(msg) *((msg->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD(msg))
+
+typedef enum {
+ MAVLINK_COMM_0,
+ MAVLINK_COMM_1,
+ MAVLINK_COMM_2,
+ MAVLINK_COMM_3
+} mavlink_channel_t;
+
+/*
+ * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number
+ * of buffers they will use. If more are used, then the result will be
+ * a stack overrun
+ */
+#ifndef MAVLINK_COMM_NUM_BUFFERS
+#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
+# define MAVLINK_COMM_NUM_BUFFERS 16
+#else
+# define MAVLINK_COMM_NUM_BUFFERS 4
+#endif
+#endif
+
+typedef enum {
+ MAVLINK_PARSE_STATE_UNINIT=0,
+ MAVLINK_PARSE_STATE_IDLE,
+ MAVLINK_PARSE_STATE_GOT_STX,
+ MAVLINK_PARSE_STATE_GOT_SEQ,
+ MAVLINK_PARSE_STATE_GOT_LENGTH,
+ MAVLINK_PARSE_STATE_GOT_SYSID,
+ MAVLINK_PARSE_STATE_GOT_COMPID,
+ MAVLINK_PARSE_STATE_GOT_MSGID,
+ MAVLINK_PARSE_STATE_GOT_PAYLOAD,
+ MAVLINK_PARSE_STATE_GOT_CRC1
+} mavlink_parse_state_t; ///< The state machine for the comm parser
+
+typedef struct __mavlink_status {
+ uint8_t msg_received; ///< Number of received messages
+ uint8_t buffer_overrun; ///< Number of buffer overruns
+ uint8_t parse_error; ///< Number of parse errors
+ mavlink_parse_state_t parse_state; ///< Parsing state machine
+ uint8_t packet_idx; ///< Index in current packet
+ uint8_t current_rx_seq; ///< Sequence number of last packet received
+ uint8_t current_tx_seq; ///< Sequence number of last packet sent
+ uint16_t packet_rx_success_count; ///< Received packets
+ uint16_t packet_rx_drop_count; ///< Number of packet drops
+} mavlink_status_t;
+
+#define MAVLINK_BIG_ENDIAN 0
+#define MAVLINK_LITTLE_ENDIAN 1
+
+#endif /* MAVLINK_TYPES_H_ */
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/protocol.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/protocol.h
new file mode 100644
index 000000000..05195c369
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/protocol.h
@@ -0,0 +1,319 @@
+#ifndef _MAVLINK_PROTOCOL_H_
+#define _MAVLINK_PROTOCOL_H_
+
+#include "string.h"
+#include "mavlink_types.h"
+
+/*
+ If you want MAVLink on a system that is native big-endian,
+ you need to define NATIVE_BIG_ENDIAN
+*/
+#ifdef NATIVE_BIG_ENDIAN
+# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN)
+#else
+# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN)
+#endif
+
+#ifndef MAVLINK_STACK_BUFFER
+#define MAVLINK_STACK_BUFFER 0
+#endif
+
+#ifndef MAVLINK_AVOID_GCC_STACK_BUG
+# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__)
+#endif
+
+#ifndef MAVLINK_ASSERT
+#define MAVLINK_ASSERT(x)
+#endif
+
+#ifndef MAVLINK_START_UART_SEND
+#define MAVLINK_START_UART_SEND(chan, length)
+#endif
+
+#ifndef MAVLINK_END_UART_SEND
+#define MAVLINK_END_UART_SEND(chan, length)
+#endif
+
+#ifdef MAVLINK_SEPARATE_HELPERS
+#define MAVLINK_HELPER
+#else
+#define MAVLINK_HELPER static inline
+#include "mavlink_helpers.h"
+#endif // MAVLINK_SEPARATE_HELPERS
+
+/* always include the prototypes to ensure we don't get out of sync */
+MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan);
+#if MAVLINK_CRC_EXTRA
+MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+ uint8_t chan, uint8_t length, uint8_t crc_extra);
+MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+ uint8_t length, uint8_t crc_extra);
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
+ uint8_t length, uint8_t crc_extra);
+#endif
+#else
+MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+ uint8_t chan, uint8_t length);
+MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+ uint8_t length);
+MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length);
+#endif // MAVLINK_CRC_EXTRA
+MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg);
+MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg);
+MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c);
+MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
+MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index,
+ uint8_t* r_bit_index, uint8_t* buffer);
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
+#endif
+
+/**
+ * @brief Get the required buffer size for this message
+ */
+static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg)
+{
+ return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES;
+}
+
+#if MAVLINK_NEED_BYTE_SWAP
+static inline void byte_swap_2(char *dst, const char *src)
+{
+ dst[0] = src[1];
+ dst[1] = src[0];
+}
+static inline void byte_swap_4(char *dst, const char *src)
+{
+ dst[0] = src[3];
+ dst[1] = src[2];
+ dst[2] = src[1];
+ dst[3] = src[0];
+}
+static inline void byte_swap_8(char *dst, const char *src)
+{
+ dst[0] = src[7];
+ dst[1] = src[6];
+ dst[2] = src[5];
+ dst[3] = src[4];
+ dst[4] = src[3];
+ dst[5] = src[2];
+ dst[6] = src[1];
+ dst[7] = src[0];
+}
+#elif !MAVLINK_ALIGNED_FIELDS
+static inline void byte_copy_2(char *dst, const char *src)
+{
+ dst[0] = src[0];
+ dst[1] = src[1];
+}
+static inline void byte_copy_4(char *dst, const char *src)
+{
+ dst[0] = src[0];
+ dst[1] = src[1];
+ dst[2] = src[2];
+ dst[3] = src[3];
+}
+static inline void byte_copy_8(char *dst, const char *src)
+{
+ memcpy(dst, src, 8);
+}
+#endif
+
+#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b
+#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b
+#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b
+
+#if MAVLINK_NEED_BYTE_SWAP
+#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b)
+#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b)
+#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
+#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
+#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
+#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
+#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
+#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
+#elif !MAVLINK_ALIGNED_FIELDS
+#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b)
+#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b)
+#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
+#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
+#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
+#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
+#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
+#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
+#else
+#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b
+#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b
+#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b
+#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b
+#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b
+#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b
+#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b
+#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b
+#endif
+
+/*
+ like memcpy(), but if src is NULL, do a memset to zero
+ */
+static void mav_array_memcpy(void *dest, const void *src, size_t n)
+{
+ if (src == NULL) {
+ memset(dest, 0, n);
+ } else {
+ memcpy(dest, src, n);
+ }
+}
+
+/*
+ * Place a char array into a buffer
+ */
+static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
+{
+ mav_array_memcpy(&buf[wire_offset], b, array_length);
+}
+
+/*
+ * Place a uint8_t array into a buffer
+ */
+static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
+{
+ mav_array_memcpy(&buf[wire_offset], b, array_length);
+}
+
+/*
+ * Place a int8_t array into a buffer
+ */
+static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length)
+{
+ mav_array_memcpy(&buf[wire_offset], b, array_length);
+}
+
+#if MAVLINK_NEED_BYTE_SWAP
+#define _MAV_PUT_ARRAY(TYPE, V) \
+static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
+{ \
+ if (b == NULL) { \
+ memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \
+ } else { \
+ uint16_t i; \
+ for (i=0; i<array_length; i++) { \
+ _mav_put_## TYPE (buf, wire_offset+(i*sizeof(TYPE)), b[i]); \
+ } \
+ } \
+}
+#else
+#define _MAV_PUT_ARRAY(TYPE, V) \
+static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
+{ \
+ mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \
+}
+#endif
+
+_MAV_PUT_ARRAY(uint16_t, u16)
+_MAV_PUT_ARRAY(uint32_t, u32)
+_MAV_PUT_ARRAY(uint64_t, u64)
+_MAV_PUT_ARRAY(int16_t, i16)
+_MAV_PUT_ARRAY(int32_t, i32)
+_MAV_PUT_ARRAY(int64_t, i64)
+_MAV_PUT_ARRAY(float, f)
+_MAV_PUT_ARRAY(double, d)
+
+#define _MAV_RETURN_char(msg, wire_offset) _MAV_PAYLOAD(msg)[wire_offset]
+#define _MAV_RETURN_int8_t(msg, wire_offset) (int8_t)_MAV_PAYLOAD(msg)[wire_offset]
+#define _MAV_RETURN_uint8_t(msg, wire_offset) (uint8_t)_MAV_PAYLOAD(msg)[wire_offset]
+
+#if MAVLINK_NEED_BYTE_SWAP
+#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
+static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
+{ TYPE r; byte_swap_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
+
+_MAV_MSG_RETURN_TYPE(uint16_t, 2)
+_MAV_MSG_RETURN_TYPE(int16_t, 2)
+_MAV_MSG_RETURN_TYPE(uint32_t, 4)
+_MAV_MSG_RETURN_TYPE(int32_t, 4)
+_MAV_MSG_RETURN_TYPE(uint64_t, 8)
+_MAV_MSG_RETURN_TYPE(int64_t, 8)
+_MAV_MSG_RETURN_TYPE(float, 4)
+_MAV_MSG_RETURN_TYPE(double, 8)
+
+#elif !MAVLINK_ALIGNED_FIELDS
+#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
+static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
+{ TYPE r; byte_copy_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
+
+_MAV_MSG_RETURN_TYPE(uint16_t, 2)
+_MAV_MSG_RETURN_TYPE(int16_t, 2)
+_MAV_MSG_RETURN_TYPE(uint32_t, 4)
+_MAV_MSG_RETURN_TYPE(int32_t, 4)
+_MAV_MSG_RETURN_TYPE(uint64_t, 8)
+_MAV_MSG_RETURN_TYPE(int64_t, 8)
+_MAV_MSG_RETURN_TYPE(float, 4)
+_MAV_MSG_RETURN_TYPE(double, 8)
+#else // nicely aligned, no swap
+#define _MAV_MSG_RETURN_TYPE(TYPE) \
+static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
+{ return *(const TYPE *)(&_MAV_PAYLOAD(msg)[ofs]);}
+
+_MAV_MSG_RETURN_TYPE(uint16_t)
+_MAV_MSG_RETURN_TYPE(int16_t)
+_MAV_MSG_RETURN_TYPE(uint32_t)
+_MAV_MSG_RETURN_TYPE(int32_t)
+_MAV_MSG_RETURN_TYPE(uint64_t)
+_MAV_MSG_RETURN_TYPE(int64_t)
+_MAV_MSG_RETURN_TYPE(float)
+_MAV_MSG_RETURN_TYPE(double)
+#endif // MAVLINK_NEED_BYTE_SWAP
+
+static inline uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value,
+ uint8_t array_length, uint8_t wire_offset)
+{
+ memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
+ return array_length;
+}
+
+static inline uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value,
+ uint8_t array_length, uint8_t wire_offset)
+{
+ memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
+ return array_length;
+}
+
+static inline uint16_t _MAV_RETURN_int8_t_array(const mavlink_message_t *msg, int8_t *value,
+ uint8_t array_length, uint8_t wire_offset)
+{
+ memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
+ return array_length;
+}
+
+#if MAVLINK_NEED_BYTE_SWAP
+#define _MAV_RETURN_ARRAY(TYPE, V) \
+static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
+ uint8_t array_length, uint8_t wire_offset) \
+{ \
+ uint16_t i; \
+ for (i=0; i<array_length; i++) { \
+ value[i] = _MAV_RETURN_## TYPE (msg, wire_offset+(i*sizeof(value[0]))); \
+ } \
+ return array_length*sizeof(value[0]); \
+}
+#else
+#define _MAV_RETURN_ARRAY(TYPE, V) \
+static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
+ uint8_t array_length, uint8_t wire_offset) \
+{ \
+ memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length*sizeof(TYPE)); \
+ return array_length*sizeof(TYPE); \
+}
+#endif
+
+_MAV_RETURN_ARRAY(uint16_t, u16)
+_MAV_RETURN_ARRAY(uint32_t, u32)
+_MAV_RETURN_ARRAY(uint64_t, u64)
+_MAV_RETURN_ARRAY(int16_t, i16)
+_MAV_RETURN_ARRAY(int32_t, i32)
+_MAV_RETURN_ARRAY(int64_t, i64)
+_MAV_RETURN_ARRAY(float, f)
+_MAV_RETURN_ARRAY(double, d)
+
+#endif // _MAVLINK_PROTOCOL_H_
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/mavlink.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/mavlink.h
new file mode 100644
index 000000000..5b91bfe2d
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/mavlink.h
@@ -0,0 +1,27 @@
+/** @file
+ * @brief MAVLink comm protocol built from test.xml
+ * @see http://pixhawk.ethz.ch/software/mavlink
+ */
+#ifndef MAVLINK_H
+#define MAVLINK_H
+
+#ifndef MAVLINK_STX
+#define MAVLINK_STX 85
+#endif
+
+#ifndef MAVLINK_ENDIAN
+#define MAVLINK_ENDIAN MAVLINK_BIG_ENDIAN
+#endif
+
+#ifndef MAVLINK_ALIGNED_FIELDS
+#define MAVLINK_ALIGNED_FIELDS 0
+#endif
+
+#ifndef MAVLINK_CRC_EXTRA
+#define MAVLINK_CRC_EXTRA 0
+#endif
+
+#include "version.h"
+#include "test.h"
+
+#endif // MAVLINK_H
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/mavlink_msg_test_types.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/mavlink_msg_test_types.h
new file mode 100644
index 000000000..50b4fd6bc
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/mavlink_msg_test_types.h
@@ -0,0 +1,610 @@
+// MESSAGE TEST_TYPES PACKING
+
+#define MAVLINK_MSG_ID_TEST_TYPES 0
+
+typedef struct __mavlink_test_types_t
+{
+ char c; ///< char
+ char s[10]; ///< string
+ uint8_t u8; ///< uint8_t
+ uint16_t u16; ///< uint16_t
+ uint32_t u32; ///< uint32_t
+ uint64_t u64; ///< uint64_t
+ int8_t s8; ///< int8_t
+ int16_t s16; ///< int16_t
+ int32_t s32; ///< int32_t
+ int64_t s64; ///< int64_t
+ float f; ///< float
+ double d; ///< double
+ uint8_t u8_array[3]; ///< uint8_t_array
+ uint16_t u16_array[3]; ///< uint16_t_array
+ uint32_t u32_array[3]; ///< uint32_t_array
+ uint64_t u64_array[3]; ///< uint64_t_array
+ int8_t s8_array[3]; ///< int8_t_array
+ int16_t s16_array[3]; ///< int16_t_array
+ int32_t s32_array[3]; ///< int32_t_array
+ int64_t s64_array[3]; ///< int64_t_array
+ float f_array[3]; ///< float_array
+ double d_array[3]; ///< double_array
+} mavlink_test_types_t;
+
+#define MAVLINK_MSG_ID_TEST_TYPES_LEN 179
+#define MAVLINK_MSG_ID_0_LEN 179
+
+#define MAVLINK_MSG_TEST_TYPES_FIELD_S_LEN 10
+#define MAVLINK_MSG_TEST_TYPES_FIELD_U8_ARRAY_LEN 3
+#define MAVLINK_MSG_TEST_TYPES_FIELD_U16_ARRAY_LEN 3
+#define MAVLINK_MSG_TEST_TYPES_FIELD_U32_ARRAY_LEN 3
+#define MAVLINK_MSG_TEST_TYPES_FIELD_U64_ARRAY_LEN 3
+#define MAVLINK_MSG_TEST_TYPES_FIELD_S8_ARRAY_LEN 3
+#define MAVLINK_MSG_TEST_TYPES_FIELD_S16_ARRAY_LEN 3
+#define MAVLINK_MSG_TEST_TYPES_FIELD_S32_ARRAY_LEN 3
+#define MAVLINK_MSG_TEST_TYPES_FIELD_S64_ARRAY_LEN 3
+#define MAVLINK_MSG_TEST_TYPES_FIELD_F_ARRAY_LEN 3
+#define MAVLINK_MSG_TEST_TYPES_FIELD_D_ARRAY_LEN 3
+
+#define MAVLINK_MESSAGE_INFO_TEST_TYPES { \
+ "TEST_TYPES", \
+ 22, \
+ { { "c", NULL, MAVLINK_TYPE_CHAR, 0, 0, offsetof(mavlink_test_types_t, c) }, \
+ { "s", NULL, MAVLINK_TYPE_CHAR, 10, 1, offsetof(mavlink_test_types_t, s) }, \
+ { "u8", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_test_types_t, u8) }, \
+ { "u16", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_test_types_t, u16) }, \
+ { "u32", "0x%08x", MAVLINK_TYPE_UINT32_T, 0, 14, offsetof(mavlink_test_types_t, u32) }, \
+ { "u64", NULL, MAVLINK_TYPE_UINT64_T, 0, 18, offsetof(mavlink_test_types_t, u64) }, \
+ { "s8", NULL, MAVLINK_TYPE_INT8_T, 0, 26, offsetof(mavlink_test_types_t, s8) }, \
+ { "s16", NULL, MAVLINK_TYPE_INT16_T, 0, 27, offsetof(mavlink_test_types_t, s16) }, \
+ { "s32", NULL, MAVLINK_TYPE_INT32_T, 0, 29, offsetof(mavlink_test_types_t, s32) }, \
+ { "s64", NULL, MAVLINK_TYPE_INT64_T, 0, 33, offsetof(mavlink_test_types_t, s64) }, \
+ { "f", NULL, MAVLINK_TYPE_FLOAT, 0, 41, offsetof(mavlink_test_types_t, f) }, \
+ { "d", NULL, MAVLINK_TYPE_DOUBLE, 0, 45, offsetof(mavlink_test_types_t, d) }, \
+ { "u8_array", NULL, MAVLINK_TYPE_UINT8_T, 3, 53, offsetof(mavlink_test_types_t, u8_array) }, \
+ { "u16_array", NULL, MAVLINK_TYPE_UINT16_T, 3, 56, offsetof(mavlink_test_types_t, u16_array) }, \
+ { "u32_array", NULL, MAVLINK_TYPE_UINT32_T, 3, 62, offsetof(mavlink_test_types_t, u32_array) }, \
+ { "u64_array", NULL, MAVLINK_TYPE_UINT64_T, 3, 74, offsetof(mavlink_test_types_t, u64_array) }, \
+ { "s8_array", NULL, MAVLINK_TYPE_INT8_T, 3, 98, offsetof(mavlink_test_types_t, s8_array) }, \
+ { "s16_array", NULL, MAVLINK_TYPE_INT16_T, 3, 101, offsetof(mavlink_test_types_t, s16_array) }, \
+ { "s32_array", NULL, MAVLINK_TYPE_INT32_T, 3, 107, offsetof(mavlink_test_types_t, s32_array) }, \
+ { "s64_array", NULL, MAVLINK_TYPE_INT64_T, 3, 119, offsetof(mavlink_test_types_t, s64_array) }, \
+ { "f_array", NULL, MAVLINK_TYPE_FLOAT, 3, 143, offsetof(mavlink_test_types_t, f_array) }, \
+ { "d_array", NULL, MAVLINK_TYPE_DOUBLE, 3, 155, offsetof(mavlink_test_types_t, d_array) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a test_types 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 c char
+ * @param s string
+ * @param u8 uint8_t
+ * @param u16 uint16_t
+ * @param u32 uint32_t
+ * @param u64 uint64_t
+ * @param s8 int8_t
+ * @param s16 int16_t
+ * @param s32 int32_t
+ * @param s64 int64_t
+ * @param f float
+ * @param d double
+ * @param u8_array uint8_t_array
+ * @param u16_array uint16_t_array
+ * @param u32_array uint32_t_array
+ * @param u64_array uint64_t_array
+ * @param s8_array int8_t_array
+ * @param s16_array int16_t_array
+ * @param s32_array int32_t_array
+ * @param s64_array int64_t_array
+ * @param f_array float_array
+ * @param d_array double_array
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_test_types_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[179];
+ _mav_put_char(buf, 0, c);
+ _mav_put_uint8_t(buf, 11, u8);
+ _mav_put_uint16_t(buf, 12, u16);
+ _mav_put_uint32_t(buf, 14, u32);
+ _mav_put_uint64_t(buf, 18, u64);
+ _mav_put_int8_t(buf, 26, s8);
+ _mav_put_int16_t(buf, 27, s16);
+ _mav_put_int32_t(buf, 29, s32);
+ _mav_put_int64_t(buf, 33, s64);
+ _mav_put_float(buf, 41, f);
+ _mav_put_double(buf, 45, d);
+ _mav_put_char_array(buf, 1, s, 10);
+ _mav_put_uint8_t_array(buf, 53, u8_array, 3);
+ _mav_put_uint16_t_array(buf, 56, u16_array, 3);
+ _mav_put_uint32_t_array(buf, 62, u32_array, 3);
+ _mav_put_uint64_t_array(buf, 74, u64_array, 3);
+ _mav_put_int8_t_array(buf, 98, s8_array, 3);
+ _mav_put_int16_t_array(buf, 101, s16_array, 3);
+ _mav_put_int32_t_array(buf, 107, s32_array, 3);
+ _mav_put_int64_t_array(buf, 119, s64_array, 3);
+ _mav_put_float_array(buf, 143, f_array, 3);
+ _mav_put_double_array(buf, 155, d_array, 3);
+ memcpy(_MAV_PAYLOAD(msg), buf, 179);
+#else
+ mavlink_test_types_t packet;
+ packet.c = c;
+ packet.u8 = u8;
+ packet.u16 = u16;
+ packet.u32 = u32;
+ packet.u64 = u64;
+ packet.s8 = s8;
+ packet.s16 = s16;
+ packet.s32 = s32;
+ packet.s64 = s64;
+ packet.f = f;
+ packet.d = d;
+ mav_array_memcpy(packet.s, s, sizeof(char)*10);
+ mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3);
+ mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3);
+ mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3);
+ mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3);
+ mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3);
+ mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3);
+ mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3);
+ mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3);
+ mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3);
+ mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3);
+ memcpy(_MAV_PAYLOAD(msg), &packet, 179);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_TEST_TYPES;
+ return mavlink_finalize_message(msg, system_id, component_id, 179);
+}
+
+/**
+ * @brief Pack a test_types 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 c char
+ * @param s string
+ * @param u8 uint8_t
+ * @param u16 uint16_t
+ * @param u32 uint32_t
+ * @param u64 uint64_t
+ * @param s8 int8_t
+ * @param s16 int16_t
+ * @param s32 int32_t
+ * @param s64 int64_t
+ * @param f float
+ * @param d double
+ * @param u8_array uint8_t_array
+ * @param u16_array uint16_t_array
+ * @param u32_array uint32_t_array
+ * @param u64_array uint64_t_array
+ * @param s8_array int8_t_array
+ * @param s16_array int16_t_array
+ * @param s32_array int32_t_array
+ * @param s64_array int64_t_array
+ * @param f_array float_array
+ * @param d_array double_array
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_test_types_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ char c,const char *s,uint8_t u8,uint16_t u16,uint32_t u32,uint64_t u64,int8_t s8,int16_t s16,int32_t s32,int64_t s64,float f,double d,const uint8_t *u8_array,const uint16_t *u16_array,const uint32_t *u32_array,const uint64_t *u64_array,const int8_t *s8_array,const int16_t *s16_array,const int32_t *s32_array,const int64_t *s64_array,const float *f_array,const double *d_array)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[179];
+ _mav_put_char(buf, 0, c);
+ _mav_put_uint8_t(buf, 11, u8);
+ _mav_put_uint16_t(buf, 12, u16);
+ _mav_put_uint32_t(buf, 14, u32);
+ _mav_put_uint64_t(buf, 18, u64);
+ _mav_put_int8_t(buf, 26, s8);
+ _mav_put_int16_t(buf, 27, s16);
+ _mav_put_int32_t(buf, 29, s32);
+ _mav_put_int64_t(buf, 33, s64);
+ _mav_put_float(buf, 41, f);
+ _mav_put_double(buf, 45, d);
+ _mav_put_char_array(buf, 1, s, 10);
+ _mav_put_uint8_t_array(buf, 53, u8_array, 3);
+ _mav_put_uint16_t_array(buf, 56, u16_array, 3);
+ _mav_put_uint32_t_array(buf, 62, u32_array, 3);
+ _mav_put_uint64_t_array(buf, 74, u64_array, 3);
+ _mav_put_int8_t_array(buf, 98, s8_array, 3);
+ _mav_put_int16_t_array(buf, 101, s16_array, 3);
+ _mav_put_int32_t_array(buf, 107, s32_array, 3);
+ _mav_put_int64_t_array(buf, 119, s64_array, 3);
+ _mav_put_float_array(buf, 143, f_array, 3);
+ _mav_put_double_array(buf, 155, d_array, 3);
+ memcpy(_MAV_PAYLOAD(msg), buf, 179);
+#else
+ mavlink_test_types_t packet;
+ packet.c = c;
+ packet.u8 = u8;
+ packet.u16 = u16;
+ packet.u32 = u32;
+ packet.u64 = u64;
+ packet.s8 = s8;
+ packet.s16 = s16;
+ packet.s32 = s32;
+ packet.s64 = s64;
+ packet.f = f;
+ packet.d = d;
+ mav_array_memcpy(packet.s, s, sizeof(char)*10);
+ mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3);
+ mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3);
+ mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3);
+ mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3);
+ mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3);
+ mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3);
+ mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3);
+ mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3);
+ mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3);
+ mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3);
+ memcpy(_MAV_PAYLOAD(msg), &packet, 179);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_TEST_TYPES;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 179);
+}
+
+/**
+ * @brief Encode a test_types 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 test_types C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_test_types_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_test_types_t* test_types)
+{
+ return mavlink_msg_test_types_pack(system_id, component_id, msg, test_types->c, test_types->s, test_types->u8, test_types->u16, test_types->u32, test_types->u64, test_types->s8, test_types->s16, test_types->s32, test_types->s64, test_types->f, test_types->d, test_types->u8_array, test_types->u16_array, test_types->u32_array, test_types->u64_array, test_types->s8_array, test_types->s16_array, test_types->s32_array, test_types->s64_array, test_types->f_array, test_types->d_array);
+}
+
+/**
+ * @brief Send a test_types message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param c char
+ * @param s string
+ * @param u8 uint8_t
+ * @param u16 uint16_t
+ * @param u32 uint32_t
+ * @param u64 uint64_t
+ * @param s8 int8_t
+ * @param s16 int16_t
+ * @param s32 int32_t
+ * @param s64 int64_t
+ * @param f float
+ * @param d double
+ * @param u8_array uint8_t_array
+ * @param u16_array uint16_t_array
+ * @param u32_array uint32_t_array
+ * @param u64_array uint64_t_array
+ * @param s8_array int8_t_array
+ * @param s16_array int16_t_array
+ * @param s32_array int32_t_array
+ * @param s64_array int64_t_array
+ * @param f_array float_array
+ * @param d_array double_array
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_test_types_send(mavlink_channel_t chan, char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[179];
+ _mav_put_char(buf, 0, c);
+ _mav_put_uint8_t(buf, 11, u8);
+ _mav_put_uint16_t(buf, 12, u16);
+ _mav_put_uint32_t(buf, 14, u32);
+ _mav_put_uint64_t(buf, 18, u64);
+ _mav_put_int8_t(buf, 26, s8);
+ _mav_put_int16_t(buf, 27, s16);
+ _mav_put_int32_t(buf, 29, s32);
+ _mav_put_int64_t(buf, 33, s64);
+ _mav_put_float(buf, 41, f);
+ _mav_put_double(buf, 45, d);
+ _mav_put_char_array(buf, 1, s, 10);
+ _mav_put_uint8_t_array(buf, 53, u8_array, 3);
+ _mav_put_uint16_t_array(buf, 56, u16_array, 3);
+ _mav_put_uint32_t_array(buf, 62, u32_array, 3);
+ _mav_put_uint64_t_array(buf, 74, u64_array, 3);
+ _mav_put_int8_t_array(buf, 98, s8_array, 3);
+ _mav_put_int16_t_array(buf, 101, s16_array, 3);
+ _mav_put_int32_t_array(buf, 107, s32_array, 3);
+ _mav_put_int64_t_array(buf, 119, s64_array, 3);
+ _mav_put_float_array(buf, 143, f_array, 3);
+ _mav_put_double_array(buf, 155, d_array, 3);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, buf, 179);
+#else
+ mavlink_test_types_t packet;
+ packet.c = c;
+ packet.u8 = u8;
+ packet.u16 = u16;
+ packet.u32 = u32;
+ packet.u64 = u64;
+ packet.s8 = s8;
+ packet.s16 = s16;
+ packet.s32 = s32;
+ packet.s64 = s64;
+ packet.f = f;
+ packet.d = d;
+ mav_array_memcpy(packet.s, s, sizeof(char)*10);
+ mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3);
+ mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3);
+ mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3);
+ mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3);
+ mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3);
+ mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3);
+ mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3);
+ mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3);
+ mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3);
+ mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, (const char *)&packet, 179);
+#endif
+}
+
+#endif
+
+// MESSAGE TEST_TYPES UNPACKING
+
+
+/**
+ * @brief Get field c from test_types message
+ *
+ * @return char
+ */
+static inline char mavlink_msg_test_types_get_c(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_char(msg, 0);
+}
+
+/**
+ * @brief Get field s from test_types message
+ *
+ * @return string
+ */
+static inline uint16_t mavlink_msg_test_types_get_s(const mavlink_message_t* msg, char *s)
+{
+ return _MAV_RETURN_char_array(msg, s, 10, 1);
+}
+
+/**
+ * @brief Get field u8 from test_types message
+ *
+ * @return uint8_t
+ */
+static inline uint8_t mavlink_msg_test_types_get_u8(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 11);
+}
+
+/**
+ * @brief Get field u16 from test_types message
+ *
+ * @return uint16_t
+ */
+static inline uint16_t mavlink_msg_test_types_get_u16(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 12);
+}
+
+/**
+ * @brief Get field u32 from test_types message
+ *
+ * @return uint32_t
+ */
+static inline uint32_t mavlink_msg_test_types_get_u32(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 14);
+}
+
+/**
+ * @brief Get field u64 from test_types message
+ *
+ * @return uint64_t
+ */
+static inline uint64_t mavlink_msg_test_types_get_u64(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint64_t(msg, 18);
+}
+
+/**
+ * @brief Get field s8 from test_types message
+ *
+ * @return int8_t
+ */
+static inline int8_t mavlink_msg_test_types_get_s8(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int8_t(msg, 26);
+}
+
+/**
+ * @brief Get field s16 from test_types message
+ *
+ * @return int16_t
+ */
+static inline int16_t mavlink_msg_test_types_get_s16(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 27);
+}
+
+/**
+ * @brief Get field s32 from test_types message
+ *
+ * @return int32_t
+ */
+static inline int32_t mavlink_msg_test_types_get_s32(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 29);
+}
+
+/**
+ * @brief Get field s64 from test_types message
+ *
+ * @return int64_t
+ */
+static inline int64_t mavlink_msg_test_types_get_s64(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int64_t(msg, 33);
+}
+
+/**
+ * @brief Get field f from test_types message
+ *
+ * @return float
+ */
+static inline float mavlink_msg_test_types_get_f(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 41);
+}
+
+/**
+ * @brief Get field d from test_types message
+ *
+ * @return double
+ */
+static inline double mavlink_msg_test_types_get_d(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_double(msg, 45);
+}
+
+/**
+ * @brief Get field u8_array from test_types message
+ *
+ * @return uint8_t_array
+ */
+static inline uint16_t mavlink_msg_test_types_get_u8_array(const mavlink_message_t* msg, uint8_t *u8_array)
+{
+ return _MAV_RETURN_uint8_t_array(msg, u8_array, 3, 53);
+}
+
+/**
+ * @brief Get field u16_array from test_types message
+ *
+ * @return uint16_t_array
+ */
+static inline uint16_t mavlink_msg_test_types_get_u16_array(const mavlink_message_t* msg, uint16_t *u16_array)
+{
+ return _MAV_RETURN_uint16_t_array(msg, u16_array, 3, 56);
+}
+
+/**
+ * @brief Get field u32_array from test_types message
+ *
+ * @return uint32_t_array
+ */
+static inline uint16_t mavlink_msg_test_types_get_u32_array(const mavlink_message_t* msg, uint32_t *u32_array)
+{
+ return _MAV_RETURN_uint32_t_array(msg, u32_array, 3, 62);
+}
+
+/**
+ * @brief Get field u64_array from test_types message
+ *
+ * @return uint64_t_array
+ */
+static inline uint16_t mavlink_msg_test_types_get_u64_array(const mavlink_message_t* msg, uint64_t *u64_array)
+{
+ return _MAV_RETURN_uint64_t_array(msg, u64_array, 3, 74);
+}
+
+/**
+ * @brief Get field s8_array from test_types message
+ *
+ * @return int8_t_array
+ */
+static inline uint16_t mavlink_msg_test_types_get_s8_array(const mavlink_message_t* msg, int8_t *s8_array)
+{
+ return _MAV_RETURN_int8_t_array(msg, s8_array, 3, 98);
+}
+
+/**
+ * @brief Get field s16_array from test_types message
+ *
+ * @return int16_t_array
+ */
+static inline uint16_t mavlink_msg_test_types_get_s16_array(const mavlink_message_t* msg, int16_t *s16_array)
+{
+ return _MAV_RETURN_int16_t_array(msg, s16_array, 3, 101);
+}
+
+/**
+ * @brief Get field s32_array from test_types message
+ *
+ * @return int32_t_array
+ */
+static inline uint16_t mavlink_msg_test_types_get_s32_array(const mavlink_message_t* msg, int32_t *s32_array)
+{
+ return _MAV_RETURN_int32_t_array(msg, s32_array, 3, 107);
+}
+
+/**
+ * @brief Get field s64_array from test_types message
+ *
+ * @return int64_t_array
+ */
+static inline uint16_t mavlink_msg_test_types_get_s64_array(const mavlink_message_t* msg, int64_t *s64_array)
+{
+ return _MAV_RETURN_int64_t_array(msg, s64_array, 3, 119);
+}
+
+/**
+ * @brief Get field f_array from test_types message
+ *
+ * @return float_array
+ */
+static inline uint16_t mavlink_msg_test_types_get_f_array(const mavlink_message_t* msg, float *f_array)
+{
+ return _MAV_RETURN_float_array(msg, f_array, 3, 143);
+}
+
+/**
+ * @brief Get field d_array from test_types message
+ *
+ * @return double_array
+ */
+static inline uint16_t mavlink_msg_test_types_get_d_array(const mavlink_message_t* msg, double *d_array)
+{
+ return _MAV_RETURN_double_array(msg, d_array, 3, 155);
+}
+
+/**
+ * @brief Decode a test_types message into a struct
+ *
+ * @param msg The message to decode
+ * @param test_types C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_test_types_decode(const mavlink_message_t* msg, mavlink_test_types_t* test_types)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ test_types->c = mavlink_msg_test_types_get_c(msg);
+ mavlink_msg_test_types_get_s(msg, test_types->s);
+ test_types->u8 = mavlink_msg_test_types_get_u8(msg);
+ test_types->u16 = mavlink_msg_test_types_get_u16(msg);
+ test_types->u32 = mavlink_msg_test_types_get_u32(msg);
+ test_types->u64 = mavlink_msg_test_types_get_u64(msg);
+ test_types->s8 = mavlink_msg_test_types_get_s8(msg);
+ test_types->s16 = mavlink_msg_test_types_get_s16(msg);
+ test_types->s32 = mavlink_msg_test_types_get_s32(msg);
+ test_types->s64 = mavlink_msg_test_types_get_s64(msg);
+ test_types->f = mavlink_msg_test_types_get_f(msg);
+ test_types->d = mavlink_msg_test_types_get_d(msg);
+ mavlink_msg_test_types_get_u8_array(msg, test_types->u8_array);
+ mavlink_msg_test_types_get_u16_array(msg, test_types->u16_array);
+ mavlink_msg_test_types_get_u32_array(msg, test_types->u32_array);
+ mavlink_msg_test_types_get_u64_array(msg, test_types->u64_array);
+ mavlink_msg_test_types_get_s8_array(msg, test_types->s8_array);
+ mavlink_msg_test_types_get_s16_array(msg, test_types->s16_array);
+ mavlink_msg_test_types_get_s32_array(msg, test_types->s32_array);
+ mavlink_msg_test_types_get_s64_array(msg, test_types->s64_array);
+ mavlink_msg_test_types_get_f_array(msg, test_types->f_array);
+ mavlink_msg_test_types_get_d_array(msg, test_types->d_array);
+#else
+ memcpy(test_types, _MAV_PAYLOAD(msg), 179);
+#endif
+}
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/test.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/test.h
new file mode 100644
index 000000000..23ee65986
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/test.h
@@ -0,0 +1,53 @@
+/** @file
+ * @brief MAVLink comm protocol generated from test.xml
+ * @see http://qgroundcontrol.org/mavlink/
+ */
+#ifndef TEST_H
+#define TEST_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+// MESSAGE LENGTHS AND CRCS
+
+#ifndef MAVLINK_MESSAGE_LENGTHS
+#define MAVLINK_MESSAGE_LENGTHS {179, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
+#endif
+
+#ifndef MAVLINK_MESSAGE_CRCS
+#define MAVLINK_MESSAGE_CRCS {91, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
+#endif
+
+#ifndef MAVLINK_MESSAGE_INFO
+#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_TEST_TYPES, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}}
+#endif
+
+#include "../protocol.h"
+
+#define MAVLINK_ENABLED_TEST
+
+
+
+// MAVLINK VERSION
+
+#ifndef MAVLINK_VERSION
+#define MAVLINK_VERSION 3
+#endif
+
+#if (MAVLINK_VERSION == 0)
+#undef MAVLINK_VERSION
+#define MAVLINK_VERSION 3
+#endif
+
+// ENUM DEFINITIONS
+
+
+
+// MESSAGE DEFINITIONS
+#include "./mavlink_msg_test_types.h"
+
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+#endif // TEST_H
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/testsuite.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/testsuite.h
new file mode 100644
index 000000000..9b0fc041b
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/testsuite.h
@@ -0,0 +1,120 @@
+/** @file
+ * @brief MAVLink comm protocol testsuite generated from test.xml
+ * @see http://qgroundcontrol.org/mavlink/
+ */
+#ifndef TEST_TESTSUITE_H
+#define TEST_TESTSUITE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#ifndef MAVLINK_TEST_ALL
+#define MAVLINK_TEST_ALL
+
+static void mavlink_test_test(uint8_t, uint8_t, mavlink_message_t *last_msg);
+
+static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+
+ mavlink_test_test(system_id, component_id, last_msg);
+}
+#endif
+
+
+
+
+static void mavlink_test_test_types(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_test_types_t packet_in = {
+ 'A',
+ "BCDEFGHIJ",
+ 230,
+ 17859,
+ 963498192,
+ 93372036854776941ULL,
+ 211,
+ 18639,
+ 963498972,
+ 93372036854777886LL,
+ 304.0,
+ 438.0,
+ { 228, 229, 230 },
+ { 20147, 20148, 20149 },
+ { 963500688, 963500689, 963500690 },
+ { 93372036854780469, 93372036854780470, 93372036854780471 },
+ { 171, 172, 173 },
+ { 22487, 22488, 22489 },
+ { 963503028, 963503029, 963503030 },
+ { 93372036854783304, 93372036854783305, 93372036854783306 },
+ { 1018.0, 1019.0, 1020.0 },
+ { 1208.0, 1209.0, 1210.0 },
+ };
+ mavlink_test_types_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.c = packet_in.c;
+ packet1.u8 = packet_in.u8;
+ packet1.u16 = packet_in.u16;
+ packet1.u32 = packet_in.u32;
+ packet1.u64 = packet_in.u64;
+ packet1.s8 = packet_in.s8;
+ packet1.s16 = packet_in.s16;
+ packet1.s32 = packet_in.s32;
+ packet1.s64 = packet_in.s64;
+ packet1.f = packet_in.f;
+ packet1.d = packet_in.d;
+
+ mav_array_memcpy(packet1.s, packet_in.s, sizeof(char)*10);
+ mav_array_memcpy(packet1.u8_array, packet_in.u8_array, sizeof(uint8_t)*3);
+ mav_array_memcpy(packet1.u16_array, packet_in.u16_array, sizeof(uint16_t)*3);
+ mav_array_memcpy(packet1.u32_array, packet_in.u32_array, sizeof(uint32_t)*3);
+ mav_array_memcpy(packet1.u64_array, packet_in.u64_array, sizeof(uint64_t)*3);
+ mav_array_memcpy(packet1.s8_array, packet_in.s8_array, sizeof(int8_t)*3);
+ mav_array_memcpy(packet1.s16_array, packet_in.s16_array, sizeof(int16_t)*3);
+ mav_array_memcpy(packet1.s32_array, packet_in.s32_array, sizeof(int32_t)*3);
+ mav_array_memcpy(packet1.s64_array, packet_in.s64_array, sizeof(int64_t)*3);
+ mav_array_memcpy(packet1.f_array, packet_in.f_array, sizeof(float)*3);
+ mav_array_memcpy(packet1.d_array, packet_in.d_array, sizeof(double)*3);
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_test_types_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_test_types_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_test_types_pack(system_id, component_id, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array );
+ mavlink_msg_test_types_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_test_types_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array );
+ mavlink_msg_test_types_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_test_types_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_test_types_send(MAVLINK_COMM_1 , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array );
+ mavlink_msg_test_types_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_test(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_test_test_types(system_id, component_id, last_msg);
+}
+
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+#endif // TEST_TESTSUITE_H
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/version.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/version.h
new file mode 100644
index 000000000..64ca0cb38
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/version.h
@@ -0,0 +1,12 @@
+/** @file
+ * @brief MAVLink comm protocol built from test.xml
+ * @see http://pixhawk.ethz.ch/software/mavlink
+ */
+#ifndef MAVLINK_VERSION_H
+#define MAVLINK_VERSION_H
+
+#define MAVLINK_BUILD_DATE "Thu Mar 1 15:11:54 2012"
+#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
+#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 179
+
+#endif // MAVLINK_VERSION_H