aboutsummaryrefslogtreecommitdiff
path: root/mavlink/share/pyshared/pymavlink/generator
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2012-08-04 15:12:36 -0700
committerpx4dev <px4@purgatory.org>2012-08-04 15:12:36 -0700
commit8a365179eafdf3aea98e60ab9f5882b200d4c759 (patch)
tree4f38d6d4cd80bd0b6e22e2bb534c3f117ce44e56 /mavlink/share/pyshared/pymavlink/generator
downloadpx4-firmware-8a365179eafdf3aea98e60ab9f5882b200d4c759.tar.gz
px4-firmware-8a365179eafdf3aea98e60ab9f5882b200d4c759.tar.bz2
px4-firmware-8a365179eafdf3aea98e60ab9f5882b200d4c759.zip
Fresh import of the PX4 firmware sources.
Diffstat (limited to 'mavlink/share/pyshared/pymavlink/generator')
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/.gitignore1
-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
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/checksum.h89
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_helpers.h507
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_protobuf_manager.hpp377
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_types.h158
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/pixhawk/pixhawk.pb.h3663
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/protocol.h322
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/mavlink.h27
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/mavlink_msg_test_types.h610
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/test.h53
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/testsuite.h120
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/version.h12
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/src_v1.0/pixhawk/pixhawk.pb.cc5431
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/test/posix/.gitignore3
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/test/posix/Makefile31
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/test/posix/testmav.c159
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.cpp8
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.h15
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/test/windows/targetver.h8
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.cpp154
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.sln20
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.suobin0 -> 15872 bytes
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.vcxproj91
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/gen_MatrixPilot.py93
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/gen_all.py44
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/gen_all.sh12
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/mavgen.py82
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/mavgen_c.py581
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/mavgen_python.py455
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/mavparse.py372
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/mavtemplate.py121
-rw-r--r--mavlink/share/pyshared/pymavlink/generator/mavtestgen.py142
41 files changed, 15779 insertions, 0 deletions
diff --git a/mavlink/share/pyshared/pymavlink/generator/.gitignore b/mavlink/share/pyshared/pymavlink/generator/.gitignore
new file mode 100644
index 000000000..0d20b6487
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/.gitignore
@@ -0,0 +1 @@
+*.pyc
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
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/checksum.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/checksum.h
new file mode 100644
index 000000000..4f4cce02f
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/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(const 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_v1.0/mavlink_helpers.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_helpers.h
new file mode 100644
index 000000000..39d6930e5
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_helpers.h
@@ -0,0 +1,507 @@
+#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];
+}
+
+/*
+ internal function to give access to the channel buffer for each channel
+ */
+MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan)
+{
+
+#if MAVLINK_EXTERNAL_RX_BUFFER
+ // No m_mavlink_message array defined in function,
+ // has to be defined externally
+#ifndef m_mavlink_message
+#error ERROR: IF #define MAVLINK_EXTERNAL_RX_BUFFER IS SET, THE BUFFER HAS TO BE ALLOCATED OUTSIDE OF THIS FUNCTION (mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];)
+#endif
+#else
+ static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];
+#endif
+ return &m_mavlink_buffer[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, (const 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)
+{
+ /*
+ 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 = mavlink_get_channel_buffer(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;
+ rxmsg->magic = c;
+ 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_NON_CONST(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;
+ _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c;
+ }
+ 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;
+ _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c;
+ 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_v1.0/mavlink_protobuf_manager.hpp b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_protobuf_manager.hpp
new file mode 100644
index 000000000..fd3ddd026
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_protobuf_manager.hpp
@@ -0,0 +1,377 @@
+#ifndef MAVLINKPROTOBUFMANAGER_HPP
+#define MAVLINKPROTOBUFMANAGER_HPP
+
+#include <deque>
+#include <google/protobuf/message.h>
+#include <iostream>
+#include <tr1/memory>
+
+#include <checksum.h>
+#include <common/mavlink.h>
+#include <mavlink_types.h>
+#include <pixhawk/pixhawk.pb.h>
+
+namespace mavlink
+{
+
+class ProtobufManager
+{
+public:
+ ProtobufManager()
+ : mRegisteredTypeCount(0)
+ , mStreamID(0)
+ , mVerbose(false)
+ , kExtendedHeaderSize(MAVLINK_EXTENDED_HEADER_LEN)
+ , kExtendedPayloadMaxSize(MAVLINK_MAX_EXTENDED_PAYLOAD_LEN)
+ {
+ // register GLOverlay
+ {
+ std::tr1::shared_ptr<px::GLOverlay> msg(new px::GLOverlay);
+ registerType(msg);
+ }
+
+ // register ObstacleList
+ {
+ std::tr1::shared_ptr<px::ObstacleList> msg(new px::ObstacleList);
+ registerType(msg);
+ }
+
+ // register ObstacleMap
+ {
+ std::tr1::shared_ptr<px::ObstacleMap> msg(new px::ObstacleMap);
+ registerType(msg);
+ }
+
+ // register Path
+ {
+ std::tr1::shared_ptr<px::Path> msg(new px::Path);
+ registerType(msg);
+ }
+
+ // register PointCloudXYZI
+ {
+ std::tr1::shared_ptr<px::PointCloudXYZI> msg(new px::PointCloudXYZI);
+ registerType(msg);
+ }
+
+ // register PointCloudXYZRGB
+ {
+ std::tr1::shared_ptr<px::PointCloudXYZRGB> msg(new px::PointCloudXYZRGB);
+ registerType(msg);
+ }
+
+ // register RGBDImage
+ {
+ std::tr1::shared_ptr<px::RGBDImage> msg(new px::RGBDImage);
+ registerType(msg);
+ }
+
+ srand(time(NULL));
+ mStreamID = rand() + 1;
+ }
+
+ bool fragmentMessage(uint8_t system_id, uint8_t component_id,
+ uint8_t target_system, uint8_t target_component,
+ const google::protobuf::Message& protobuf_msg,
+ std::vector<mavlink_extended_message_t>& fragments) const
+ {
+ TypeMap::const_iterator it = mTypeMap.find(protobuf_msg.GetTypeName());
+ if (it == mTypeMap.end())
+ {
+ std::cout << "# WARNING: Protobuf message with type "
+ << protobuf_msg.GetTypeName() << " is not registered."
+ << std::endl;
+ return false;
+ }
+
+ uint8_t typecode = it->second;
+
+ std::string data = protobuf_msg.SerializeAsString();
+
+ int fragmentCount = (protobuf_msg.ByteSize() + kExtendedPayloadMaxSize - 1) / kExtendedPayloadMaxSize;
+ unsigned int offset = 0;
+
+ for (int i = 0; i < fragmentCount; ++i)
+ {
+ mavlink_extended_message_t fragment;
+
+ // write extended header data
+ uint8_t* payload = reinterpret_cast<uint8_t*>(fragment.base_msg.payload64);
+ unsigned int length = 0;
+ uint8_t flags = 0;
+
+ if (i < fragmentCount - 1)
+ {
+ length = kExtendedPayloadMaxSize;
+ flags |= 0x1;
+ }
+ else
+ {
+ length = protobuf_msg.ByteSize() - kExtendedPayloadMaxSize * (fragmentCount - 1);
+ }
+
+ memcpy(payload, &target_system, 1);
+ memcpy(payload + 1, &target_component, 1);
+ memcpy(payload + 2, &typecode, 1);
+ memcpy(payload + 3, &length, 4);
+ memcpy(payload + 7, &mStreamID, 2);
+ memcpy(payload + 9, &offset, 4);
+ memcpy(payload + 13, &flags, 1);
+
+ fragment.base_msg.msgid = MAVLINK_MSG_ID_EXTENDED_MESSAGE;
+ mavlink_finalize_message(&fragment.base_msg, system_id, component_id, kExtendedHeaderSize, 0);
+
+ // write extended payload data
+ fragment.extended_payload_len = length;
+ memcpy(fragment.extended_payload, &data[offset], length);
+
+ fragments.push_back(fragment);
+ offset += length;
+ }
+
+ if (mVerbose)
+ {
+ std::cerr << "# INFO: Split extended message with size "
+ << protobuf_msg.ByteSize() << " into "
+ << fragmentCount << " fragments." << std::endl;
+ }
+
+ return true;
+ }
+
+ bool cacheFragment(mavlink_extended_message_t& msg)
+ {
+ if (!validFragment(msg))
+ {
+ if (mVerbose)
+ {
+ std::cerr << "# WARNING: Message is not a valid fragment. "
+ << "Dropping message..." << std::endl;
+ }
+ return false;
+ }
+
+ // read extended header
+ uint8_t* payload = reinterpret_cast<uint8_t*>(msg.base_msg.payload64);
+ uint8_t typecode = 0;
+ unsigned int length = 0;
+ unsigned short streamID = 0;
+ unsigned int offset = 0;
+ uint8_t flags = 0;
+
+ memcpy(&typecode, payload + 2, 1);
+ memcpy(&length, payload + 3, 4);
+ memcpy(&streamID, payload + 7, 2);
+ memcpy(&offset, payload + 9, 4);
+ memcpy(&flags, payload + 13, 1);
+
+ if (typecode >= mTypeMap.size())
+ {
+ std::cout << "# WARNING: Protobuf message with type code "
+ << static_cast<int>(typecode) << " is not registered." << std::endl;
+ return false;
+ }
+
+ bool reassemble = false;
+
+ FragmentQueue::iterator it = mFragmentQueue.find(streamID);
+ if (it == mFragmentQueue.end())
+ {
+ if (offset == 0)
+ {
+ mFragmentQueue[streamID].push_back(msg);
+
+ if ((flags & 0x1) != 0x1)
+ {
+ reassemble = true;
+ }
+
+ if (mVerbose)
+ {
+ std::cerr << "# INFO: Added fragment to new queue."
+ << std::endl;
+ }
+ }
+ else
+ {
+ if (mVerbose)
+ {
+ std::cerr << "# WARNING: Message is not a valid fragment. "
+ << "Dropping message..." << std::endl;
+ }
+ }
+ }
+ else
+ {
+ std::deque<mavlink_extended_message_t>& queue = it->second;
+
+ if (queue.empty())
+ {
+ if (offset == 0)
+ {
+ queue.push_back(msg);
+
+ if ((flags & 0x1) != 0x1)
+ {
+ reassemble = true;
+ }
+ }
+ else
+ {
+ if (mVerbose)
+ {
+ std::cerr << "# WARNING: Message is not a valid fragment. "
+ << "Dropping message..." << std::endl;
+ }
+ }
+ }
+ else
+ {
+ if (fragmentDataSize(queue.back()) + fragmentOffset(queue.back()) != offset)
+ {
+ if (mVerbose)
+ {
+ std::cerr << "# WARNING: Previous fragment(s) have been lost. "
+ << "Dropping message and clearing queue..." << std::endl;
+ }
+ queue.clear();
+ }
+ else
+ {
+ queue.push_back(msg);
+
+ if ((flags & 0x1) != 0x1)
+ {
+ reassemble = true;
+ }
+ }
+ }
+ }
+
+ if (reassemble)
+ {
+ std::deque<mavlink_extended_message_t>& queue = mFragmentQueue[streamID];
+
+ std::string data;
+ for (size_t i = 0; i < queue.size(); ++i)
+ {
+ mavlink_extended_message_t& mavlink_msg = queue.at(i);
+
+ data.append(reinterpret_cast<char*>(&mavlink_msg.extended_payload[0]),
+ static_cast<size_t>(mavlink_msg.extended_payload_len));
+ }
+
+ mMessages.at(typecode)->ParseFromString(data);
+
+ mMessageAvailable.at(typecode) = true;
+
+ queue.clear();
+
+ if (mVerbose)
+ {
+ std::cerr << "# INFO: Reassembled fragments for message with typename "
+ << mMessages.at(typecode)->GetTypeName() << " and size "
+ << mMessages.at(typecode)->ByteSize()
+ << "." << std::endl;
+ }
+ }
+
+ return true;
+ }
+
+ bool getMessage(std::tr1::shared_ptr<google::protobuf::Message>& msg)
+ {
+ for (size_t i = 0; i < mMessageAvailable.size(); ++i)
+ {
+ if (mMessageAvailable.at(i))
+ {
+ msg = mMessages.at(i);
+ mMessageAvailable.at(i) = false;
+
+ return true;
+ }
+ }
+
+ return false;
+ }
+
+private:
+ void registerType(const std::tr1::shared_ptr<google::protobuf::Message>& msg)
+ {
+ mTypeMap[msg->GetTypeName()] = mRegisteredTypeCount;
+ ++mRegisteredTypeCount;
+ mMessages.push_back(msg);
+ mMessageAvailable.push_back(false);
+ }
+
+ bool validFragment(const mavlink_extended_message_t& msg) const
+ {
+ if (msg.base_msg.magic != MAVLINK_STX ||
+ msg.base_msg.len != kExtendedHeaderSize ||
+ msg.base_msg.msgid != MAVLINK_MSG_ID_EXTENDED_MESSAGE)
+ {
+ return false;
+ }
+
+ uint16_t checksum;
+ checksum = crc_calculate(reinterpret_cast<const uint8_t*>(&msg.base_msg.len), MAVLINK_CORE_HEADER_LEN);
+ crc_accumulate_buffer(&checksum, reinterpret_cast<const char*>(&msg.base_msg.payload64), kExtendedHeaderSize);
+#if MAVLINK_CRC_EXTRA
+ static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS;
+ crc_accumulate(mavlink_message_crcs[msg.base_msg.msgid], &checksum);
+#endif
+
+ if (mavlink_ck_a(&(msg.base_msg)) != (uint8_t)(checksum & 0xFF) &&
+ mavlink_ck_b(&(msg.base_msg)) != (uint8_t)(checksum >> 8))
+ {
+ return false;
+ }
+
+ return true;
+ }
+
+ unsigned int fragmentDataSize(const mavlink_extended_message_t& msg) const
+ {
+ const uint8_t* payload = reinterpret_cast<const uint8_t*>(msg.base_msg.payload64);
+
+ return *(reinterpret_cast<const unsigned int*>(payload + 3));
+ }
+
+ unsigned int fragmentOffset(const mavlink_extended_message_t& msg) const
+ {
+ const uint8_t* payload = reinterpret_cast<const uint8_t*>(msg.base_msg.payload64);
+
+ return *(reinterpret_cast<const unsigned int*>(payload + 9));
+ }
+
+ int mRegisteredTypeCount;
+ unsigned short mStreamID;
+ bool mVerbose;
+
+ typedef std::map<std::string, uint8_t> TypeMap;
+ TypeMap mTypeMap;
+ std::vector< std::tr1::shared_ptr<google::protobuf::Message> > mMessages;
+ std::vector<bool> mMessageAvailable;
+
+ typedef std::map<unsigned short, std::deque<mavlink_extended_message_t> > FragmentQueue;
+ FragmentQueue mFragmentQueue;
+
+ const int kExtendedHeaderSize;
+ /**
+ * Extended header structure
+ * =========================
+ * byte 0 - target_system
+ * byte 1 - target_component
+ * byte 2 - extended message id (type code)
+ * bytes 3-6 - extended payload size in bytes
+ * byte 7-8 - stream ID
+ * byte 9-12 - fragment offset
+ * byte 13 - fragment flags (bit 0 - 1=more fragments, 0=last fragment)
+ */
+
+ const int kExtendedPayloadMaxSize;
+};
+
+}
+
+#endif
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_types.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_types.h
new file mode 100644
index 000000000..5fbde97f7
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_types.h
@@ -0,0 +1,158 @@
+#ifndef MAVLINK_TYPES_H_
+#define MAVLINK_TYPES_H_
+
+#include <inttypes.h>
+
+#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
+
+#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255
+#define MAVLINK_EXTENDED_HEADER_LEN 14
+
+#if (defined _MSC_VER) | ((defined __APPLE__) & (defined __MACH__)) | (defined __linux__)
+ /* full fledged 32bit++ OS */
+ #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507
+#else
+ /* small microcontrollers */
+ #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048
+#endif
+
+#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
+
+typedef struct param_union {
+ union {
+ float param_float;
+ int32_t param_int32;
+ uint32_t param_uint32;
+ uint8_t param_uint8;
+ uint8_t bytes[4];
+ };
+ 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 struct __mavlink_extended_message {
+ mavlink_message_t base_msg;
+ int32_t extended_payload_len; ///< Length of extended payload if any
+ uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];
+} mavlink_extended_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 int array_length; // if non-zero, field is an array
+ unsigned int wire_offset; // offset of each field in the payload
+ unsigned int 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) ((const 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_NON_CONST(msg))
+#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(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_v1.0/pixhawk/pixhawk.pb.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/pixhawk/pixhawk.pb.h
new file mode 100644
index 000000000..7556606e9
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/pixhawk/pixhawk.pb.h
@@ -0,0 +1,3663 @@
+// Generated by the protocol buffer compiler. DO NOT EDIT!
+// source: pixhawk.proto
+
+#ifndef PROTOBUF_pixhawk_2eproto__INCLUDED
+#define PROTOBUF_pixhawk_2eproto__INCLUDED
+
+#include <string>
+
+#include <google/protobuf/stubs/common.h>
+
+#if GOOGLE_PROTOBUF_VERSION < 2004000
+#error This file was generated by a newer version of protoc which is
+#error incompatible with your Protocol Buffer headers. Please update
+#error your headers.
+#endif
+#if 2004001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION
+#error This file was generated by an older version of protoc which is
+#error incompatible with your Protocol Buffer headers. Please
+#error regenerate this file with a newer version of protoc.
+#endif
+
+#include <google/protobuf/generated_message_util.h>
+#include <google/protobuf/repeated_field.h>
+#include <google/protobuf/extension_set.h>
+#include <google/protobuf/generated_message_reflection.h>
+// @@protoc_insertion_point(includes)
+
+namespace px {
+
+// Internal implementation detail -- do not call these.
+void protobuf_AddDesc_pixhawk_2eproto();
+void protobuf_AssignDesc_pixhawk_2eproto();
+void protobuf_ShutdownFile_pixhawk_2eproto();
+
+class HeaderInfo;
+class GLOverlay;
+class Obstacle;
+class ObstacleList;
+class ObstacleMap;
+class Path;
+class PointCloudXYZI;
+class PointCloudXYZI_PointXYZI;
+class PointCloudXYZRGB;
+class PointCloudXYZRGB_PointXYZRGB;
+class RGBDImage;
+class Waypoint;
+
+enum GLOverlay_CoordinateFrameType {
+ GLOverlay_CoordinateFrameType_GLOBAL = 0,
+ GLOverlay_CoordinateFrameType_LOCAL = 1
+};
+bool GLOverlay_CoordinateFrameType_IsValid(int value);
+const GLOverlay_CoordinateFrameType GLOverlay_CoordinateFrameType_CoordinateFrameType_MIN = GLOverlay_CoordinateFrameType_GLOBAL;
+const GLOverlay_CoordinateFrameType GLOverlay_CoordinateFrameType_CoordinateFrameType_MAX = GLOverlay_CoordinateFrameType_LOCAL;
+const int GLOverlay_CoordinateFrameType_CoordinateFrameType_ARRAYSIZE = GLOverlay_CoordinateFrameType_CoordinateFrameType_MAX + 1;
+
+const ::google::protobuf::EnumDescriptor* GLOverlay_CoordinateFrameType_descriptor();
+inline const ::std::string& GLOverlay_CoordinateFrameType_Name(GLOverlay_CoordinateFrameType value) {
+ return ::google::protobuf::internal::NameOfEnum(
+ GLOverlay_CoordinateFrameType_descriptor(), value);
+}
+inline bool GLOverlay_CoordinateFrameType_Parse(
+ const ::std::string& name, GLOverlay_CoordinateFrameType* value) {
+ return ::google::protobuf::internal::ParseNamedEnum<GLOverlay_CoordinateFrameType>(
+ GLOverlay_CoordinateFrameType_descriptor(), name, value);
+}
+enum GLOverlay_Mode {
+ GLOverlay_Mode_POINTS = 0,
+ GLOverlay_Mode_LINES = 1,
+ GLOverlay_Mode_LINE_STRIP = 2,
+ GLOverlay_Mode_LINE_LOOP = 3,
+ GLOverlay_Mode_TRIANGLES = 4,
+ GLOverlay_Mode_TRIANGLE_STRIP = 5,
+ GLOverlay_Mode_TRIANGLE_FAN = 6,
+ GLOverlay_Mode_QUADS = 7,
+ GLOverlay_Mode_QUAD_STRIP = 8,
+ GLOverlay_Mode_POLYGON = 9,
+ GLOverlay_Mode_SOLID_CIRCLE = 10,
+ GLOverlay_Mode_WIRE_CIRCLE = 11,
+ GLOverlay_Mode_SOLID_CUBE = 12,
+ GLOverlay_Mode_WIRE_CUBE = 13
+};
+bool GLOverlay_Mode_IsValid(int value);
+const GLOverlay_Mode GLOverlay_Mode_Mode_MIN = GLOverlay_Mode_POINTS;
+const GLOverlay_Mode GLOverlay_Mode_Mode_MAX = GLOverlay_Mode_WIRE_CUBE;
+const int GLOverlay_Mode_Mode_ARRAYSIZE = GLOverlay_Mode_Mode_MAX + 1;
+
+const ::google::protobuf::EnumDescriptor* GLOverlay_Mode_descriptor();
+inline const ::std::string& GLOverlay_Mode_Name(GLOverlay_Mode value) {
+ return ::google::protobuf::internal::NameOfEnum(
+ GLOverlay_Mode_descriptor(), value);
+}
+inline bool GLOverlay_Mode_Parse(
+ const ::std::string& name, GLOverlay_Mode* value) {
+ return ::google::protobuf::internal::ParseNamedEnum<GLOverlay_Mode>(
+ GLOverlay_Mode_descriptor(), name, value);
+}
+enum GLOverlay_Identifier {
+ GLOverlay_Identifier_END = 14,
+ GLOverlay_Identifier_VERTEX2F = 15,
+ GLOverlay_Identifier_VERTEX3F = 16,
+ GLOverlay_Identifier_ROTATEF = 17,
+ GLOverlay_Identifier_TRANSLATEF = 18,
+ GLOverlay_Identifier_SCALEF = 19,
+ GLOverlay_Identifier_PUSH_MATRIX = 20,
+ GLOverlay_Identifier_POP_MATRIX = 21,
+ GLOverlay_Identifier_COLOR3F = 22,
+ GLOverlay_Identifier_COLOR4F = 23,
+ GLOverlay_Identifier_POINTSIZE = 24,
+ GLOverlay_Identifier_LINEWIDTH = 25
+};
+bool GLOverlay_Identifier_IsValid(int value);
+const GLOverlay_Identifier GLOverlay_Identifier_Identifier_MIN = GLOverlay_Identifier_END;
+const GLOverlay_Identifier GLOverlay_Identifier_Identifier_MAX = GLOverlay_Identifier_LINEWIDTH;
+const int GLOverlay_Identifier_Identifier_ARRAYSIZE = GLOverlay_Identifier_Identifier_MAX + 1;
+
+const ::google::protobuf::EnumDescriptor* GLOverlay_Identifier_descriptor();
+inline const ::std::string& GLOverlay_Identifier_Name(GLOverlay_Identifier value) {
+ return ::google::protobuf::internal::NameOfEnum(
+ GLOverlay_Identifier_descriptor(), value);
+}
+inline bool GLOverlay_Identifier_Parse(
+ const ::std::string& name, GLOverlay_Identifier* value) {
+ return ::google::protobuf::internal::ParseNamedEnum<GLOverlay_Identifier>(
+ GLOverlay_Identifier_descriptor(), name, value);
+}
+// ===================================================================
+
+class HeaderInfo : public ::google::protobuf::Message {
+ public:
+ HeaderInfo();
+ virtual ~HeaderInfo();
+
+ HeaderInfo(const HeaderInfo& from);
+
+ inline HeaderInfo& operator=(const HeaderInfo& from) {
+ CopyFrom(from);
+ return *this;
+ }
+
+ inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
+ return _unknown_fields_;
+ }
+
+ inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
+ return &_unknown_fields_;
+ }
+
+ static const ::google::protobuf::Descriptor* descriptor();
+ static const HeaderInfo& default_instance();
+
+ void Swap(HeaderInfo* other);
+
+ // implements Message ----------------------------------------------
+
+ HeaderInfo* New() const;
+ void CopyFrom(const ::google::protobuf::Message& from);
+ void MergeFrom(const ::google::protobuf::Message& from);
+ void CopyFrom(const HeaderInfo& from);
+ void MergeFrom(const HeaderInfo& from);
+ void Clear();
+ bool IsInitialized() const;
+
+ int ByteSize() const;
+ bool MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input);
+ void SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const;
+ ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
+ int GetCachedSize() const { return _cached_size_; }
+ private:
+ void SharedCtor();
+ void SharedDtor();
+ void SetCachedSize(int size) const;
+ public:
+
+ ::google::protobuf::Metadata GetMetadata() const;
+
+ // nested types ----------------------------------------------------
+
+ // accessors -------------------------------------------------------
+
+ // required int32 source_sysid = 1;
+ inline bool has_source_sysid() const;
+ inline void clear_source_sysid();
+ static const int kSourceSysidFieldNumber = 1;
+ inline ::google::protobuf::int32 source_sysid() const;
+ inline void set_source_sysid(::google::protobuf::int32 value);
+
+ // required int32 source_compid = 2;
+ inline bool has_source_compid() const;
+ inline void clear_source_compid();
+ static const int kSourceCompidFieldNumber = 2;
+ inline ::google::protobuf::int32 source_compid() const;
+ inline void set_source_compid(::google::protobuf::int32 value);
+
+ // required double timestamp = 3;
+ inline bool has_timestamp() const;
+ inline void clear_timestamp();
+ static const int kTimestampFieldNumber = 3;
+ inline double timestamp() const;
+ inline void set_timestamp(double value);
+
+ // @@protoc_insertion_point(class_scope:px.HeaderInfo)
+ private:
+ inline void set_has_source_sysid();
+ inline void clear_has_source_sysid();
+ inline void set_has_source_compid();
+ inline void clear_has_source_compid();
+ inline void set_has_timestamp();
+ inline void clear_has_timestamp();
+
+ ::google::protobuf::UnknownFieldSet _unknown_fields_;
+
+ ::google::protobuf::int32 source_sysid_;
+ ::google::protobuf::int32 source_compid_;
+ double timestamp_;
+
+ mutable int _cached_size_;
+ ::google::protobuf::uint32 _has_bits_[(3 + 31) / 32];
+
+ friend void protobuf_AddDesc_pixhawk_2eproto();
+ friend void protobuf_AssignDesc_pixhawk_2eproto();
+ friend void protobuf_ShutdownFile_pixhawk_2eproto();
+
+ void InitAsDefaultInstance();
+ static HeaderInfo* default_instance_;
+};
+// -------------------------------------------------------------------
+
+class GLOverlay : public ::google::protobuf::Message {
+ public:
+ GLOverlay();
+ virtual ~GLOverlay();
+
+ GLOverlay(const GLOverlay& from);
+
+ inline GLOverlay& operator=(const GLOverlay& from) {
+ CopyFrom(from);
+ return *this;
+ }
+
+ inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
+ return _unknown_fields_;
+ }
+
+ inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
+ return &_unknown_fields_;
+ }
+
+ static const ::google::protobuf::Descriptor* descriptor();
+ static const GLOverlay& default_instance();
+
+ void Swap(GLOverlay* other);
+
+ // implements Message ----------------------------------------------
+
+ GLOverlay* New() const;
+ void CopyFrom(const ::google::protobuf::Message& from);
+ void MergeFrom(const ::google::protobuf::Message& from);
+ void CopyFrom(const GLOverlay& from);
+ void MergeFrom(const GLOverlay& from);
+ void Clear();
+ bool IsInitialized() const;
+
+ int ByteSize() const;
+ bool MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input);
+ void SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const;
+ ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
+ int GetCachedSize() const { return _cached_size_; }
+ private:
+ void SharedCtor();
+ void SharedDtor();
+ void SetCachedSize(int size) const;
+ public:
+
+ ::google::protobuf::Metadata GetMetadata() const;
+
+ // nested types ----------------------------------------------------
+
+ typedef GLOverlay_CoordinateFrameType CoordinateFrameType;
+ static const CoordinateFrameType GLOBAL = GLOverlay_CoordinateFrameType_GLOBAL;
+ static const CoordinateFrameType LOCAL = GLOverlay_CoordinateFrameType_LOCAL;
+ static inline bool CoordinateFrameType_IsValid(int value) {
+ return GLOverlay_CoordinateFrameType_IsValid(value);
+ }
+ static const CoordinateFrameType CoordinateFrameType_MIN =
+ GLOverlay_CoordinateFrameType_CoordinateFrameType_MIN;
+ static const CoordinateFrameType CoordinateFrameType_MAX =
+ GLOverlay_CoordinateFrameType_CoordinateFrameType_MAX;
+ static const int CoordinateFrameType_ARRAYSIZE =
+ GLOverlay_CoordinateFrameType_CoordinateFrameType_ARRAYSIZE;
+ static inline const ::google::protobuf::EnumDescriptor*
+ CoordinateFrameType_descriptor() {
+ return GLOverlay_CoordinateFrameType_descriptor();
+ }
+ static inline const ::std::string& CoordinateFrameType_Name(CoordinateFrameType value) {
+ return GLOverlay_CoordinateFrameType_Name(value);
+ }
+ static inline bool CoordinateFrameType_Parse(const ::std::string& name,
+ CoordinateFrameType* value) {
+ return GLOverlay_CoordinateFrameType_Parse(name, value);
+ }
+
+ typedef GLOverlay_Mode Mode;
+ static const Mode POINTS = GLOverlay_Mode_POINTS;
+ static const Mode LINES = GLOverlay_Mode_LINES;
+ static const Mode LINE_STRIP = GLOverlay_Mode_LINE_STRIP;
+ static const Mode LINE_LOOP = GLOverlay_Mode_LINE_LOOP;
+ static const Mode TRIANGLES = GLOverlay_Mode_TRIANGLES;
+ static const Mode TRIANGLE_STRIP = GLOverlay_Mode_TRIANGLE_STRIP;
+ static const Mode TRIANGLE_FAN = GLOverlay_Mode_TRIANGLE_FAN;
+ static const Mode QUADS = GLOverlay_Mode_QUADS;
+ static const Mode QUAD_STRIP = GLOverlay_Mode_QUAD_STRIP;
+ static const Mode POLYGON = GLOverlay_Mode_POLYGON;
+ static const Mode SOLID_CIRCLE = GLOverlay_Mode_SOLID_CIRCLE;
+ static const Mode WIRE_CIRCLE = GLOverlay_Mode_WIRE_CIRCLE;
+ static const Mode SOLID_CUBE = GLOverlay_Mode_SOLID_CUBE;
+ static const Mode WIRE_CUBE = GLOverlay_Mode_WIRE_CUBE;
+ static inline bool Mode_IsValid(int value) {
+ return GLOverlay_Mode_IsValid(value);
+ }
+ static const Mode Mode_MIN =
+ GLOverlay_Mode_Mode_MIN;
+ static const Mode Mode_MAX =
+ GLOverlay_Mode_Mode_MAX;
+ static const int Mode_ARRAYSIZE =
+ GLOverlay_Mode_Mode_ARRAYSIZE;
+ static inline const ::google::protobuf::EnumDescriptor*
+ Mode_descriptor() {
+ return GLOverlay_Mode_descriptor();
+ }
+ static inline const ::std::string& Mode_Name(Mode value) {
+ return GLOverlay_Mode_Name(value);
+ }
+ static inline bool Mode_Parse(const ::std::string& name,
+ Mode* value) {
+ return GLOverlay_Mode_Parse(name, value);
+ }
+
+ typedef GLOverlay_Identifier Identifier;
+ static const Identifier END = GLOverlay_Identifier_END;
+ static const Identifier VERTEX2F = GLOverlay_Identifier_VERTEX2F;
+ static const Identifier VERTEX3F = GLOverlay_Identifier_VERTEX3F;
+ static const Identifier ROTATEF = GLOverlay_Identifier_ROTATEF;
+ static const Identifier TRANSLATEF = GLOverlay_Identifier_TRANSLATEF;
+ static const Identifier SCALEF = GLOverlay_Identifier_SCALEF;
+ static const Identifier PUSH_MATRIX = GLOverlay_Identifier_PUSH_MATRIX;
+ static const Identifier POP_MATRIX = GLOverlay_Identifier_POP_MATRIX;
+ static const Identifier COLOR3F = GLOverlay_Identifier_COLOR3F;
+ static const Identifier COLOR4F = GLOverlay_Identifier_COLOR4F;
+ static const Identifier POINTSIZE = GLOverlay_Identifier_POINTSIZE;
+ static const Identifier LINEWIDTH = GLOverlay_Identifier_LINEWIDTH;
+ static inline bool Identifier_IsValid(int value) {
+ return GLOverlay_Identifier_IsValid(value);
+ }
+ static const Identifier Identifier_MIN =
+ GLOverlay_Identifier_Identifier_MIN;
+ static const Identifier Identifier_MAX =
+ GLOverlay_Identifier_Identifier_MAX;
+ static const int Identifier_ARRAYSIZE =
+ GLOverlay_Identifier_Identifier_ARRAYSIZE;
+ static inline const ::google::protobuf::EnumDescriptor*
+ Identifier_descriptor() {
+ return GLOverlay_Identifier_descriptor();
+ }
+ static inline const ::std::string& Identifier_Name(Identifier value) {
+ return GLOverlay_Identifier_Name(value);
+ }
+ static inline bool Identifier_Parse(const ::std::string& name,
+ Identifier* value) {
+ return GLOverlay_Identifier_Parse(name, value);
+ }
+
+ // accessors -------------------------------------------------------
+
+ // required .px.HeaderInfo header = 1;
+ inline bool has_header() const;
+ inline void clear_header();
+ static const int kHeaderFieldNumber = 1;
+ inline const ::px::HeaderInfo& header() const;
+ inline ::px::HeaderInfo* mutable_header();
+ inline ::px::HeaderInfo* release_header();
+
+ // optional string name = 2;
+ inline bool has_name() const;
+ inline void clear_name();
+ static const int kNameFieldNumber = 2;
+ inline const ::std::string& name() const;
+ inline void set_name(const ::std::string& value);
+ inline void set_name(const char* value);
+ inline void set_name(const char* value, size_t size);
+ inline ::std::string* mutable_name();
+ inline ::std::string* release_name();
+
+ // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3;
+ inline bool has_coordinateframetype() const;
+ inline void clear_coordinateframetype();
+ static const int kCoordinateFrameTypeFieldNumber = 3;
+ inline ::px::GLOverlay_CoordinateFrameType coordinateframetype() const;
+ inline void set_coordinateframetype(::px::GLOverlay_CoordinateFrameType value);
+
+ // optional double origin_x = 4;
+ inline bool has_origin_x() const;
+ inline void clear_origin_x();
+ static const int kOriginXFieldNumber = 4;
+ inline double origin_x() const;
+ inline void set_origin_x(double value);
+
+ // optional double origin_y = 5;
+ inline bool has_origin_y() const;
+ inline void clear_origin_y();
+ static const int kOriginYFieldNumber = 5;
+ inline double origin_y() const;
+ inline void set_origin_y(double value);
+
+ // optional double origin_z = 6;
+ inline bool has_origin_z() const;
+ inline void clear_origin_z();
+ static const int kOriginZFieldNumber = 6;
+ inline double origin_z() const;
+ inline void set_origin_z(double value);
+
+ // optional bytes data = 7;
+ inline bool has_data() const;
+ inline void clear_data();
+ static const int kDataFieldNumber = 7;
+ inline const ::std::string& data() const;
+ inline void set_data(const ::std::string& value);
+ inline void set_data(const char* value);
+ inline void set_data(const void* value, size_t size);
+ inline ::std::string* mutable_data();
+ inline ::std::string* release_data();
+
+ // @@protoc_insertion_point(class_scope:px.GLOverlay)
+ private:
+ inline void set_has_header();
+ inline void clear_has_header();
+ inline void set_has_name();
+ inline void clear_has_name();
+ inline void set_has_coordinateframetype();
+ inline void clear_has_coordinateframetype();
+ inline void set_has_origin_x();
+ inline void clear_has_origin_x();
+ inline void set_has_origin_y();
+ inline void clear_has_origin_y();
+ inline void set_has_origin_z();
+ inline void clear_has_origin_z();
+ inline void set_has_data();
+ inline void clear_has_data();
+
+ ::google::protobuf::UnknownFieldSet _unknown_fields_;
+
+ ::px::HeaderInfo* header_;
+ ::std::string* name_;
+ double origin_x_;
+ double origin_y_;
+ double origin_z_;
+ ::std::string* data_;
+ int coordinateframetype_;
+
+ mutable int _cached_size_;
+ ::google::protobuf::uint32 _has_bits_[(7 + 31) / 32];
+
+ friend void protobuf_AddDesc_pixhawk_2eproto();
+ friend void protobuf_AssignDesc_pixhawk_2eproto();
+ friend void protobuf_ShutdownFile_pixhawk_2eproto();
+
+ void InitAsDefaultInstance();
+ static GLOverlay* default_instance_;
+};
+// -------------------------------------------------------------------
+
+class Obstacle : public ::google::protobuf::Message {
+ public:
+ Obstacle();
+ virtual ~Obstacle();
+
+ Obstacle(const Obstacle& from);
+
+ inline Obstacle& operator=(const Obstacle& from) {
+ CopyFrom(from);
+ return *this;
+ }
+
+ inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
+ return _unknown_fields_;
+ }
+
+ inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
+ return &_unknown_fields_;
+ }
+
+ static const ::google::protobuf::Descriptor* descriptor();
+ static const Obstacle& default_instance();
+
+ void Swap(Obstacle* other);
+
+ // implements Message ----------------------------------------------
+
+ Obstacle* New() const;
+ void CopyFrom(const ::google::protobuf::Message& from);
+ void MergeFrom(const ::google::protobuf::Message& from);
+ void CopyFrom(const Obstacle& from);
+ void MergeFrom(const Obstacle& from);
+ void Clear();
+ bool IsInitialized() const;
+
+ int ByteSize() const;
+ bool MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input);
+ void SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const;
+ ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
+ int GetCachedSize() const { return _cached_size_; }
+ private:
+ void SharedCtor();
+ void SharedDtor();
+ void SetCachedSize(int size) const;
+ public:
+
+ ::google::protobuf::Metadata GetMetadata() const;
+
+ // nested types ----------------------------------------------------
+
+ // accessors -------------------------------------------------------
+
+ // optional float x = 1;
+ inline bool has_x() const;
+ inline void clear_x();
+ static const int kXFieldNumber = 1;
+ inline float x() const;
+ inline void set_x(float value);
+
+ // optional float y = 2;
+ inline bool has_y() const;
+ inline void clear_y();
+ static const int kYFieldNumber = 2;
+ inline float y() const;
+ inline void set_y(float value);
+
+ // optional float z = 3;
+ inline bool has_z() const;
+ inline void clear_z();
+ static const int kZFieldNumber = 3;
+ inline float z() const;
+ inline void set_z(float value);
+
+ // optional float length = 4;
+ inline bool has_length() const;
+ inline void clear_length();
+ static const int kLengthFieldNumber = 4;
+ inline float length() const;
+ inline void set_length(float value);
+
+ // optional float width = 5;
+ inline bool has_width() const;
+ inline void clear_width();
+ static const int kWidthFieldNumber = 5;
+ inline float width() const;
+ inline void set_width(float value);
+
+ // optional float height = 6;
+ inline bool has_height() const;
+ inline void clear_height();
+ static const int kHeightFieldNumber = 6;
+ inline float height() const;
+ inline void set_height(float value);
+
+ // @@protoc_insertion_point(class_scope:px.Obstacle)
+ private:
+ inline void set_has_x();
+ inline void clear_has_x();
+ inline void set_has_y();
+ inline void clear_has_y();
+ inline void set_has_z();
+ inline void clear_has_z();
+ inline void set_has_length();
+ inline void clear_has_length();
+ inline void set_has_width();
+ inline void clear_has_width();
+ inline void set_has_height();
+ inline void clear_has_height();
+
+ ::google::protobuf::UnknownFieldSet _unknown_fields_;
+
+ float x_;
+ float y_;
+ float z_;
+ float length_;
+ float width_;
+ float height_;
+
+ mutable int _cached_size_;
+ ::google::protobuf::uint32 _has_bits_[(6 + 31) / 32];
+
+ friend void protobuf_AddDesc_pixhawk_2eproto();
+ friend void protobuf_AssignDesc_pixhawk_2eproto();
+ friend void protobuf_ShutdownFile_pixhawk_2eproto();
+
+ void InitAsDefaultInstance();
+ static Obstacle* default_instance_;
+};
+// -------------------------------------------------------------------
+
+class ObstacleList : public ::google::protobuf::Message {
+ public:
+ ObstacleList();
+ virtual ~ObstacleList();
+
+ ObstacleList(const ObstacleList& from);
+
+ inline ObstacleList& operator=(const ObstacleList& from) {
+ CopyFrom(from);
+ return *this;
+ }
+
+ inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
+ return _unknown_fields_;
+ }
+
+ inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
+ return &_unknown_fields_;
+ }
+
+ static const ::google::protobuf::Descriptor* descriptor();
+ static const ObstacleList& default_instance();
+
+ void Swap(ObstacleList* other);
+
+ // implements Message ----------------------------------------------
+
+ ObstacleList* New() const;
+ void CopyFrom(const ::google::protobuf::Message& from);
+ void MergeFrom(const ::google::protobuf::Message& from);
+ void CopyFrom(const ObstacleList& from);
+ void MergeFrom(const ObstacleList& from);
+ void Clear();
+ bool IsInitialized() const;
+
+ int ByteSize() const;
+ bool MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input);
+ void SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const;
+ ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
+ int GetCachedSize() const { return _cached_size_; }
+ private:
+ void SharedCtor();
+ void SharedDtor();
+ void SetCachedSize(int size) const;
+ public:
+
+ ::google::protobuf::Metadata GetMetadata() const;
+
+ // nested types ----------------------------------------------------
+
+ // accessors -------------------------------------------------------
+
+ // required .px.HeaderInfo header = 1;
+ inline bool has_header() const;
+ inline void clear_header();
+ static const int kHeaderFieldNumber = 1;
+ inline const ::px::HeaderInfo& header() const;
+ inline ::px::HeaderInfo* mutable_header();
+ inline ::px::HeaderInfo* release_header();
+
+ // repeated .px.Obstacle obstacles = 2;
+ inline int obstacles_size() const;
+ inline void clear_obstacles();
+ static const int kObstaclesFieldNumber = 2;
+ inline const ::px::Obstacle& obstacles(int index) const;
+ inline ::px::Obstacle* mutable_obstacles(int index);
+ inline ::px::Obstacle* add_obstacles();
+ inline const ::google::protobuf::RepeatedPtrField< ::px::Obstacle >&
+ obstacles() const;
+ inline ::google::protobuf::RepeatedPtrField< ::px::Obstacle >*
+ mutable_obstacles();
+
+ // @@protoc_insertion_point(class_scope:px.ObstacleList)
+ private:
+ inline void set_has_header();
+ inline void clear_has_header();
+
+ ::google::protobuf::UnknownFieldSet _unknown_fields_;
+
+ ::px::HeaderInfo* header_;
+ ::google::protobuf::RepeatedPtrField< ::px::Obstacle > obstacles_;
+
+ mutable int _cached_size_;
+ ::google::protobuf::uint32 _has_bits_[(2 + 31) / 32];
+
+ friend void protobuf_AddDesc_pixhawk_2eproto();
+ friend void protobuf_AssignDesc_pixhawk_2eproto();
+ friend void protobuf_ShutdownFile_pixhawk_2eproto();
+
+ void InitAsDefaultInstance();
+ static ObstacleList* default_instance_;
+};
+// -------------------------------------------------------------------
+
+class ObstacleMap : public ::google::protobuf::Message {
+ public:
+ ObstacleMap();
+ virtual ~ObstacleMap();
+
+ ObstacleMap(const ObstacleMap& from);
+
+ inline ObstacleMap& operator=(const ObstacleMap& from) {
+ CopyFrom(from);
+ return *this;
+ }
+
+ inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
+ return _unknown_fields_;
+ }
+
+ inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
+ return &_unknown_fields_;
+ }
+
+ static const ::google::protobuf::Descriptor* descriptor();
+ static const ObstacleMap& default_instance();
+
+ void Swap(ObstacleMap* other);
+
+ // implements Message ----------------------------------------------
+
+ ObstacleMap* New() const;
+ void CopyFrom(const ::google::protobuf::Message& from);
+ void MergeFrom(const ::google::protobuf::Message& from);
+ void CopyFrom(const ObstacleMap& from);
+ void MergeFrom(const ObstacleMap& from);
+ void Clear();
+ bool IsInitialized() const;
+
+ int ByteSize() const;
+ bool MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input);
+ void SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const;
+ ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
+ int GetCachedSize() const { return _cached_size_; }
+ private:
+ void SharedCtor();
+ void SharedDtor();
+ void SetCachedSize(int size) const;
+ public:
+
+ ::google::protobuf::Metadata GetMetadata() const;
+
+ // nested types ----------------------------------------------------
+
+ // accessors -------------------------------------------------------
+
+ // required .px.HeaderInfo header = 1;
+ inline bool has_header() const;
+ inline void clear_header();
+ static const int kHeaderFieldNumber = 1;
+ inline const ::px::HeaderInfo& header() const;
+ inline ::px::HeaderInfo* mutable_header();
+ inline ::px::HeaderInfo* release_header();
+
+ // required int32 type = 2;
+ inline bool has_type() const;
+ inline void clear_type();
+ static const int kTypeFieldNumber = 2;
+ inline ::google::protobuf::int32 type() const;
+ inline void set_type(::google::protobuf::int32 value);
+
+ // optional float resolution = 3;
+ inline bool has_resolution() const;
+ inline void clear_resolution();
+ static const int kResolutionFieldNumber = 3;
+ inline float resolution() const;
+ inline void set_resolution(float value);
+
+ // optional int32 rows = 4;
+ inline bool has_rows() const;
+ inline void clear_rows();
+ static const int kRowsFieldNumber = 4;
+ inline ::google::protobuf::int32 rows() const;
+ inline void set_rows(::google::protobuf::int32 value);
+
+ // optional int32 cols = 5;
+ inline bool has_cols() const;
+ inline void clear_cols();
+ static const int kColsFieldNumber = 5;
+ inline ::google::protobuf::int32 cols() const;
+ inline void set_cols(::google::protobuf::int32 value);
+
+ // optional int32 mapR0 = 6;
+ inline bool has_mapr0() const;
+ inline void clear_mapr0();
+ static const int kMapR0FieldNumber = 6;
+ inline ::google::protobuf::int32 mapr0() const;
+ inline void set_mapr0(::google::protobuf::int32 value);
+
+ // optional int32 mapC0 = 7;
+ inline bool has_mapc0() const;
+ inline void clear_mapc0();
+ static const int kMapC0FieldNumber = 7;
+ inline ::google::protobuf::int32 mapc0() const;
+ inline void set_mapc0(::google::protobuf::int32 value);
+
+ // optional int32 arrayR0 = 8;
+ inline bool has_arrayr0() const;
+ inline void clear_arrayr0();
+ static const int kArrayR0FieldNumber = 8;
+ inline ::google::protobuf::int32 arrayr0() const;
+ inline void set_arrayr0(::google::protobuf::int32 value);
+
+ // optional int32 arrayC0 = 9;
+ inline bool has_arrayc0() const;
+ inline void clear_arrayc0();
+ static const int kArrayC0FieldNumber = 9;
+ inline ::google::protobuf::int32 arrayc0() const;
+ inline void set_arrayc0(::google::protobuf::int32 value);
+
+ // optional bytes data = 10;
+ inline bool has_data() const;
+ inline void clear_data();
+ static const int kDataFieldNumber = 10;
+ inline const ::std::string& data() const;
+ inline void set_data(const ::std::string& value);
+ inline void set_data(const char* value);
+ inline void set_data(const void* value, size_t size);
+ inline ::std::string* mutable_data();
+ inline ::std::string* release_data();
+
+ // @@protoc_insertion_point(class_scope:px.ObstacleMap)
+ private:
+ inline void set_has_header();
+ inline void clear_has_header();
+ inline void set_has_type();
+ inline void clear_has_type();
+ inline void set_has_resolution();
+ inline void clear_has_resolution();
+ inline void set_has_rows();
+ inline void clear_has_rows();
+ inline void set_has_cols();
+ inline void clear_has_cols();
+ inline void set_has_mapr0();
+ inline void clear_has_mapr0();
+ inline void set_has_mapc0();
+ inline void clear_has_mapc0();
+ inline void set_has_arrayr0();
+ inline void clear_has_arrayr0();
+ inline void set_has_arrayc0();
+ inline void clear_has_arrayc0();
+ inline void set_has_data();
+ inline void clear_has_data();
+
+ ::google::protobuf::UnknownFieldSet _unknown_fields_;
+
+ ::px::HeaderInfo* header_;
+ ::google::protobuf::int32 type_;
+ float resolution_;
+ ::google::protobuf::int32 rows_;
+ ::google::protobuf::int32 cols_;
+ ::google::protobuf::int32 mapr0_;
+ ::google::protobuf::int32 mapc0_;
+ ::google::protobuf::int32 arrayr0_;
+ ::google::protobuf::int32 arrayc0_;
+ ::std::string* data_;
+
+ mutable int _cached_size_;
+ ::google::protobuf::uint32 _has_bits_[(10 + 31) / 32];
+
+ friend void protobuf_AddDesc_pixhawk_2eproto();
+ friend void protobuf_AssignDesc_pixhawk_2eproto();
+ friend void protobuf_ShutdownFile_pixhawk_2eproto();
+
+ void InitAsDefaultInstance();
+ static ObstacleMap* default_instance_;
+};
+// -------------------------------------------------------------------
+
+class Path : public ::google::protobuf::Message {
+ public:
+ Path();
+ virtual ~Path();
+
+ Path(const Path& from);
+
+ inline Path& operator=(const Path& from) {
+ CopyFrom(from);
+ return *this;
+ }
+
+ inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
+ return _unknown_fields_;
+ }
+
+ inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
+ return &_unknown_fields_;
+ }
+
+ static const ::google::protobuf::Descriptor* descriptor();
+ static const Path& default_instance();
+
+ void Swap(Path* other);
+
+ // implements Message ----------------------------------------------
+
+ Path* New() const;
+ void CopyFrom(const ::google::protobuf::Message& from);
+ void MergeFrom(const ::google::protobuf::Message& from);
+ void CopyFrom(const Path& from);
+ void MergeFrom(const Path& from);
+ void Clear();
+ bool IsInitialized() const;
+
+ int ByteSize() const;
+ bool MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input);
+ void SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const;
+ ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
+ int GetCachedSize() const { return _cached_size_; }
+ private:
+ void SharedCtor();
+ void SharedDtor();
+ void SetCachedSize(int size) const;
+ public:
+
+ ::google::protobuf::Metadata GetMetadata() const;
+
+ // nested types ----------------------------------------------------
+
+ // accessors -------------------------------------------------------
+
+ // required .px.HeaderInfo header = 1;
+ inline bool has_header() const;
+ inline void clear_header();
+ static const int kHeaderFieldNumber = 1;
+ inline const ::px::HeaderInfo& header() const;
+ inline ::px::HeaderInfo* mutable_header();
+ inline ::px::HeaderInfo* release_header();
+
+ // repeated .px.Waypoint waypoints = 2;
+ inline int waypoints_size() const;
+ inline void clear_waypoints();
+ static const int kWaypointsFieldNumber = 2;
+ inline const ::px::Waypoint& waypoints(int index) const;
+ inline ::px::Waypoint* mutable_waypoints(int index);
+ inline ::px::Waypoint* add_waypoints();
+ inline const ::google::protobuf::RepeatedPtrField< ::px::Waypoint >&
+ waypoints() const;
+ inline ::google::protobuf::RepeatedPtrField< ::px::Waypoint >*
+ mutable_waypoints();
+
+ // @@protoc_insertion_point(class_scope:px.Path)
+ private:
+ inline void set_has_header();
+ inline void clear_has_header();
+
+ ::google::protobuf::UnknownFieldSet _unknown_fields_;
+
+ ::px::HeaderInfo* header_;
+ ::google::protobuf::RepeatedPtrField< ::px::Waypoint > waypoints_;
+
+ mutable int _cached_size_;
+ ::google::protobuf::uint32 _has_bits_[(2 + 31) / 32];
+
+ friend void protobuf_AddDesc_pixhawk_2eproto();
+ friend void protobuf_AssignDesc_pixhawk_2eproto();
+ friend void protobuf_ShutdownFile_pixhawk_2eproto();
+
+ void InitAsDefaultInstance();
+ static Path* default_instance_;
+};
+// -------------------------------------------------------------------
+
+class PointCloudXYZI_PointXYZI : public ::google::protobuf::Message {
+ public:
+ PointCloudXYZI_PointXYZI();
+ virtual ~PointCloudXYZI_PointXYZI();
+
+ PointCloudXYZI_PointXYZI(const PointCloudXYZI_PointXYZI& from);
+
+ inline PointCloudXYZI_PointXYZI& operator=(const PointCloudXYZI_PointXYZI& from) {
+ CopyFrom(from);
+ return *this;
+ }
+
+ inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
+ return _unknown_fields_;
+ }
+
+ inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
+ return &_unknown_fields_;
+ }
+
+ static const ::google::protobuf::Descriptor* descriptor();
+ static const PointCloudXYZI_PointXYZI& default_instance();
+
+ void Swap(PointCloudXYZI_PointXYZI* other);
+
+ // implements Message ----------------------------------------------
+
+ PointCloudXYZI_PointXYZI* New() const;
+ void CopyFrom(const ::google::protobuf::Message& from);
+ void MergeFrom(const ::google::protobuf::Message& from);
+ void CopyFrom(const PointCloudXYZI_PointXYZI& from);
+ void MergeFrom(const PointCloudXYZI_PointXYZI& from);
+ void Clear();
+ bool IsInitialized() const;
+
+ int ByteSize() const;
+ bool MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input);
+ void SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const;
+ ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
+ int GetCachedSize() const { return _cached_size_; }
+ private:
+ void SharedCtor();
+ void SharedDtor();
+ void SetCachedSize(int size) const;
+ public:
+
+ ::google::protobuf::Metadata GetMetadata() const;
+
+ // nested types ----------------------------------------------------
+
+ // accessors -------------------------------------------------------
+
+ // required float x = 1;
+ inline bool has_x() const;
+ inline void clear_x();
+ static const int kXFieldNumber = 1;
+ inline float x() const;
+ inline void set_x(float value);
+
+ // required float y = 2;
+ inline bool has_y() const;
+ inline void clear_y();
+ static const int kYFieldNumber = 2;
+ inline float y() const;
+ inline void set_y(float value);
+
+ // required float z = 3;
+ inline bool has_z() const;
+ inline void clear_z();
+ static const int kZFieldNumber = 3;
+ inline float z() const;
+ inline void set_z(float value);
+
+ // required float intensity = 4;
+ inline bool has_intensity() const;
+ inline void clear_intensity();
+ static const int kIntensityFieldNumber = 4;
+ inline float intensity() const;
+ inline void set_intensity(float value);
+
+ // @@protoc_insertion_point(class_scope:px.PointCloudXYZI.PointXYZI)
+ private:
+ inline void set_has_x();
+ inline void clear_has_x();
+ inline void set_has_y();
+ inline void clear_has_y();
+ inline void set_has_z();
+ inline void clear_has_z();
+ inline void set_has_intensity();
+ inline void clear_has_intensity();
+
+ ::google::protobuf::UnknownFieldSet _unknown_fields_;
+
+ float x_;
+ float y_;
+ float z_;
+ float intensity_;
+
+ mutable int _cached_size_;
+ ::google::protobuf::uint32 _has_bits_[(4 + 31) / 32];
+
+ friend void protobuf_AddDesc_pixhawk_2eproto();
+ friend void protobuf_AssignDesc_pixhawk_2eproto();
+ friend void protobuf_ShutdownFile_pixhawk_2eproto();
+
+ void InitAsDefaultInstance();
+ static PointCloudXYZI_PointXYZI* default_instance_;
+};
+// -------------------------------------------------------------------
+
+class PointCloudXYZI : public ::google::protobuf::Message {
+ public:
+ PointCloudXYZI();
+ virtual ~PointCloudXYZI();
+
+ PointCloudXYZI(const PointCloudXYZI& from);
+
+ inline PointCloudXYZI& operator=(const PointCloudXYZI& from) {
+ CopyFrom(from);
+ return *this;
+ }
+
+ inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
+ return _unknown_fields_;
+ }
+
+ inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
+ return &_unknown_fields_;
+ }
+
+ static const ::google::protobuf::Descriptor* descriptor();
+ static const PointCloudXYZI& default_instance();
+
+ void Swap(PointCloudXYZI* other);
+
+ // implements Message ----------------------------------------------
+
+ PointCloudXYZI* New() const;
+ void CopyFrom(const ::google::protobuf::Message& from);
+ void MergeFrom(const ::google::protobuf::Message& from);
+ void CopyFrom(const PointCloudXYZI& from);
+ void MergeFrom(const PointCloudXYZI& from);
+ void Clear();
+ bool IsInitialized() const;
+
+ int ByteSize() const;
+ bool MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input);
+ void SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const;
+ ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
+ int GetCachedSize() const { return _cached_size_; }
+ private:
+ void SharedCtor();
+ void SharedDtor();
+ void SetCachedSize(int size) const;
+ public:
+
+ ::google::protobuf::Metadata GetMetadata() const;
+
+ // nested types ----------------------------------------------------
+
+ typedef PointCloudXYZI_PointXYZI PointXYZI;
+
+ // accessors -------------------------------------------------------
+
+ // required .px.HeaderInfo header = 1;
+ inline bool has_header() const;
+ inline void clear_header();
+ static const int kHeaderFieldNumber = 1;
+ inline const ::px::HeaderInfo& header() const;
+ inline ::px::HeaderInfo* mutable_header();
+ inline ::px::HeaderInfo* release_header();
+
+ // repeated .px.PointCloudXYZI.PointXYZI points = 2;
+ inline int points_size() const;
+ inline void clear_points();
+ static const int kPointsFieldNumber = 2;
+ inline const ::px::PointCloudXYZI_PointXYZI& points(int index) const;
+ inline ::px::PointCloudXYZI_PointXYZI* mutable_points(int index);
+ inline ::px::PointCloudXYZI_PointXYZI* add_points();
+ inline const ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI >&
+ points() const;
+ inline ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI >*
+ mutable_points();
+
+ // @@protoc_insertion_point(class_scope:px.PointCloudXYZI)
+ private:
+ inline void set_has_header();
+ inline void clear_has_header();
+
+ ::google::protobuf::UnknownFieldSet _unknown_fields_;
+
+ ::px::HeaderInfo* header_;
+ ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI > points_;
+
+ mutable int _cached_size_;
+ ::google::protobuf::uint32 _has_bits_[(2 + 31) / 32];
+
+ friend void protobuf_AddDesc_pixhawk_2eproto();
+ friend void protobuf_AssignDesc_pixhawk_2eproto();
+ friend void protobuf_ShutdownFile_pixhawk_2eproto();
+
+ void InitAsDefaultInstance();
+ static PointCloudXYZI* default_instance_;
+};
+// -------------------------------------------------------------------
+
+class PointCloudXYZRGB_PointXYZRGB : public ::google::protobuf::Message {
+ public:
+ PointCloudXYZRGB_PointXYZRGB();
+ virtual ~PointCloudXYZRGB_PointXYZRGB();
+
+ PointCloudXYZRGB_PointXYZRGB(const PointCloudXYZRGB_PointXYZRGB& from);
+
+ inline PointCloudXYZRGB_PointXYZRGB& operator=(const PointCloudXYZRGB_PointXYZRGB& from) {
+ CopyFrom(from);
+ return *this;
+ }
+
+ inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
+ return _unknown_fields_;
+ }
+
+ inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
+ return &_unknown_fields_;
+ }
+
+ static const ::google::protobuf::Descriptor* descriptor();
+ static const PointCloudXYZRGB_PointXYZRGB& default_instance();
+
+ void Swap(PointCloudXYZRGB_PointXYZRGB* other);
+
+ // implements Message ----------------------------------------------
+
+ PointCloudXYZRGB_PointXYZRGB* New() const;
+ void CopyFrom(const ::google::protobuf::Message& from);
+ void MergeFrom(const ::google::protobuf::Message& from);
+ void CopyFrom(const PointCloudXYZRGB_PointXYZRGB& from);
+ void MergeFrom(const PointCloudXYZRGB_PointXYZRGB& from);
+ void Clear();
+ bool IsInitialized() const;
+
+ int ByteSize() const;
+ bool MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input);
+ void SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const;
+ ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
+ int GetCachedSize() const { return _cached_size_; }
+ private:
+ void SharedCtor();
+ void SharedDtor();
+ void SetCachedSize(int size) const;
+ public:
+
+ ::google::protobuf::Metadata GetMetadata() const;
+
+ // nested types ----------------------------------------------------
+
+ // accessors -------------------------------------------------------
+
+ // required float x = 1;
+ inline bool has_x() const;
+ inline void clear_x();
+ static const int kXFieldNumber = 1;
+ inline float x() const;
+ inline void set_x(float value);
+
+ // required float y = 2;
+ inline bool has_y() const;
+ inline void clear_y();
+ static const int kYFieldNumber = 2;
+ inline float y() const;
+ inline void set_y(float value);
+
+ // required float z = 3;
+ inline bool has_z() const;
+ inline void clear_z();
+ static const int kZFieldNumber = 3;
+ inline float z() const;
+ inline void set_z(float value);
+
+ // required float rgb = 4;
+ inline bool has_rgb() const;
+ inline void clear_rgb();
+ static const int kRgbFieldNumber = 4;
+ inline float rgb() const;
+ inline void set_rgb(float value);
+
+ // @@protoc_insertion_point(class_scope:px.PointCloudXYZRGB.PointXYZRGB)
+ private:
+ inline void set_has_x();
+ inline void clear_has_x();
+ inline void set_has_y();
+ inline void clear_has_y();
+ inline void set_has_z();
+ inline void clear_has_z();
+ inline void set_has_rgb();
+ inline void clear_has_rgb();
+
+ ::google::protobuf::UnknownFieldSet _unknown_fields_;
+
+ float x_;
+ float y_;
+ float z_;
+ float rgb_;
+
+ mutable int _cached_size_;
+ ::google::protobuf::uint32 _has_bits_[(4 + 31) / 32];
+
+ friend void protobuf_AddDesc_pixhawk_2eproto();
+ friend void protobuf_AssignDesc_pixhawk_2eproto();
+ friend void protobuf_ShutdownFile_pixhawk_2eproto();
+
+ void InitAsDefaultInstance();
+ static PointCloudXYZRGB_PointXYZRGB* default_instance_;
+};
+// -------------------------------------------------------------------
+
+class PointCloudXYZRGB : public ::google::protobuf::Message {
+ public:
+ PointCloudXYZRGB();
+ virtual ~PointCloudXYZRGB();
+
+ PointCloudXYZRGB(const PointCloudXYZRGB& from);
+
+ inline PointCloudXYZRGB& operator=(const PointCloudXYZRGB& from) {
+ CopyFrom(from);
+ return *this;
+ }
+
+ inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
+ return _unknown_fields_;
+ }
+
+ inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
+ return &_unknown_fields_;
+ }
+
+ static const ::google::protobuf::Descriptor* descriptor();
+ static const PointCloudXYZRGB& default_instance();
+
+ void Swap(PointCloudXYZRGB* other);
+
+ // implements Message ----------------------------------------------
+
+ PointCloudXYZRGB* New() const;
+ void CopyFrom(const ::google::protobuf::Message& from);
+ void MergeFrom(const ::google::protobuf::Message& from);
+ void CopyFrom(const PointCloudXYZRGB& from);
+ void MergeFrom(const PointCloudXYZRGB& from);
+ void Clear();
+ bool IsInitialized() const;
+
+ int ByteSize() const;
+ bool MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input);
+ void SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const;
+ ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
+ int GetCachedSize() const { return _cached_size_; }
+ private:
+ void SharedCtor();
+ void SharedDtor();
+ void SetCachedSize(int size) const;
+ public:
+
+ ::google::protobuf::Metadata GetMetadata() const;
+
+ // nested types ----------------------------------------------------
+
+ typedef PointCloudXYZRGB_PointXYZRGB PointXYZRGB;
+
+ // accessors -------------------------------------------------------
+
+ // required .px.HeaderInfo header = 1;
+ inline bool has_header() const;
+ inline void clear_header();
+ static const int kHeaderFieldNumber = 1;
+ inline const ::px::HeaderInfo& header() const;
+ inline ::px::HeaderInfo* mutable_header();
+ inline ::px::HeaderInfo* release_header();
+
+ // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2;
+ inline int points_size() const;
+ inline void clear_points();
+ static const int kPointsFieldNumber = 2;
+ inline const ::px::PointCloudXYZRGB_PointXYZRGB& points(int index) const;
+ inline ::px::PointCloudXYZRGB_PointXYZRGB* mutable_points(int index);
+ inline ::px::PointCloudXYZRGB_PointXYZRGB* add_points();
+ inline const ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB >&
+ points() const;
+ inline ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB >*
+ mutable_points();
+
+ // @@protoc_insertion_point(class_scope:px.PointCloudXYZRGB)
+ private:
+ inline void set_has_header();
+ inline void clear_has_header();
+
+ ::google::protobuf::UnknownFieldSet _unknown_fields_;
+
+ ::px::HeaderInfo* header_;
+ ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB > points_;
+
+ mutable int _cached_size_;
+ ::google::protobuf::uint32 _has_bits_[(2 + 31) / 32];
+
+ friend void protobuf_AddDesc_pixhawk_2eproto();
+ friend void protobuf_AssignDesc_pixhawk_2eproto();
+ friend void protobuf_ShutdownFile_pixhawk_2eproto();
+
+ void InitAsDefaultInstance();
+ static PointCloudXYZRGB* default_instance_;
+};
+// -------------------------------------------------------------------
+
+class RGBDImage : public ::google::protobuf::Message {
+ public:
+ RGBDImage();
+ virtual ~RGBDImage();
+
+ RGBDImage(const RGBDImage& from);
+
+ inline RGBDImage& operator=(const RGBDImage& from) {
+ CopyFrom(from);
+ return *this;
+ }
+
+ inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
+ return _unknown_fields_;
+ }
+
+ inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
+ return &_unknown_fields_;
+ }
+
+ static const ::google::protobuf::Descriptor* descriptor();
+ static const RGBDImage& default_instance();
+
+ void Swap(RGBDImage* other);
+
+ // implements Message ----------------------------------------------
+
+ RGBDImage* New() const;
+ void CopyFrom(const ::google::protobuf::Message& from);
+ void MergeFrom(const ::google::protobuf::Message& from);
+ void CopyFrom(const RGBDImage& from);
+ void MergeFrom(const RGBDImage& from);
+ void Clear();
+ bool IsInitialized() const;
+
+ int ByteSize() const;
+ bool MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input);
+ void SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const;
+ ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
+ int GetCachedSize() const { return _cached_size_; }
+ private:
+ void SharedCtor();
+ void SharedDtor();
+ void SetCachedSize(int size) const;
+ public:
+
+ ::google::protobuf::Metadata GetMetadata() const;
+
+ // nested types ----------------------------------------------------
+
+ // accessors -------------------------------------------------------
+
+ // required .px.HeaderInfo header = 1;
+ inline bool has_header() const;
+ inline void clear_header();
+ static const int kHeaderFieldNumber = 1;
+ inline const ::px::HeaderInfo& header() const;
+ inline ::px::HeaderInfo* mutable_header();
+ inline ::px::HeaderInfo* release_header();
+
+ // required uint32 cols = 2;
+ inline bool has_cols() const;
+ inline void clear_cols();
+ static const int kColsFieldNumber = 2;
+ inline ::google::protobuf::uint32 cols() const;
+ inline void set_cols(::google::protobuf::uint32 value);
+
+ // required uint32 rows = 3;
+ inline bool has_rows() const;
+ inline void clear_rows();
+ static const int kRowsFieldNumber = 3;
+ inline ::google::protobuf::uint32 rows() const;
+ inline void set_rows(::google::protobuf::uint32 value);
+
+ // required uint32 step1 = 4;
+ inline bool has_step1() const;
+ inline void clear_step1();
+ static const int kStep1FieldNumber = 4;
+ inline ::google::protobuf::uint32 step1() const;
+ inline void set_step1(::google::protobuf::uint32 value);
+
+ // required uint32 type1 = 5;
+ inline bool has_type1() const;
+ inline void clear_type1();
+ static const int kType1FieldNumber = 5;
+ inline ::google::protobuf::uint32 type1() const;
+ inline void set_type1(::google::protobuf::uint32 value);
+
+ // required bytes imageData1 = 6;
+ inline bool has_imagedata1() const;
+ inline void clear_imagedata1();
+ static const int kImageData1FieldNumber = 6;
+ inline const ::std::string& imagedata1() const;
+ inline void set_imagedata1(const ::std::string& value);
+ inline void set_imagedata1(const char* value);
+ inline void set_imagedata1(const void* value, size_t size);
+ inline ::std::string* mutable_imagedata1();
+ inline ::std::string* release_imagedata1();
+
+ // required uint32 step2 = 7;
+ inline bool has_step2() const;
+ inline void clear_step2();
+ static const int kStep2FieldNumber = 7;
+ inline ::google::protobuf::uint32 step2() const;
+ inline void set_step2(::google::protobuf::uint32 value);
+
+ // required uint32 type2 = 8;
+ inline bool has_type2() const;
+ inline void clear_type2();
+ static const int kType2FieldNumber = 8;
+ inline ::google::protobuf::uint32 type2() const;
+ inline void set_type2(::google::protobuf::uint32 value);
+
+ // required bytes imageData2 = 9;
+ inline bool has_imagedata2() const;
+ inline void clear_imagedata2();
+ static const int kImageData2FieldNumber = 9;
+ inline const ::std::string& imagedata2() const;
+ inline void set_imagedata2(const ::std::string& value);
+ inline void set_imagedata2(const char* value);
+ inline void set_imagedata2(const void* value, size_t size);
+ inline ::std::string* mutable_imagedata2();
+ inline ::std::string* release_imagedata2();
+
+ // optional uint32 camera_config = 10;
+ inline bool has_camera_config() const;
+ inline void clear_camera_config();
+ static const int kCameraConfigFieldNumber = 10;
+ inline ::google::protobuf::uint32 camera_config() const;
+ inline void set_camera_config(::google::protobuf::uint32 value);
+
+ // optional uint32 camera_type = 11;
+ inline bool has_camera_type() const;
+ inline void clear_camera_type();
+ static const int kCameraTypeFieldNumber = 11;
+ inline ::google::protobuf::uint32 camera_type() const;
+ inline void set_camera_type(::google::protobuf::uint32 value);
+
+ // optional float roll = 12;
+ inline bool has_roll() const;
+ inline void clear_roll();
+ static const int kRollFieldNumber = 12;
+ inline float roll() const;
+ inline void set_roll(float value);
+
+ // optional float pitch = 13;
+ inline bool has_pitch() const;
+ inline void clear_pitch();
+ static const int kPitchFieldNumber = 13;
+ inline float pitch() const;
+ inline void set_pitch(float value);
+
+ // optional float yaw = 14;
+ inline bool has_yaw() const;
+ inline void clear_yaw();
+ static const int kYawFieldNumber = 14;
+ inline float yaw() const;
+ inline void set_yaw(float value);
+
+ // optional float lon = 15;
+ inline bool has_lon() const;
+ inline void clear_lon();
+ static const int kLonFieldNumber = 15;
+ inline float lon() const;
+ inline void set_lon(float value);
+
+ // optional float lat = 16;
+ inline bool has_lat() const;
+ inline void clear_lat();
+ static const int kLatFieldNumber = 16;
+ inline float lat() const;
+ inline void set_lat(float value);
+
+ // optional float alt = 17;
+ inline bool has_alt() const;
+ inline void clear_alt();
+ static const int kAltFieldNumber = 17;
+ inline float alt() const;
+ inline void set_alt(float value);
+
+ // optional float ground_x = 18;
+ inline bool has_ground_x() const;
+ inline void clear_ground_x();
+ static const int kGroundXFieldNumber = 18;
+ inline float ground_x() const;
+ inline void set_ground_x(float value);
+
+ // optional float ground_y = 19;
+ inline bool has_ground_y() const;
+ inline void clear_ground_y();
+ static const int kGroundYFieldNumber = 19;
+ inline float ground_y() const;
+ inline void set_ground_y(float value);
+
+ // optional float ground_z = 20;
+ inline bool has_ground_z() const;
+ inline void clear_ground_z();
+ static const int kGroundZFieldNumber = 20;
+ inline float ground_z() const;
+ inline void set_ground_z(float value);
+
+ // repeated float camera_matrix = 21;
+ inline int camera_matrix_size() const;
+ inline void clear_camera_matrix();
+ static const int kCameraMatrixFieldNumber = 21;
+ inline float camera_matrix(int index) const;
+ inline void set_camera_matrix(int index, float value);
+ inline void add_camera_matrix(float value);
+ inline const ::google::protobuf::RepeatedField< float >&
+ camera_matrix() const;
+ inline ::google::protobuf::RepeatedField< float >*
+ mutable_camera_matrix();
+
+ // @@protoc_insertion_point(class_scope:px.RGBDImage)
+ private:
+ inline void set_has_header();
+ inline void clear_has_header();
+ inline void set_has_cols();
+ inline void clear_has_cols();
+ inline void set_has_rows();
+ inline void clear_has_rows();
+ inline void set_has_step1();
+ inline void clear_has_step1();
+ inline void set_has_type1();
+ inline void clear_has_type1();
+ inline void set_has_imagedata1();
+ inline void clear_has_imagedata1();
+ inline void set_has_step2();
+ inline void clear_has_step2();
+ inline void set_has_type2();
+ inline void clear_has_type2();
+ inline void set_has_imagedata2();
+ inline void clear_has_imagedata2();
+ inline void set_has_camera_config();
+ inline void clear_has_camera_config();
+ inline void set_has_camera_type();
+ inline void clear_has_camera_type();
+ inline void set_has_roll();
+ inline void clear_has_roll();
+ inline void set_has_pitch();
+ inline void clear_has_pitch();
+ inline void set_has_yaw();
+ inline void clear_has_yaw();
+ inline void set_has_lon();
+ inline void clear_has_lon();
+ inline void set_has_lat();
+ inline void clear_has_lat();
+ inline void set_has_alt();
+ inline void clear_has_alt();
+ inline void set_has_ground_x();
+ inline void clear_has_ground_x();
+ inline void set_has_ground_y();
+ inline void clear_has_ground_y();
+ inline void set_has_ground_z();
+ inline void clear_has_ground_z();
+
+ ::google::protobuf::UnknownFieldSet _unknown_fields_;
+
+ ::px::HeaderInfo* header_;
+ ::google::protobuf::uint32 cols_;
+ ::google::protobuf::uint32 rows_;
+ ::google::protobuf::uint32 step1_;
+ ::google::protobuf::uint32 type1_;
+ ::std::string* imagedata1_;
+ ::google::protobuf::uint32 step2_;
+ ::google::protobuf::uint32 type2_;
+ ::std::string* imagedata2_;
+ ::google::protobuf::uint32 camera_config_;
+ ::google::protobuf::uint32 camera_type_;
+ float roll_;
+ float pitch_;
+ float yaw_;
+ float lon_;
+ float lat_;
+ float alt_;
+ float ground_x_;
+ float ground_y_;
+ ::google::protobuf::RepeatedField< float > camera_matrix_;
+ float ground_z_;
+
+ mutable int _cached_size_;
+ ::google::protobuf::uint32 _has_bits_[(21 + 31) / 32];
+
+ friend void protobuf_AddDesc_pixhawk_2eproto();
+ friend void protobuf_AssignDesc_pixhawk_2eproto();
+ friend void protobuf_ShutdownFile_pixhawk_2eproto();
+
+ void InitAsDefaultInstance();
+ static RGBDImage* default_instance_;
+};
+// -------------------------------------------------------------------
+
+class Waypoint : public ::google::protobuf::Message {
+ public:
+ Waypoint();
+ virtual ~Waypoint();
+
+ Waypoint(const Waypoint& from);
+
+ inline Waypoint& operator=(const Waypoint& from) {
+ CopyFrom(from);
+ return *this;
+ }
+
+ inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
+ return _unknown_fields_;
+ }
+
+ inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
+ return &_unknown_fields_;
+ }
+
+ static const ::google::protobuf::Descriptor* descriptor();
+ static const Waypoint& default_instance();
+
+ void Swap(Waypoint* other);
+
+ // implements Message ----------------------------------------------
+
+ Waypoint* New() const;
+ void CopyFrom(const ::google::protobuf::Message& from);
+ void MergeFrom(const ::google::protobuf::Message& from);
+ void CopyFrom(const Waypoint& from);
+ void MergeFrom(const Waypoint& from);
+ void Clear();
+ bool IsInitialized() const;
+
+ int ByteSize() const;
+ bool MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input);
+ void SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const;
+ ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
+ int GetCachedSize() const { return _cached_size_; }
+ private:
+ void SharedCtor();
+ void SharedDtor();
+ void SetCachedSize(int size) const;
+ public:
+
+ ::google::protobuf::Metadata GetMetadata() const;
+
+ // nested types ----------------------------------------------------
+
+ // accessors -------------------------------------------------------
+
+ // required double x = 1;
+ inline bool has_x() const;
+ inline void clear_x();
+ static const int kXFieldNumber = 1;
+ inline double x() const;
+ inline void set_x(double value);
+
+ // required double y = 2;
+ inline bool has_y() const;
+ inline void clear_y();
+ static const int kYFieldNumber = 2;
+ inline double y() const;
+ inline void set_y(double value);
+
+ // optional double z = 3;
+ inline bool has_z() const;
+ inline void clear_z();
+ static const int kZFieldNumber = 3;
+ inline double z() const;
+ inline void set_z(double value);
+
+ // optional double roll = 4;
+ inline bool has_roll() const;
+ inline void clear_roll();
+ static const int kRollFieldNumber = 4;
+ inline double roll() const;
+ inline void set_roll(double value);
+
+ // optional double pitch = 5;
+ inline bool has_pitch() const;
+ inline void clear_pitch();
+ static const int kPitchFieldNumber = 5;
+ inline double pitch() const;
+ inline void set_pitch(double value);
+
+ // optional double yaw = 6;
+ inline bool has_yaw() const;
+ inline void clear_yaw();
+ static const int kYawFieldNumber = 6;
+ inline double yaw() const;
+ inline void set_yaw(double value);
+
+ // @@protoc_insertion_point(class_scope:px.Waypoint)
+ private:
+ inline void set_has_x();
+ inline void clear_has_x();
+ inline void set_has_y();
+ inline void clear_has_y();
+ inline void set_has_z();
+ inline void clear_has_z();
+ inline void set_has_roll();
+ inline void clear_has_roll();
+ inline void set_has_pitch();
+ inline void clear_has_pitch();
+ inline void set_has_yaw();
+ inline void clear_has_yaw();
+
+ ::google::protobuf::UnknownFieldSet _unknown_fields_;
+
+ double x_;
+ double y_;
+ double z_;
+ double roll_;
+ double pitch_;
+ double yaw_;
+
+ mutable int _cached_size_;
+ ::google::protobuf::uint32 _has_bits_[(6 + 31) / 32];
+
+ friend void protobuf_AddDesc_pixhawk_2eproto();
+ friend void protobuf_AssignDesc_pixhawk_2eproto();
+ friend void protobuf_ShutdownFile_pixhawk_2eproto();
+
+ void InitAsDefaultInstance();
+ static Waypoint* default_instance_;
+};
+// ===================================================================
+
+
+// ===================================================================
+
+// HeaderInfo
+
+// required int32 source_sysid = 1;
+inline bool HeaderInfo::has_source_sysid() const {
+ return (_has_bits_[0] & 0x00000001u) != 0;
+}
+inline void HeaderInfo::set_has_source_sysid() {
+ _has_bits_[0] |= 0x00000001u;
+}
+inline void HeaderInfo::clear_has_source_sysid() {
+ _has_bits_[0] &= ~0x00000001u;
+}
+inline void HeaderInfo::clear_source_sysid() {
+ source_sysid_ = 0;
+ clear_has_source_sysid();
+}
+inline ::google::protobuf::int32 HeaderInfo::source_sysid() const {
+ return source_sysid_;
+}
+inline void HeaderInfo::set_source_sysid(::google::protobuf::int32 value) {
+ set_has_source_sysid();
+ source_sysid_ = value;
+}
+
+// required int32 source_compid = 2;
+inline bool HeaderInfo::has_source_compid() const {
+ return (_has_bits_[0] & 0x00000002u) != 0;
+}
+inline void HeaderInfo::set_has_source_compid() {
+ _has_bits_[0] |= 0x00000002u;
+}
+inline void HeaderInfo::clear_has_source_compid() {
+ _has_bits_[0] &= ~0x00000002u;
+}
+inline void HeaderInfo::clear_source_compid() {
+ source_compid_ = 0;
+ clear_has_source_compid();
+}
+inline ::google::protobuf::int32 HeaderInfo::source_compid() const {
+ return source_compid_;
+}
+inline void HeaderInfo::set_source_compid(::google::protobuf::int32 value) {
+ set_has_source_compid();
+ source_compid_ = value;
+}
+
+// required double timestamp = 3;
+inline bool HeaderInfo::has_timestamp() const {
+ return (_has_bits_[0] & 0x00000004u) != 0;
+}
+inline void HeaderInfo::set_has_timestamp() {
+ _has_bits_[0] |= 0x00000004u;
+}
+inline void HeaderInfo::clear_has_timestamp() {
+ _has_bits_[0] &= ~0x00000004u;
+}
+inline void HeaderInfo::clear_timestamp() {
+ timestamp_ = 0;
+ clear_has_timestamp();
+}
+inline double HeaderInfo::timestamp() const {
+ return timestamp_;
+}
+inline void HeaderInfo::set_timestamp(double value) {
+ set_has_timestamp();
+ timestamp_ = value;
+}
+
+// -------------------------------------------------------------------
+
+// GLOverlay
+
+// required .px.HeaderInfo header = 1;
+inline bool GLOverlay::has_header() const {
+ return (_has_bits_[0] & 0x00000001u) != 0;
+}
+inline void GLOverlay::set_has_header() {
+ _has_bits_[0] |= 0x00000001u;
+}
+inline void GLOverlay::clear_has_header() {
+ _has_bits_[0] &= ~0x00000001u;
+}
+inline void GLOverlay::clear_header() {
+ if (header_ != NULL) header_->::px::HeaderInfo::Clear();
+ clear_has_header();
+}
+inline const ::px::HeaderInfo& GLOverlay::header() const {
+ return header_ != NULL ? *header_ : *default_instance_->header_;
+}
+inline ::px::HeaderInfo* GLOverlay::mutable_header() {
+ set_has_header();
+ if (header_ == NULL) header_ = new ::px::HeaderInfo;
+ return header_;
+}
+inline ::px::HeaderInfo* GLOverlay::release_header() {
+ clear_has_header();
+ ::px::HeaderInfo* temp = header_;
+ header_ = NULL;
+ return temp;
+}
+
+// optional string name = 2;
+inline bool GLOverlay::has_name() const {
+ return (_has_bits_[0] & 0x00000002u) != 0;
+}
+inline void GLOverlay::set_has_name() {
+ _has_bits_[0] |= 0x00000002u;
+}
+inline void GLOverlay::clear_has_name() {
+ _has_bits_[0] &= ~0x00000002u;
+}
+inline void GLOverlay::clear_name() {
+ if (name_ != &::google::protobuf::internal::kEmptyString) {
+ name_->clear();
+ }
+ clear_has_name();
+}
+inline const ::std::string& GLOverlay::name() const {
+ return *name_;
+}
+inline void GLOverlay::set_name(const ::std::string& value) {
+ set_has_name();
+ if (name_ == &::google::protobuf::internal::kEmptyString) {
+ name_ = new ::std::string;
+ }
+ name_->assign(value);
+}
+inline void GLOverlay::set_name(const char* value) {
+ set_has_name();
+ if (name_ == &::google::protobuf::internal::kEmptyString) {
+ name_ = new ::std::string;
+ }
+ name_->assign(value);
+}
+inline void GLOverlay::set_name(const char* value, size_t size) {
+ set_has_name();
+ if (name_ == &::google::protobuf::internal::kEmptyString) {
+ name_ = new ::std::string;
+ }
+ name_->assign(reinterpret_cast<const char*>(value), size);
+}
+inline ::std::string* GLOverlay::mutable_name() {
+ set_has_name();
+ if (name_ == &::google::protobuf::internal::kEmptyString) {
+ name_ = new ::std::string;
+ }
+ return name_;
+}
+inline ::std::string* GLOverlay::release_name() {
+ clear_has_name();
+ if (name_ == &::google::protobuf::internal::kEmptyString) {
+ return NULL;
+ } else {
+ ::std::string* temp = name_;
+ name_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
+ return temp;
+ }
+}
+
+// optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3;
+inline bool GLOverlay::has_coordinateframetype() const {
+ return (_has_bits_[0] & 0x00000004u) != 0;
+}
+inline void GLOverlay::set_has_coordinateframetype() {
+ _has_bits_[0] |= 0x00000004u;
+}
+inline void GLOverlay::clear_has_coordinateframetype() {
+ _has_bits_[0] &= ~0x00000004u;
+}
+inline void GLOverlay::clear_coordinateframetype() {
+ coordinateframetype_ = 0;
+ clear_has_coordinateframetype();
+}
+inline ::px::GLOverlay_CoordinateFrameType GLOverlay::coordinateframetype() const {
+ return static_cast< ::px::GLOverlay_CoordinateFrameType >(coordinateframetype_);
+}
+inline void GLOverlay::set_coordinateframetype(::px::GLOverlay_CoordinateFrameType value) {
+ GOOGLE_DCHECK(::px::GLOverlay_CoordinateFrameType_IsValid(value));
+ set_has_coordinateframetype();
+ coordinateframetype_ = value;
+}
+
+// optional double origin_x = 4;
+inline bool GLOverlay::has_origin_x() const {
+ return (_has_bits_[0] & 0x00000008u) != 0;
+}
+inline void GLOverlay::set_has_origin_x() {
+ _has_bits_[0] |= 0x00000008u;
+}
+inline void GLOverlay::clear_has_origin_x() {
+ _has_bits_[0] &= ~0x00000008u;
+}
+inline void GLOverlay::clear_origin_x() {
+ origin_x_ = 0;
+ clear_has_origin_x();
+}
+inline double GLOverlay::origin_x() const {
+ return origin_x_;
+}
+inline void GLOverlay::set_origin_x(double value) {
+ set_has_origin_x();
+ origin_x_ = value;
+}
+
+// optional double origin_y = 5;
+inline bool GLOverlay::has_origin_y() const {
+ return (_has_bits_[0] & 0x00000010u) != 0;
+}
+inline void GLOverlay::set_has_origin_y() {
+ _has_bits_[0] |= 0x00000010u;
+}
+inline void GLOverlay::clear_has_origin_y() {
+ _has_bits_[0] &= ~0x00000010u;
+}
+inline void GLOverlay::clear_origin_y() {
+ origin_y_ = 0;
+ clear_has_origin_y();
+}
+inline double GLOverlay::origin_y() const {
+ return origin_y_;
+}
+inline void GLOverlay::set_origin_y(double value) {
+ set_has_origin_y();
+ origin_y_ = value;
+}
+
+// optional double origin_z = 6;
+inline bool GLOverlay::has_origin_z() const {
+ return (_has_bits_[0] & 0x00000020u) != 0;
+}
+inline void GLOverlay::set_has_origin_z() {
+ _has_bits_[0] |= 0x00000020u;
+}
+inline void GLOverlay::clear_has_origin_z() {
+ _has_bits_[0] &= ~0x00000020u;
+}
+inline void GLOverlay::clear_origin_z() {
+ origin_z_ = 0;
+ clear_has_origin_z();
+}
+inline double GLOverlay::origin_z() const {
+ return origin_z_;
+}
+inline void GLOverlay::set_origin_z(double value) {
+ set_has_origin_z();
+ origin_z_ = value;
+}
+
+// optional bytes data = 7;
+inline bool GLOverlay::has_data() const {
+ return (_has_bits_[0] & 0x00000040u) != 0;
+}
+inline void GLOverlay::set_has_data() {
+ _has_bits_[0] |= 0x00000040u;
+}
+inline void GLOverlay::clear_has_data() {
+ _has_bits_[0] &= ~0x00000040u;
+}
+inline void GLOverlay::clear_data() {
+ if (data_ != &::google::protobuf::internal::kEmptyString) {
+ data_->clear();
+ }
+ clear_has_data();
+}
+inline const ::std::string& GLOverlay::data() const {
+ return *data_;
+}
+inline void GLOverlay::set_data(const ::std::string& value) {
+ set_has_data();
+ if (data_ == &::google::protobuf::internal::kEmptyString) {
+ data_ = new ::std::string;
+ }
+ data_->assign(value);
+}
+inline void GLOverlay::set_data(const char* value) {
+ set_has_data();
+ if (data_ == &::google::protobuf::internal::kEmptyString) {
+ data_ = new ::std::string;
+ }
+ data_->assign(value);
+}
+inline void GLOverlay::set_data(const void* value, size_t size) {
+ set_has_data();
+ if (data_ == &::google::protobuf::internal::kEmptyString) {
+ data_ = new ::std::string;
+ }
+ data_->assign(reinterpret_cast<const char*>(value), size);
+}
+inline ::std::string* GLOverlay::mutable_data() {
+ set_has_data();
+ if (data_ == &::google::protobuf::internal::kEmptyString) {
+ data_ = new ::std::string;
+ }
+ return data_;
+}
+inline ::std::string* GLOverlay::release_data() {
+ clear_has_data();
+ if (data_ == &::google::protobuf::internal::kEmptyString) {
+ return NULL;
+ } else {
+ ::std::string* temp = data_;
+ data_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
+ return temp;
+ }
+}
+
+// -------------------------------------------------------------------
+
+// Obstacle
+
+// optional float x = 1;
+inline bool Obstacle::has_x() const {
+ return (_has_bits_[0] & 0x00000001u) != 0;
+}
+inline void Obstacle::set_has_x() {
+ _has_bits_[0] |= 0x00000001u;
+}
+inline void Obstacle::clear_has_x() {
+ _has_bits_[0] &= ~0x00000001u;
+}
+inline void Obstacle::clear_x() {
+ x_ = 0;
+ clear_has_x();
+}
+inline float Obstacle::x() const {
+ return x_;
+}
+inline void Obstacle::set_x(float value) {
+ set_has_x();
+ x_ = value;
+}
+
+// optional float y = 2;
+inline bool Obstacle::has_y() const {
+ return (_has_bits_[0] & 0x00000002u) != 0;
+}
+inline void Obstacle::set_has_y() {
+ _has_bits_[0] |= 0x00000002u;
+}
+inline void Obstacle::clear_has_y() {
+ _has_bits_[0] &= ~0x00000002u;
+}
+inline void Obstacle::clear_y() {
+ y_ = 0;
+ clear_has_y();
+}
+inline float Obstacle::y() const {
+ return y_;
+}
+inline void Obstacle::set_y(float value) {
+ set_has_y();
+ y_ = value;
+}
+
+// optional float z = 3;
+inline bool Obstacle::has_z() const {
+ return (_has_bits_[0] & 0x00000004u) != 0;
+}
+inline void Obstacle::set_has_z() {
+ _has_bits_[0] |= 0x00000004u;
+}
+inline void Obstacle::clear_has_z() {
+ _has_bits_[0] &= ~0x00000004u;
+}
+inline void Obstacle::clear_z() {
+ z_ = 0;
+ clear_has_z();
+}
+inline float Obstacle::z() const {
+ return z_;
+}
+inline void Obstacle::set_z(float value) {
+ set_has_z();
+ z_ = value;
+}
+
+// optional float length = 4;
+inline bool Obstacle::has_length() const {
+ return (_has_bits_[0] & 0x00000008u) != 0;
+}
+inline void Obstacle::set_has_length() {
+ _has_bits_[0] |= 0x00000008u;
+}
+inline void Obstacle::clear_has_length() {
+ _has_bits_[0] &= ~0x00000008u;
+}
+inline void Obstacle::clear_length() {
+ length_ = 0;
+ clear_has_length();
+}
+inline float Obstacle::length() const {
+ return length_;
+}
+inline void Obstacle::set_length(float value) {
+ set_has_length();
+ length_ = value;
+}
+
+// optional float width = 5;
+inline bool Obstacle::has_width() const {
+ return (_has_bits_[0] & 0x00000010u) != 0;
+}
+inline void Obstacle::set_has_width() {
+ _has_bits_[0] |= 0x00000010u;
+}
+inline void Obstacle::clear_has_width() {
+ _has_bits_[0] &= ~0x00000010u;
+}
+inline void Obstacle::clear_width() {
+ width_ = 0;
+ clear_has_width();
+}
+inline float Obstacle::width() const {
+ return width_;
+}
+inline void Obstacle::set_width(float value) {
+ set_has_width();
+ width_ = value;
+}
+
+// optional float height = 6;
+inline bool Obstacle::has_height() const {
+ return (_has_bits_[0] & 0x00000020u) != 0;
+}
+inline void Obstacle::set_has_height() {
+ _has_bits_[0] |= 0x00000020u;
+}
+inline void Obstacle::clear_has_height() {
+ _has_bits_[0] &= ~0x00000020u;
+}
+inline void Obstacle::clear_height() {
+ height_ = 0;
+ clear_has_height();
+}
+inline float Obstacle::height() const {
+ return height_;
+}
+inline void Obstacle::set_height(float value) {
+ set_has_height();
+ height_ = value;
+}
+
+// -------------------------------------------------------------------
+
+// ObstacleList
+
+// required .px.HeaderInfo header = 1;
+inline bool ObstacleList::has_header() const {
+ return (_has_bits_[0] & 0x00000001u) != 0;
+}
+inline void ObstacleList::set_has_header() {
+ _has_bits_[0] |= 0x00000001u;
+}
+inline void ObstacleList::clear_has_header() {
+ _has_bits_[0] &= ~0x00000001u;
+}
+inline void ObstacleList::clear_header() {
+ if (header_ != NULL) header_->::px::HeaderInfo::Clear();
+ clear_has_header();
+}
+inline const ::px::HeaderInfo& ObstacleList::header() const {
+ return header_ != NULL ? *header_ : *default_instance_->header_;
+}
+inline ::px::HeaderInfo* ObstacleList::mutable_header() {
+ set_has_header();
+ if (header_ == NULL) header_ = new ::px::HeaderInfo;
+ return header_;
+}
+inline ::px::HeaderInfo* ObstacleList::release_header() {
+ clear_has_header();
+ ::px::HeaderInfo* temp = header_;
+ header_ = NULL;
+ return temp;
+}
+
+// repeated .px.Obstacle obstacles = 2;
+inline int ObstacleList::obstacles_size() const {
+ return obstacles_.size();
+}
+inline void ObstacleList::clear_obstacles() {
+ obstacles_.Clear();
+}
+inline const ::px::Obstacle& ObstacleList::obstacles(int index) const {
+ return obstacles_.Get(index);
+}
+inline ::px::Obstacle* ObstacleList::mutable_obstacles(int index) {
+ return obstacles_.Mutable(index);
+}
+inline ::px::Obstacle* ObstacleList::add_obstacles() {
+ return obstacles_.Add();
+}
+inline const ::google::protobuf::RepeatedPtrField< ::px::Obstacle >&
+ObstacleList::obstacles() const {
+ return obstacles_;
+}
+inline ::google::protobuf::RepeatedPtrField< ::px::Obstacle >*
+ObstacleList::mutable_obstacles() {
+ return &obstacles_;
+}
+
+// -------------------------------------------------------------------
+
+// ObstacleMap
+
+// required .px.HeaderInfo header = 1;
+inline bool ObstacleMap::has_header() const {
+ return (_has_bits_[0] & 0x00000001u) != 0;
+}
+inline void ObstacleMap::set_has_header() {
+ _has_bits_[0] |= 0x00000001u;
+}
+inline void ObstacleMap::clear_has_header() {
+ _has_bits_[0] &= ~0x00000001u;
+}
+inline void ObstacleMap::clear_header() {
+ if (header_ != NULL) header_->::px::HeaderInfo::Clear();
+ clear_has_header();
+}
+inline const ::px::HeaderInfo& ObstacleMap::header() const {
+ return header_ != NULL ? *header_ : *default_instance_->header_;
+}
+inline ::px::HeaderInfo* ObstacleMap::mutable_header() {
+ set_has_header();
+ if (header_ == NULL) header_ = new ::px::HeaderInfo;
+ return header_;
+}
+inline ::px::HeaderInfo* ObstacleMap::release_header() {
+ clear_has_header();
+ ::px::HeaderInfo* temp = header_;
+ header_ = NULL;
+ return temp;
+}
+
+// required int32 type = 2;
+inline bool ObstacleMap::has_type() const {
+ return (_has_bits_[0] & 0x00000002u) != 0;
+}
+inline void ObstacleMap::set_has_type() {
+ _has_bits_[0] |= 0x00000002u;
+}
+inline void ObstacleMap::clear_has_type() {
+ _has_bits_[0] &= ~0x00000002u;
+}
+inline void ObstacleMap::clear_type() {
+ type_ = 0;
+ clear_has_type();
+}
+inline ::google::protobuf::int32 ObstacleMap::type() const {
+ return type_;
+}
+inline void ObstacleMap::set_type(::google::protobuf::int32 value) {
+ set_has_type();
+ type_ = value;
+}
+
+// optional float resolution = 3;
+inline bool ObstacleMap::has_resolution() const {
+ return (_has_bits_[0] & 0x00000004u) != 0;
+}
+inline void ObstacleMap::set_has_resolution() {
+ _has_bits_[0] |= 0x00000004u;
+}
+inline void ObstacleMap::clear_has_resolution() {
+ _has_bits_[0] &= ~0x00000004u;
+}
+inline void ObstacleMap::clear_resolution() {
+ resolution_ = 0;
+ clear_has_resolution();
+}
+inline float ObstacleMap::resolution() const {
+ return resolution_;
+}
+inline void ObstacleMap::set_resolution(float value) {
+ set_has_resolution();
+ resolution_ = value;
+}
+
+// optional int32 rows = 4;
+inline bool ObstacleMap::has_rows() const {
+ return (_has_bits_[0] & 0x00000008u) != 0;
+}
+inline void ObstacleMap::set_has_rows() {
+ _has_bits_[0] |= 0x00000008u;
+}
+inline void ObstacleMap::clear_has_rows() {
+ _has_bits_[0] &= ~0x00000008u;
+}
+inline void ObstacleMap::clear_rows() {
+ rows_ = 0;
+ clear_has_rows();
+}
+inline ::google::protobuf::int32 ObstacleMap::rows() const {
+ return rows_;
+}
+inline void ObstacleMap::set_rows(::google::protobuf::int32 value) {
+ set_has_rows();
+ rows_ = value;
+}
+
+// optional int32 cols = 5;
+inline bool ObstacleMap::has_cols() const {
+ return (_has_bits_[0] & 0x00000010u) != 0;
+}
+inline void ObstacleMap::set_has_cols() {
+ _has_bits_[0] |= 0x00000010u;
+}
+inline void ObstacleMap::clear_has_cols() {
+ _has_bits_[0] &= ~0x00000010u;
+}
+inline void ObstacleMap::clear_cols() {
+ cols_ = 0;
+ clear_has_cols();
+}
+inline ::google::protobuf::int32 ObstacleMap::cols() const {
+ return cols_;
+}
+inline void ObstacleMap::set_cols(::google::protobuf::int32 value) {
+ set_has_cols();
+ cols_ = value;
+}
+
+// optional int32 mapR0 = 6;
+inline bool ObstacleMap::has_mapr0() const {
+ return (_has_bits_[0] & 0x00000020u) != 0;
+}
+inline void ObstacleMap::set_has_mapr0() {
+ _has_bits_[0] |= 0x00000020u;
+}
+inline void ObstacleMap::clear_has_mapr0() {
+ _has_bits_[0] &= ~0x00000020u;
+}
+inline void ObstacleMap::clear_mapr0() {
+ mapr0_ = 0;
+ clear_has_mapr0();
+}
+inline ::google::protobuf::int32 ObstacleMap::mapr0() const {
+ return mapr0_;
+}
+inline void ObstacleMap::set_mapr0(::google::protobuf::int32 value) {
+ set_has_mapr0();
+ mapr0_ = value;
+}
+
+// optional int32 mapC0 = 7;
+inline bool ObstacleMap::has_mapc0() const {
+ return (_has_bits_[0] & 0x00000040u) != 0;
+}
+inline void ObstacleMap::set_has_mapc0() {
+ _has_bits_[0] |= 0x00000040u;
+}
+inline void ObstacleMap::clear_has_mapc0() {
+ _has_bits_[0] &= ~0x00000040u;
+}
+inline void ObstacleMap::clear_mapc0() {
+ mapc0_ = 0;
+ clear_has_mapc0();
+}
+inline ::google::protobuf::int32 ObstacleMap::mapc0() const {
+ return mapc0_;
+}
+inline void ObstacleMap::set_mapc0(::google::protobuf::int32 value) {
+ set_has_mapc0();
+ mapc0_ = value;
+}
+
+// optional int32 arrayR0 = 8;
+inline bool ObstacleMap::has_arrayr0() const {
+ return (_has_bits_[0] & 0x00000080u) != 0;
+}
+inline void ObstacleMap::set_has_arrayr0() {
+ _has_bits_[0] |= 0x00000080u;
+}
+inline void ObstacleMap::clear_has_arrayr0() {
+ _has_bits_[0] &= ~0x00000080u;
+}
+inline void ObstacleMap::clear_arrayr0() {
+ arrayr0_ = 0;
+ clear_has_arrayr0();
+}
+inline ::google::protobuf::int32 ObstacleMap::arrayr0() const {
+ return arrayr0_;
+}
+inline void ObstacleMap::set_arrayr0(::google::protobuf::int32 value) {
+ set_has_arrayr0();
+ arrayr0_ = value;
+}
+
+// optional int32 arrayC0 = 9;
+inline bool ObstacleMap::has_arrayc0() const {
+ return (_has_bits_[0] & 0x00000100u) != 0;
+}
+inline void ObstacleMap::set_has_arrayc0() {
+ _has_bits_[0] |= 0x00000100u;
+}
+inline void ObstacleMap::clear_has_arrayc0() {
+ _has_bits_[0] &= ~0x00000100u;
+}
+inline void ObstacleMap::clear_arrayc0() {
+ arrayc0_ = 0;
+ clear_has_arrayc0();
+}
+inline ::google::protobuf::int32 ObstacleMap::arrayc0() const {
+ return arrayc0_;
+}
+inline void ObstacleMap::set_arrayc0(::google::protobuf::int32 value) {
+ set_has_arrayc0();
+ arrayc0_ = value;
+}
+
+// optional bytes data = 10;
+inline bool ObstacleMap::has_data() const {
+ return (_has_bits_[0] & 0x00000200u) != 0;
+}
+inline void ObstacleMap::set_has_data() {
+ _has_bits_[0] |= 0x00000200u;
+}
+inline void ObstacleMap::clear_has_data() {
+ _has_bits_[0] &= ~0x00000200u;
+}
+inline void ObstacleMap::clear_data() {
+ if (data_ != &::google::protobuf::internal::kEmptyString) {
+ data_->clear();
+ }
+ clear_has_data();
+}
+inline const ::std::string& ObstacleMap::data() const {
+ return *data_;
+}
+inline void ObstacleMap::set_data(const ::std::string& value) {
+ set_has_data();
+ if (data_ == &::google::protobuf::internal::kEmptyString) {
+ data_ = new ::std::string;
+ }
+ data_->assign(value);
+}
+inline void ObstacleMap::set_data(const char* value) {
+ set_has_data();
+ if (data_ == &::google::protobuf::internal::kEmptyString) {
+ data_ = new ::std::string;
+ }
+ data_->assign(value);
+}
+inline void ObstacleMap::set_data(const void* value, size_t size) {
+ set_has_data();
+ if (data_ == &::google::protobuf::internal::kEmptyString) {
+ data_ = new ::std::string;
+ }
+ data_->assign(reinterpret_cast<const char*>(value), size);
+}
+inline ::std::string* ObstacleMap::mutable_data() {
+ set_has_data();
+ if (data_ == &::google::protobuf::internal::kEmptyString) {
+ data_ = new ::std::string;
+ }
+ return data_;
+}
+inline ::std::string* ObstacleMap::release_data() {
+ clear_has_data();
+ if (data_ == &::google::protobuf::internal::kEmptyString) {
+ return NULL;
+ } else {
+ ::std::string* temp = data_;
+ data_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
+ return temp;
+ }
+}
+
+// -------------------------------------------------------------------
+
+// Path
+
+// required .px.HeaderInfo header = 1;
+inline bool Path::has_header() const {
+ return (_has_bits_[0] & 0x00000001u) != 0;
+}
+inline void Path::set_has_header() {
+ _has_bits_[0] |= 0x00000001u;
+}
+inline void Path::clear_has_header() {
+ _has_bits_[0] &= ~0x00000001u;
+}
+inline void Path::clear_header() {
+ if (header_ != NULL) header_->::px::HeaderInfo::Clear();
+ clear_has_header();
+}
+inline const ::px::HeaderInfo& Path::header() const {
+ return header_ != NULL ? *header_ : *default_instance_->header_;
+}
+inline ::px::HeaderInfo* Path::mutable_header() {
+ set_has_header();
+ if (header_ == NULL) header_ = new ::px::HeaderInfo;
+ return header_;
+}
+inline ::px::HeaderInfo* Path::release_header() {
+ clear_has_header();
+ ::px::HeaderInfo* temp = header_;
+ header_ = NULL;
+ return temp;
+}
+
+// repeated .px.Waypoint waypoints = 2;
+inline int Path::waypoints_size() const {
+ return waypoints_.size();
+}
+inline void Path::clear_waypoints() {
+ waypoints_.Clear();
+}
+inline const ::px::Waypoint& Path::waypoints(int index) const {
+ return waypoints_.Get(index);
+}
+inline ::px::Waypoint* Path::mutable_waypoints(int index) {
+ return waypoints_.Mutable(index);
+}
+inline ::px::Waypoint* Path::add_waypoints() {
+ return waypoints_.Add();
+}
+inline const ::google::protobuf::RepeatedPtrField< ::px::Waypoint >&
+Path::waypoints() const {
+ return waypoints_;
+}
+inline ::google::protobuf::RepeatedPtrField< ::px::Waypoint >*
+Path::mutable_waypoints() {
+ return &waypoints_;
+}
+
+// -------------------------------------------------------------------
+
+// PointCloudXYZI_PointXYZI
+
+// required float x = 1;
+inline bool PointCloudXYZI_PointXYZI::has_x() const {
+ return (_has_bits_[0] & 0x00000001u) != 0;
+}
+inline void PointCloudXYZI_PointXYZI::set_has_x() {
+ _has_bits_[0] |= 0x00000001u;
+}
+inline void PointCloudXYZI_PointXYZI::clear_has_x() {
+ _has_bits_[0] &= ~0x00000001u;
+}
+inline void PointCloudXYZI_PointXYZI::clear_x() {
+ x_ = 0;
+ clear_has_x();
+}
+inline float PointCloudXYZI_PointXYZI::x() const {
+ return x_;
+}
+inline void PointCloudXYZI_PointXYZI::set_x(float value) {
+ set_has_x();
+ x_ = value;
+}
+
+// required float y = 2;
+inline bool PointCloudXYZI_PointXYZI::has_y() const {
+ return (_has_bits_[0] & 0x00000002u) != 0;
+}
+inline void PointCloudXYZI_PointXYZI::set_has_y() {
+ _has_bits_[0] |= 0x00000002u;
+}
+inline void PointCloudXYZI_PointXYZI::clear_has_y() {
+ _has_bits_[0] &= ~0x00000002u;
+}
+inline void PointCloudXYZI_PointXYZI::clear_y() {
+ y_ = 0;
+ clear_has_y();
+}
+inline float PointCloudXYZI_PointXYZI::y() const {
+ return y_;
+}
+inline void PointCloudXYZI_PointXYZI::set_y(float value) {
+ set_has_y();
+ y_ = value;
+}
+
+// required float z = 3;
+inline bool PointCloudXYZI_PointXYZI::has_z() const {
+ return (_has_bits_[0] & 0x00000004u) != 0;
+}
+inline void PointCloudXYZI_PointXYZI::set_has_z() {
+ _has_bits_[0] |= 0x00000004u;
+}
+inline void PointCloudXYZI_PointXYZI::clear_has_z() {
+ _has_bits_[0] &= ~0x00000004u;
+}
+inline void PointCloudXYZI_PointXYZI::clear_z() {
+ z_ = 0;
+ clear_has_z();
+}
+inline float PointCloudXYZI_PointXYZI::z() const {
+ return z_;
+}
+inline void PointCloudXYZI_PointXYZI::set_z(float value) {
+ set_has_z();
+ z_ = value;
+}
+
+// required float intensity = 4;
+inline bool PointCloudXYZI_PointXYZI::has_intensity() const {
+ return (_has_bits_[0] & 0x00000008u) != 0;
+}
+inline void PointCloudXYZI_PointXYZI::set_has_intensity() {
+ _has_bits_[0] |= 0x00000008u;
+}
+inline void PointCloudXYZI_PointXYZI::clear_has_intensity() {
+ _has_bits_[0] &= ~0x00000008u;
+}
+inline void PointCloudXYZI_PointXYZI::clear_intensity() {
+ intensity_ = 0;
+ clear_has_intensity();
+}
+inline float PointCloudXYZI_PointXYZI::intensity() const {
+ return intensity_;
+}
+inline void PointCloudXYZI_PointXYZI::set_intensity(float value) {
+ set_has_intensity();
+ intensity_ = value;
+}
+
+// -------------------------------------------------------------------
+
+// PointCloudXYZI
+
+// required .px.HeaderInfo header = 1;
+inline bool PointCloudXYZI::has_header() const {
+ return (_has_bits_[0] & 0x00000001u) != 0;
+}
+inline void PointCloudXYZI::set_has_header() {
+ _has_bits_[0] |= 0x00000001u;
+}
+inline void PointCloudXYZI::clear_has_header() {
+ _has_bits_[0] &= ~0x00000001u;
+}
+inline void PointCloudXYZI::clear_header() {
+ if (header_ != NULL) header_->::px::HeaderInfo::Clear();
+ clear_has_header();
+}
+inline const ::px::HeaderInfo& PointCloudXYZI::header() const {
+ return header_ != NULL ? *header_ : *default_instance_->header_;
+}
+inline ::px::HeaderInfo* PointCloudXYZI::mutable_header() {
+ set_has_header();
+ if (header_ == NULL) header_ = new ::px::HeaderInfo;
+ return header_;
+}
+inline ::px::HeaderInfo* PointCloudXYZI::release_header() {
+ clear_has_header();
+ ::px::HeaderInfo* temp = header_;
+ header_ = NULL;
+ return temp;
+}
+
+// repeated .px.PointCloudXYZI.PointXYZI points = 2;
+inline int PointCloudXYZI::points_size() const {
+ return points_.size();
+}
+inline void PointCloudXYZI::clear_points() {
+ points_.Clear();
+}
+inline const ::px::PointCloudXYZI_PointXYZI& PointCloudXYZI::points(int index) const {
+ return points_.Get(index);
+}
+inline ::px::PointCloudXYZI_PointXYZI* PointCloudXYZI::mutable_points(int index) {
+ return points_.Mutable(index);
+}
+inline ::px::PointCloudXYZI_PointXYZI* PointCloudXYZI::add_points() {
+ return points_.Add();
+}
+inline const ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI >&
+PointCloudXYZI::points() const {
+ return points_;
+}
+inline ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI >*
+PointCloudXYZI::mutable_points() {
+ return &points_;
+}
+
+// -------------------------------------------------------------------
+
+// PointCloudXYZRGB_PointXYZRGB
+
+// required float x = 1;
+inline bool PointCloudXYZRGB_PointXYZRGB::has_x() const {
+ return (_has_bits_[0] & 0x00000001u) != 0;
+}
+inline void PointCloudXYZRGB_PointXYZRGB::set_has_x() {
+ _has_bits_[0] |= 0x00000001u;
+}
+inline void PointCloudXYZRGB_PointXYZRGB::clear_has_x() {
+ _has_bits_[0] &= ~0x00000001u;
+}
+inline void PointCloudXYZRGB_PointXYZRGB::clear_x() {
+ x_ = 0;
+ clear_has_x();
+}
+inline float PointCloudXYZRGB_PointXYZRGB::x() const {
+ return x_;
+}
+inline void PointCloudXYZRGB_PointXYZRGB::set_x(float value) {
+ set_has_x();
+ x_ = value;
+}
+
+// required float y = 2;
+inline bool PointCloudXYZRGB_PointXYZRGB::has_y() const {
+ return (_has_bits_[0] & 0x00000002u) != 0;
+}
+inline void PointCloudXYZRGB_PointXYZRGB::set_has_y() {
+ _has_bits_[0] |= 0x00000002u;
+}
+inline void PointCloudXYZRGB_PointXYZRGB::clear_has_y() {
+ _has_bits_[0] &= ~0x00000002u;
+}
+inline void PointCloudXYZRGB_PointXYZRGB::clear_y() {
+ y_ = 0;
+ clear_has_y();
+}
+inline float PointCloudXYZRGB_PointXYZRGB::y() const {
+ return y_;
+}
+inline void PointCloudXYZRGB_PointXYZRGB::set_y(float value) {
+ set_has_y();
+ y_ = value;
+}
+
+// required float z = 3;
+inline bool PointCloudXYZRGB_PointXYZRGB::has_z() const {
+ return (_has_bits_[0] & 0x00000004u) != 0;
+}
+inline void PointCloudXYZRGB_PointXYZRGB::set_has_z() {
+ _has_bits_[0] |= 0x00000004u;
+}
+inline void PointCloudXYZRGB_PointXYZRGB::clear_has_z() {
+ _has_bits_[0] &= ~0x00000004u;
+}
+inline void PointCloudXYZRGB_PointXYZRGB::clear_z() {
+ z_ = 0;
+ clear_has_z();
+}
+inline float PointCloudXYZRGB_PointXYZRGB::z() const {
+ return z_;
+}
+inline void PointCloudXYZRGB_PointXYZRGB::set_z(float value) {
+ set_has_z();
+ z_ = value;
+}
+
+// required float rgb = 4;
+inline bool PointCloudXYZRGB_PointXYZRGB::has_rgb() const {
+ return (_has_bits_[0] & 0x00000008u) != 0;
+}
+inline void PointCloudXYZRGB_PointXYZRGB::set_has_rgb() {
+ _has_bits_[0] |= 0x00000008u;
+}
+inline void PointCloudXYZRGB_PointXYZRGB::clear_has_rgb() {
+ _has_bits_[0] &= ~0x00000008u;
+}
+inline void PointCloudXYZRGB_PointXYZRGB::clear_rgb() {
+ rgb_ = 0;
+ clear_has_rgb();
+}
+inline float PointCloudXYZRGB_PointXYZRGB::rgb() const {
+ return rgb_;
+}
+inline void PointCloudXYZRGB_PointXYZRGB::set_rgb(float value) {
+ set_has_rgb();
+ rgb_ = value;
+}
+
+// -------------------------------------------------------------------
+
+// PointCloudXYZRGB
+
+// required .px.HeaderInfo header = 1;
+inline bool PointCloudXYZRGB::has_header() const {
+ return (_has_bits_[0] & 0x00000001u) != 0;
+}
+inline void PointCloudXYZRGB::set_has_header() {
+ _has_bits_[0] |= 0x00000001u;
+}
+inline void PointCloudXYZRGB::clear_has_header() {
+ _has_bits_[0] &= ~0x00000001u;
+}
+inline void PointCloudXYZRGB::clear_header() {
+ if (header_ != NULL) header_->::px::HeaderInfo::Clear();
+ clear_has_header();
+}
+inline const ::px::HeaderInfo& PointCloudXYZRGB::header() const {
+ return header_ != NULL ? *header_ : *default_instance_->header_;
+}
+inline ::px::HeaderInfo* PointCloudXYZRGB::mutable_header() {
+ set_has_header();
+ if (header_ == NULL) header_ = new ::px::HeaderInfo;
+ return header_;
+}
+inline ::px::HeaderInfo* PointCloudXYZRGB::release_header() {
+ clear_has_header();
+ ::px::HeaderInfo* temp = header_;
+ header_ = NULL;
+ return temp;
+}
+
+// repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2;
+inline int PointCloudXYZRGB::points_size() const {
+ return points_.size();
+}
+inline void PointCloudXYZRGB::clear_points() {
+ points_.Clear();
+}
+inline const ::px::PointCloudXYZRGB_PointXYZRGB& PointCloudXYZRGB::points(int index) const {
+ return points_.Get(index);
+}
+inline ::px::PointCloudXYZRGB_PointXYZRGB* PointCloudXYZRGB::mutable_points(int index) {
+ return points_.Mutable(index);
+}
+inline ::px::PointCloudXYZRGB_PointXYZRGB* PointCloudXYZRGB::add_points() {
+ return points_.Add();
+}
+inline const ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB >&
+PointCloudXYZRGB::points() const {
+ return points_;
+}
+inline ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB >*
+PointCloudXYZRGB::mutable_points() {
+ return &points_;
+}
+
+// -------------------------------------------------------------------
+
+// RGBDImage
+
+// required .px.HeaderInfo header = 1;
+inline bool RGBDImage::has_header() const {
+ return (_has_bits_[0] & 0x00000001u) != 0;
+}
+inline void RGBDImage::set_has_header() {
+ _has_bits_[0] |= 0x00000001u;
+}
+inline void RGBDImage::clear_has_header() {
+ _has_bits_[0] &= ~0x00000001u;
+}
+inline void RGBDImage::clear_header() {
+ if (header_ != NULL) header_->::px::HeaderInfo::Clear();
+ clear_has_header();
+}
+inline const ::px::HeaderInfo& RGBDImage::header() const {
+ return header_ != NULL ? *header_ : *default_instance_->header_;
+}
+inline ::px::HeaderInfo* RGBDImage::mutable_header() {
+ set_has_header();
+ if (header_ == NULL) header_ = new ::px::HeaderInfo;
+ return header_;
+}
+inline ::px::HeaderInfo* RGBDImage::release_header() {
+ clear_has_header();
+ ::px::HeaderInfo* temp = header_;
+ header_ = NULL;
+ return temp;
+}
+
+// required uint32 cols = 2;
+inline bool RGBDImage::has_cols() const {
+ return (_has_bits_[0] & 0x00000002u) != 0;
+}
+inline void RGBDImage::set_has_cols() {
+ _has_bits_[0] |= 0x00000002u;
+}
+inline void RGBDImage::clear_has_cols() {
+ _has_bits_[0] &= ~0x00000002u;
+}
+inline void RGBDImage::clear_cols() {
+ cols_ = 0u;
+ clear_has_cols();
+}
+inline ::google::protobuf::uint32 RGBDImage::cols() const {
+ return cols_;
+}
+inline void RGBDImage::set_cols(::google::protobuf::uint32 value) {
+ set_has_cols();
+ cols_ = value;
+}
+
+// required uint32 rows = 3;
+inline bool RGBDImage::has_rows() const {
+ return (_has_bits_[0] & 0x00000004u) != 0;
+}
+inline void RGBDImage::set_has_rows() {
+ _has_bits_[0] |= 0x00000004u;
+}
+inline void RGBDImage::clear_has_rows() {
+ _has_bits_[0] &= ~0x00000004u;
+}
+inline void RGBDImage::clear_rows() {
+ rows_ = 0u;
+ clear_has_rows();
+}
+inline ::google::protobuf::uint32 RGBDImage::rows() const {
+ return rows_;
+}
+inline void RGBDImage::set_rows(::google::protobuf::uint32 value) {
+ set_has_rows();
+ rows_ = value;
+}
+
+// required uint32 step1 = 4;
+inline bool RGBDImage::has_step1() const {
+ return (_has_bits_[0] & 0x00000008u) != 0;
+}
+inline void RGBDImage::set_has_step1() {
+ _has_bits_[0] |= 0x00000008u;
+}
+inline void RGBDImage::clear_has_step1() {
+ _has_bits_[0] &= ~0x00000008u;
+}
+inline void RGBDImage::clear_step1() {
+ step1_ = 0u;
+ clear_has_step1();
+}
+inline ::google::protobuf::uint32 RGBDImage::step1() const {
+ return step1_;
+}
+inline void RGBDImage::set_step1(::google::protobuf::uint32 value) {
+ set_has_step1();
+ step1_ = value;
+}
+
+// required uint32 type1 = 5;
+inline bool RGBDImage::has_type1() const {
+ return (_has_bits_[0] & 0x00000010u) != 0;
+}
+inline void RGBDImage::set_has_type1() {
+ _has_bits_[0] |= 0x00000010u;
+}
+inline void RGBDImage::clear_has_type1() {
+ _has_bits_[0] &= ~0x00000010u;
+}
+inline void RGBDImage::clear_type1() {
+ type1_ = 0u;
+ clear_has_type1();
+}
+inline ::google::protobuf::uint32 RGBDImage::type1() const {
+ return type1_;
+}
+inline void RGBDImage::set_type1(::google::protobuf::uint32 value) {
+ set_has_type1();
+ type1_ = value;
+}
+
+// required bytes imageData1 = 6;
+inline bool RGBDImage::has_imagedata1() const {
+ return (_has_bits_[0] & 0x00000020u) != 0;
+}
+inline void RGBDImage::set_has_imagedata1() {
+ _has_bits_[0] |= 0x00000020u;
+}
+inline void RGBDImage::clear_has_imagedata1() {
+ _has_bits_[0] &= ~0x00000020u;
+}
+inline void RGBDImage::clear_imagedata1() {
+ if (imagedata1_ != &::google::protobuf::internal::kEmptyString) {
+ imagedata1_->clear();
+ }
+ clear_has_imagedata1();
+}
+inline const ::std::string& RGBDImage::imagedata1() const {
+ return *imagedata1_;
+}
+inline void RGBDImage::set_imagedata1(const ::std::string& value) {
+ set_has_imagedata1();
+ if (imagedata1_ == &::google::protobuf::internal::kEmptyString) {
+ imagedata1_ = new ::std::string;
+ }
+ imagedata1_->assign(value);
+}
+inline void RGBDImage::set_imagedata1(const char* value) {
+ set_has_imagedata1();
+ if (imagedata1_ == &::google::protobuf::internal::kEmptyString) {
+ imagedata1_ = new ::std::string;
+ }
+ imagedata1_->assign(value);
+}
+inline void RGBDImage::set_imagedata1(const void* value, size_t size) {
+ set_has_imagedata1();
+ if (imagedata1_ == &::google::protobuf::internal::kEmptyString) {
+ imagedata1_ = new ::std::string;
+ }
+ imagedata1_->assign(reinterpret_cast<const char*>(value), size);
+}
+inline ::std::string* RGBDImage::mutable_imagedata1() {
+ set_has_imagedata1();
+ if (imagedata1_ == &::google::protobuf::internal::kEmptyString) {
+ imagedata1_ = new ::std::string;
+ }
+ return imagedata1_;
+}
+inline ::std::string* RGBDImage::release_imagedata1() {
+ clear_has_imagedata1();
+ if (imagedata1_ == &::google::protobuf::internal::kEmptyString) {
+ return NULL;
+ } else {
+ ::std::string* temp = imagedata1_;
+ imagedata1_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
+ return temp;
+ }
+}
+
+// required uint32 step2 = 7;
+inline bool RGBDImage::has_step2() const {
+ return (_has_bits_[0] & 0x00000040u) != 0;
+}
+inline void RGBDImage::set_has_step2() {
+ _has_bits_[0] |= 0x00000040u;
+}
+inline void RGBDImage::clear_has_step2() {
+ _has_bits_[0] &= ~0x00000040u;
+}
+inline void RGBDImage::clear_step2() {
+ step2_ = 0u;
+ clear_has_step2();
+}
+inline ::google::protobuf::uint32 RGBDImage::step2() const {
+ return step2_;
+}
+inline void RGBDImage::set_step2(::google::protobuf::uint32 value) {
+ set_has_step2();
+ step2_ = value;
+}
+
+// required uint32 type2 = 8;
+inline bool RGBDImage::has_type2() const {
+ return (_has_bits_[0] & 0x00000080u) != 0;
+}
+inline void RGBDImage::set_has_type2() {
+ _has_bits_[0] |= 0x00000080u;
+}
+inline void RGBDImage::clear_has_type2() {
+ _has_bits_[0] &= ~0x00000080u;
+}
+inline void RGBDImage::clear_type2() {
+ type2_ = 0u;
+ clear_has_type2();
+}
+inline ::google::protobuf::uint32 RGBDImage::type2() const {
+ return type2_;
+}
+inline void RGBDImage::set_type2(::google::protobuf::uint32 value) {
+ set_has_type2();
+ type2_ = value;
+}
+
+// required bytes imageData2 = 9;
+inline bool RGBDImage::has_imagedata2() const {
+ return (_has_bits_[0] & 0x00000100u) != 0;
+}
+inline void RGBDImage::set_has_imagedata2() {
+ _has_bits_[0] |= 0x00000100u;
+}
+inline void RGBDImage::clear_has_imagedata2() {
+ _has_bits_[0] &= ~0x00000100u;
+}
+inline void RGBDImage::clear_imagedata2() {
+ if (imagedata2_ != &::google::protobuf::internal::kEmptyString) {
+ imagedata2_->clear();
+ }
+ clear_has_imagedata2();
+}
+inline const ::std::string& RGBDImage::imagedata2() const {
+ return *imagedata2_;
+}
+inline void RGBDImage::set_imagedata2(const ::std::string& value) {
+ set_has_imagedata2();
+ if (imagedata2_ == &::google::protobuf::internal::kEmptyString) {
+ imagedata2_ = new ::std::string;
+ }
+ imagedata2_->assign(value);
+}
+inline void RGBDImage::set_imagedata2(const char* value) {
+ set_has_imagedata2();
+ if (imagedata2_ == &::google::protobuf::internal::kEmptyString) {
+ imagedata2_ = new ::std::string;
+ }
+ imagedata2_->assign(value);
+}
+inline void RGBDImage::set_imagedata2(const void* value, size_t size) {
+ set_has_imagedata2();
+ if (imagedata2_ == &::google::protobuf::internal::kEmptyString) {
+ imagedata2_ = new ::std::string;
+ }
+ imagedata2_->assign(reinterpret_cast<const char*>(value), size);
+}
+inline ::std::string* RGBDImage::mutable_imagedata2() {
+ set_has_imagedata2();
+ if (imagedata2_ == &::google::protobuf::internal::kEmptyString) {
+ imagedata2_ = new ::std::string;
+ }
+ return imagedata2_;
+}
+inline ::std::string* RGBDImage::release_imagedata2() {
+ clear_has_imagedata2();
+ if (imagedata2_ == &::google::protobuf::internal::kEmptyString) {
+ return NULL;
+ } else {
+ ::std::string* temp = imagedata2_;
+ imagedata2_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
+ return temp;
+ }
+}
+
+// optional uint32 camera_config = 10;
+inline bool RGBDImage::has_camera_config() const {
+ return (_has_bits_[0] & 0x00000200u) != 0;
+}
+inline void RGBDImage::set_has_camera_config() {
+ _has_bits_[0] |= 0x00000200u;
+}
+inline void RGBDImage::clear_has_camera_config() {
+ _has_bits_[0] &= ~0x00000200u;
+}
+inline void RGBDImage::clear_camera_config() {
+ camera_config_ = 0u;
+ clear_has_camera_config();
+}
+inline ::google::protobuf::uint32 RGBDImage::camera_config() const {
+ return camera_config_;
+}
+inline void RGBDImage::set_camera_config(::google::protobuf::uint32 value) {
+ set_has_camera_config();
+ camera_config_ = value;
+}
+
+// optional uint32 camera_type = 11;
+inline bool RGBDImage::has_camera_type() const {
+ return (_has_bits_[0] & 0x00000400u) != 0;
+}
+inline void RGBDImage::set_has_camera_type() {
+ _has_bits_[0] |= 0x00000400u;
+}
+inline void RGBDImage::clear_has_camera_type() {
+ _has_bits_[0] &= ~0x00000400u;
+}
+inline void RGBDImage::clear_camera_type() {
+ camera_type_ = 0u;
+ clear_has_camera_type();
+}
+inline ::google::protobuf::uint32 RGBDImage::camera_type() const {
+ return camera_type_;
+}
+inline void RGBDImage::set_camera_type(::google::protobuf::uint32 value) {
+ set_has_camera_type();
+ camera_type_ = value;
+}
+
+// optional float roll = 12;
+inline bool RGBDImage::has_roll() const {
+ return (_has_bits_[0] & 0x00000800u) != 0;
+}
+inline void RGBDImage::set_has_roll() {
+ _has_bits_[0] |= 0x00000800u;
+}
+inline void RGBDImage::clear_has_roll() {
+ _has_bits_[0] &= ~0x00000800u;
+}
+inline void RGBDImage::clear_roll() {
+ roll_ = 0;
+ clear_has_roll();
+}
+inline float RGBDImage::roll() const {
+ return roll_;
+}
+inline void RGBDImage::set_roll(float value) {
+ set_has_roll();
+ roll_ = value;
+}
+
+// optional float pitch = 13;
+inline bool RGBDImage::has_pitch() const {
+ return (_has_bits_[0] & 0x00001000u) != 0;
+}
+inline void RGBDImage::set_has_pitch() {
+ _has_bits_[0] |= 0x00001000u;
+}
+inline void RGBDImage::clear_has_pitch() {
+ _has_bits_[0] &= ~0x00001000u;
+}
+inline void RGBDImage::clear_pitch() {
+ pitch_ = 0;
+ clear_has_pitch();
+}
+inline float RGBDImage::pitch() const {
+ return pitch_;
+}
+inline void RGBDImage::set_pitch(float value) {
+ set_has_pitch();
+ pitch_ = value;
+}
+
+// optional float yaw = 14;
+inline bool RGBDImage::has_yaw() const {
+ return (_has_bits_[0] & 0x00002000u) != 0;
+}
+inline void RGBDImage::set_has_yaw() {
+ _has_bits_[0] |= 0x00002000u;
+}
+inline void RGBDImage::clear_has_yaw() {
+ _has_bits_[0] &= ~0x00002000u;
+}
+inline void RGBDImage::clear_yaw() {
+ yaw_ = 0;
+ clear_has_yaw();
+}
+inline float RGBDImage::yaw() const {
+ return yaw_;
+}
+inline void RGBDImage::set_yaw(float value) {
+ set_has_yaw();
+ yaw_ = value;
+}
+
+// optional float lon = 15;
+inline bool RGBDImage::has_lon() const {
+ return (_has_bits_[0] & 0x00004000u) != 0;
+}
+inline void RGBDImage::set_has_lon() {
+ _has_bits_[0] |= 0x00004000u;
+}
+inline void RGBDImage::clear_has_lon() {
+ _has_bits_[0] &= ~0x00004000u;
+}
+inline void RGBDImage::clear_lon() {
+ lon_ = 0;
+ clear_has_lon();
+}
+inline float RGBDImage::lon() const {
+ return lon_;
+}
+inline void RGBDImage::set_lon(float value) {
+ set_has_lon();
+ lon_ = value;
+}
+
+// optional float lat = 16;
+inline bool RGBDImage::has_lat() const {
+ return (_has_bits_[0] & 0x00008000u) != 0;
+}
+inline void RGBDImage::set_has_lat() {
+ _has_bits_[0] |= 0x00008000u;
+}
+inline void RGBDImage::clear_has_lat() {
+ _has_bits_[0] &= ~0x00008000u;
+}
+inline void RGBDImage::clear_lat() {
+ lat_ = 0;
+ clear_has_lat();
+}
+inline float RGBDImage::lat() const {
+ return lat_;
+}
+inline void RGBDImage::set_lat(float value) {
+ set_has_lat();
+ lat_ = value;
+}
+
+// optional float alt = 17;
+inline bool RGBDImage::has_alt() const {
+ return (_has_bits_[0] & 0x00010000u) != 0;
+}
+inline void RGBDImage::set_has_alt() {
+ _has_bits_[0] |= 0x00010000u;
+}
+inline void RGBDImage::clear_has_alt() {
+ _has_bits_[0] &= ~0x00010000u;
+}
+inline void RGBDImage::clear_alt() {
+ alt_ = 0;
+ clear_has_alt();
+}
+inline float RGBDImage::alt() const {
+ return alt_;
+}
+inline void RGBDImage::set_alt(float value) {
+ set_has_alt();
+ alt_ = value;
+}
+
+// optional float ground_x = 18;
+inline bool RGBDImage::has_ground_x() const {
+ return (_has_bits_[0] & 0x00020000u) != 0;
+}
+inline void RGBDImage::set_has_ground_x() {
+ _has_bits_[0] |= 0x00020000u;
+}
+inline void RGBDImage::clear_has_ground_x() {
+ _has_bits_[0] &= ~0x00020000u;
+}
+inline void RGBDImage::clear_ground_x() {
+ ground_x_ = 0;
+ clear_has_ground_x();
+}
+inline float RGBDImage::ground_x() const {
+ return ground_x_;
+}
+inline void RGBDImage::set_ground_x(float value) {
+ set_has_ground_x();
+ ground_x_ = value;
+}
+
+// optional float ground_y = 19;
+inline bool RGBDImage::has_ground_y() const {
+ return (_has_bits_[0] & 0x00040000u) != 0;
+}
+inline void RGBDImage::set_has_ground_y() {
+ _has_bits_[0] |= 0x00040000u;
+}
+inline void RGBDImage::clear_has_ground_y() {
+ _has_bits_[0] &= ~0x00040000u;
+}
+inline void RGBDImage::clear_ground_y() {
+ ground_y_ = 0;
+ clear_has_ground_y();
+}
+inline float RGBDImage::ground_y() const {
+ return ground_y_;
+}
+inline void RGBDImage::set_ground_y(float value) {
+ set_has_ground_y();
+ ground_y_ = value;
+}
+
+// optional float ground_z = 20;
+inline bool RGBDImage::has_ground_z() const {
+ return (_has_bits_[0] & 0x00080000u) != 0;
+}
+inline void RGBDImage::set_has_ground_z() {
+ _has_bits_[0] |= 0x00080000u;
+}
+inline void RGBDImage::clear_has_ground_z() {
+ _has_bits_[0] &= ~0x00080000u;
+}
+inline void RGBDImage::clear_ground_z() {
+ ground_z_ = 0;
+ clear_has_ground_z();
+}
+inline float RGBDImage::ground_z() const {
+ return ground_z_;
+}
+inline void RGBDImage::set_ground_z(float value) {
+ set_has_ground_z();
+ ground_z_ = value;
+}
+
+// repeated float camera_matrix = 21;
+inline int RGBDImage::camera_matrix_size() const {
+ return camera_matrix_.size();
+}
+inline void RGBDImage::clear_camera_matrix() {
+ camera_matrix_.Clear();
+}
+inline float RGBDImage::camera_matrix(int index) const {
+ return camera_matrix_.Get(index);
+}
+inline void RGBDImage::set_camera_matrix(int index, float value) {
+ camera_matrix_.Set(index, value);
+}
+inline void RGBDImage::add_camera_matrix(float value) {
+ camera_matrix_.Add(value);
+}
+inline const ::google::protobuf::RepeatedField< float >&
+RGBDImage::camera_matrix() const {
+ return camera_matrix_;
+}
+inline ::google::protobuf::RepeatedField< float >*
+RGBDImage::mutable_camera_matrix() {
+ return &camera_matrix_;
+}
+
+// -------------------------------------------------------------------
+
+// Waypoint
+
+// required double x = 1;
+inline bool Waypoint::has_x() const {
+ return (_has_bits_[0] & 0x00000001u) != 0;
+}
+inline void Waypoint::set_has_x() {
+ _has_bits_[0] |= 0x00000001u;
+}
+inline void Waypoint::clear_has_x() {
+ _has_bits_[0] &= ~0x00000001u;
+}
+inline void Waypoint::clear_x() {
+ x_ = 0;
+ clear_has_x();
+}
+inline double Waypoint::x() const {
+ return x_;
+}
+inline void Waypoint::set_x(double value) {
+ set_has_x();
+ x_ = value;
+}
+
+// required double y = 2;
+inline bool Waypoint::has_y() const {
+ return (_has_bits_[0] & 0x00000002u) != 0;
+}
+inline void Waypoint::set_has_y() {
+ _has_bits_[0] |= 0x00000002u;
+}
+inline void Waypoint::clear_has_y() {
+ _has_bits_[0] &= ~0x00000002u;
+}
+inline void Waypoint::clear_y() {
+ y_ = 0;
+ clear_has_y();
+}
+inline double Waypoint::y() const {
+ return y_;
+}
+inline void Waypoint::set_y(double value) {
+ set_has_y();
+ y_ = value;
+}
+
+// optional double z = 3;
+inline bool Waypoint::has_z() const {
+ return (_has_bits_[0] & 0x00000004u) != 0;
+}
+inline void Waypoint::set_has_z() {
+ _has_bits_[0] |= 0x00000004u;
+}
+inline void Waypoint::clear_has_z() {
+ _has_bits_[0] &= ~0x00000004u;
+}
+inline void Waypoint::clear_z() {
+ z_ = 0;
+ clear_has_z();
+}
+inline double Waypoint::z() const {
+ return z_;
+}
+inline void Waypoint::set_z(double value) {
+ set_has_z();
+ z_ = value;
+}
+
+// optional double roll = 4;
+inline bool Waypoint::has_roll() const {
+ return (_has_bits_[0] & 0x00000008u) != 0;
+}
+inline void Waypoint::set_has_roll() {
+ _has_bits_[0] |= 0x00000008u;
+}
+inline void Waypoint::clear_has_roll() {
+ _has_bits_[0] &= ~0x00000008u;
+}
+inline void Waypoint::clear_roll() {
+ roll_ = 0;
+ clear_has_roll();
+}
+inline double Waypoint::roll() const {
+ return roll_;
+}
+inline void Waypoint::set_roll(double value) {
+ set_has_roll();
+ roll_ = value;
+}
+
+// optional double pitch = 5;
+inline bool Waypoint::has_pitch() const {
+ return (_has_bits_[0] & 0x00000010u) != 0;
+}
+inline void Waypoint::set_has_pitch() {
+ _has_bits_[0] |= 0x00000010u;
+}
+inline void Waypoint::clear_has_pitch() {
+ _has_bits_[0] &= ~0x00000010u;
+}
+inline void Waypoint::clear_pitch() {
+ pitch_ = 0;
+ clear_has_pitch();
+}
+inline double Waypoint::pitch() const {
+ return pitch_;
+}
+inline void Waypoint::set_pitch(double value) {
+ set_has_pitch();
+ pitch_ = value;
+}
+
+// optional double yaw = 6;
+inline bool Waypoint::has_yaw() const {
+ return (_has_bits_[0] & 0x00000020u) != 0;
+}
+inline void Waypoint::set_has_yaw() {
+ _has_bits_[0] |= 0x00000020u;
+}
+inline void Waypoint::clear_has_yaw() {
+ _has_bits_[0] &= ~0x00000020u;
+}
+inline void Waypoint::clear_yaw() {
+ yaw_ = 0;
+ clear_has_yaw();
+}
+inline double Waypoint::yaw() const {
+ return yaw_;
+}
+inline void Waypoint::set_yaw(double value) {
+ set_has_yaw();
+ yaw_ = value;
+}
+
+
+// @@protoc_insertion_point(namespace_scope)
+
+} // namespace px
+
+#ifndef SWIG
+namespace google {
+namespace protobuf {
+
+template <>
+inline const EnumDescriptor* GetEnumDescriptor< ::px::GLOverlay_CoordinateFrameType>() {
+ return ::px::GLOverlay_CoordinateFrameType_descriptor();
+}
+template <>
+inline const EnumDescriptor* GetEnumDescriptor< ::px::GLOverlay_Mode>() {
+ return ::px::GLOverlay_Mode_descriptor();
+}
+template <>
+inline const EnumDescriptor* GetEnumDescriptor< ::px::GLOverlay_Identifier>() {
+ return ::px::GLOverlay_Identifier_descriptor();
+}
+
+} // namespace google
+} // namespace protobuf
+#endif // SWIG
+
+// @@protoc_insertion_point(global_scope)
+
+#endif // PROTOBUF_pixhawk_2eproto__INCLUDED
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/protocol.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/protocol.h
new file mode 100644
index 000000000..7b3e3c0bd
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/protocol.h
@@ -0,0 +1,322 @@
+#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) (const char)_MAV_PAYLOAD(msg)[wire_offset]
+#define _MAV_RETURN_int8_t(msg, wire_offset) (const int8_t)_MAV_PAYLOAD(msg)[wire_offset]
+#define _MAV_RETURN_uint8_t(msg, wire_offset) (const 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_v1.0/test/mavlink.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/mavlink.h
new file mode 100644
index 000000000..e596b8fba
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/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 254
+#endif
+
+#ifndef MAVLINK_ENDIAN
+#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN
+#endif
+
+#ifndef MAVLINK_ALIGNED_FIELDS
+#define MAVLINK_ALIGNED_FIELDS 1
+#endif
+
+#ifndef MAVLINK_CRC_EXTRA
+#define MAVLINK_CRC_EXTRA 1
+#endif
+
+#include "version.h"
+#include "test.h"
+
+#endif // MAVLINK_H
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/mavlink_msg_test_types.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/mavlink_msg_test_types.h
new file mode 100644
index 000000000..2a3a89ff9
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/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
+{
+ uint64_t u64; ///< uint64_t
+ int64_t s64; ///< int64_t
+ double d; ///< double
+ uint64_t u64_array[3]; ///< uint64_t_array
+ int64_t s64_array[3]; ///< int64_t_array
+ double d_array[3]; ///< double_array
+ uint32_t u32; ///< uint32_t
+ int32_t s32; ///< int32_t
+ float f; ///< float
+ uint32_t u32_array[3]; ///< uint32_t_array
+ int32_t s32_array[3]; ///< int32_t_array
+ float f_array[3]; ///< float_array
+ uint16_t u16; ///< uint16_t
+ int16_t s16; ///< int16_t
+ uint16_t u16_array[3]; ///< uint16_t_array
+ int16_t s16_array[3]; ///< int16_t_array
+ char c; ///< char
+ char s[10]; ///< string
+ uint8_t u8; ///< uint8_t
+ int8_t s8; ///< int8_t
+ uint8_t u8_array[3]; ///< uint8_t_array
+ int8_t s8_array[3]; ///< int8_t_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_U64_ARRAY_LEN 3
+#define MAVLINK_MSG_TEST_TYPES_FIELD_S64_ARRAY_LEN 3
+#define MAVLINK_MSG_TEST_TYPES_FIELD_D_ARRAY_LEN 3
+#define MAVLINK_MSG_TEST_TYPES_FIELD_U32_ARRAY_LEN 3
+#define MAVLINK_MSG_TEST_TYPES_FIELD_S32_ARRAY_LEN 3
+#define MAVLINK_MSG_TEST_TYPES_FIELD_F_ARRAY_LEN 3
+#define MAVLINK_MSG_TEST_TYPES_FIELD_U16_ARRAY_LEN 3
+#define MAVLINK_MSG_TEST_TYPES_FIELD_S16_ARRAY_LEN 3
+#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_S8_ARRAY_LEN 3
+
+#define MAVLINK_MESSAGE_INFO_TEST_TYPES { \
+ "TEST_TYPES", \
+ 22, \
+ { { "u64", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_test_types_t, u64) }, \
+ { "s64", NULL, MAVLINK_TYPE_INT64_T, 0, 8, offsetof(mavlink_test_types_t, s64) }, \
+ { "d", NULL, MAVLINK_TYPE_DOUBLE, 0, 16, offsetof(mavlink_test_types_t, d) }, \
+ { "u64_array", NULL, MAVLINK_TYPE_UINT64_T, 3, 24, offsetof(mavlink_test_types_t, u64_array) }, \
+ { "s64_array", NULL, MAVLINK_TYPE_INT64_T, 3, 48, offsetof(mavlink_test_types_t, s64_array) }, \
+ { "d_array", NULL, MAVLINK_TYPE_DOUBLE, 3, 72, offsetof(mavlink_test_types_t, d_array) }, \
+ { "u32", "0x%08x", MAVLINK_TYPE_UINT32_T, 0, 96, offsetof(mavlink_test_types_t, u32) }, \
+ { "s32", NULL, MAVLINK_TYPE_INT32_T, 0, 100, offsetof(mavlink_test_types_t, s32) }, \
+ { "f", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_test_types_t, f) }, \
+ { "u32_array", NULL, MAVLINK_TYPE_UINT32_T, 3, 108, offsetof(mavlink_test_types_t, u32_array) }, \
+ { "s32_array", NULL, MAVLINK_TYPE_INT32_T, 3, 120, offsetof(mavlink_test_types_t, s32_array) }, \
+ { "f_array", NULL, MAVLINK_TYPE_FLOAT, 3, 132, offsetof(mavlink_test_types_t, f_array) }, \
+ { "u16", NULL, MAVLINK_TYPE_UINT16_T, 0, 144, offsetof(mavlink_test_types_t, u16) }, \
+ { "s16", NULL, MAVLINK_TYPE_INT16_T, 0, 146, offsetof(mavlink_test_types_t, s16) }, \
+ { "u16_array", NULL, MAVLINK_TYPE_UINT16_T, 3, 148, offsetof(mavlink_test_types_t, u16_array) }, \
+ { "s16_array", NULL, MAVLINK_TYPE_INT16_T, 3, 154, offsetof(mavlink_test_types_t, s16_array) }, \
+ { "c", NULL, MAVLINK_TYPE_CHAR, 0, 160, offsetof(mavlink_test_types_t, c) }, \
+ { "s", NULL, MAVLINK_TYPE_CHAR, 10, 161, offsetof(mavlink_test_types_t, s) }, \
+ { "u8", NULL, MAVLINK_TYPE_UINT8_T, 0, 171, offsetof(mavlink_test_types_t, u8) }, \
+ { "s8", NULL, MAVLINK_TYPE_INT8_T, 0, 172, offsetof(mavlink_test_types_t, s8) }, \
+ { "u8_array", NULL, MAVLINK_TYPE_UINT8_T, 3, 173, offsetof(mavlink_test_types_t, u8_array) }, \
+ { "s8_array", NULL, MAVLINK_TYPE_INT8_T, 3, 176, offsetof(mavlink_test_types_t, s8_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_uint64_t(buf, 0, u64);
+ _mav_put_int64_t(buf, 8, s64);
+ _mav_put_double(buf, 16, d);
+ _mav_put_uint32_t(buf, 96, u32);
+ _mav_put_int32_t(buf, 100, s32);
+ _mav_put_float(buf, 104, f);
+ _mav_put_uint16_t(buf, 144, u16);
+ _mav_put_int16_t(buf, 146, s16);
+ _mav_put_char(buf, 160, c);
+ _mav_put_uint8_t(buf, 171, u8);
+ _mav_put_int8_t(buf, 172, s8);
+ _mav_put_uint64_t_array(buf, 24, u64_array, 3);
+ _mav_put_int64_t_array(buf, 48, s64_array, 3);
+ _mav_put_double_array(buf, 72, d_array, 3);
+ _mav_put_uint32_t_array(buf, 108, u32_array, 3);
+ _mav_put_int32_t_array(buf, 120, s32_array, 3);
+ _mav_put_float_array(buf, 132, f_array, 3);
+ _mav_put_uint16_t_array(buf, 148, u16_array, 3);
+ _mav_put_int16_t_array(buf, 154, s16_array, 3);
+ _mav_put_char_array(buf, 161, s, 10);
+ _mav_put_uint8_t_array(buf, 173, u8_array, 3);
+ _mav_put_int8_t_array(buf, 176, s8_array, 3);
+ memcpy(_MAV_PAYLOAD(msg), buf, 179);
+#else
+ mavlink_test_types_t packet;
+ packet.u64 = u64;
+ packet.s64 = s64;
+ packet.d = d;
+ packet.u32 = u32;
+ packet.s32 = s32;
+ packet.f = f;
+ packet.u16 = u16;
+ packet.s16 = s16;
+ packet.c = c;
+ packet.u8 = u8;
+ packet.s8 = s8;
+ mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3);
+ mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3);
+ mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3);
+ mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3);
+ mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3);
+ mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3);
+ mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3);
+ mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3);
+ 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.s8_array, s8_array, sizeof(int8_t)*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, 103);
+}
+
+/**
+ * @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_uint64_t(buf, 0, u64);
+ _mav_put_int64_t(buf, 8, s64);
+ _mav_put_double(buf, 16, d);
+ _mav_put_uint32_t(buf, 96, u32);
+ _mav_put_int32_t(buf, 100, s32);
+ _mav_put_float(buf, 104, f);
+ _mav_put_uint16_t(buf, 144, u16);
+ _mav_put_int16_t(buf, 146, s16);
+ _mav_put_char(buf, 160, c);
+ _mav_put_uint8_t(buf, 171, u8);
+ _mav_put_int8_t(buf, 172, s8);
+ _mav_put_uint64_t_array(buf, 24, u64_array, 3);
+ _mav_put_int64_t_array(buf, 48, s64_array, 3);
+ _mav_put_double_array(buf, 72, d_array, 3);
+ _mav_put_uint32_t_array(buf, 108, u32_array, 3);
+ _mav_put_int32_t_array(buf, 120, s32_array, 3);
+ _mav_put_float_array(buf, 132, f_array, 3);
+ _mav_put_uint16_t_array(buf, 148, u16_array, 3);
+ _mav_put_int16_t_array(buf, 154, s16_array, 3);
+ _mav_put_char_array(buf, 161, s, 10);
+ _mav_put_uint8_t_array(buf, 173, u8_array, 3);
+ _mav_put_int8_t_array(buf, 176, s8_array, 3);
+ memcpy(_MAV_PAYLOAD(msg), buf, 179);
+#else
+ mavlink_test_types_t packet;
+ packet.u64 = u64;
+ packet.s64 = s64;
+ packet.d = d;
+ packet.u32 = u32;
+ packet.s32 = s32;
+ packet.f = f;
+ packet.u16 = u16;
+ packet.s16 = s16;
+ packet.c = c;
+ packet.u8 = u8;
+ packet.s8 = s8;
+ mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3);
+ mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3);
+ mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3);
+ mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3);
+ mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3);
+ mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3);
+ mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3);
+ mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3);
+ 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.s8_array, s8_array, sizeof(int8_t)*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, 103);
+}
+
+/**
+ * @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_uint64_t(buf, 0, u64);
+ _mav_put_int64_t(buf, 8, s64);
+ _mav_put_double(buf, 16, d);
+ _mav_put_uint32_t(buf, 96, u32);
+ _mav_put_int32_t(buf, 100, s32);
+ _mav_put_float(buf, 104, f);
+ _mav_put_uint16_t(buf, 144, u16);
+ _mav_put_int16_t(buf, 146, s16);
+ _mav_put_char(buf, 160, c);
+ _mav_put_uint8_t(buf, 171, u8);
+ _mav_put_int8_t(buf, 172, s8);
+ _mav_put_uint64_t_array(buf, 24, u64_array, 3);
+ _mav_put_int64_t_array(buf, 48, s64_array, 3);
+ _mav_put_double_array(buf, 72, d_array, 3);
+ _mav_put_uint32_t_array(buf, 108, u32_array, 3);
+ _mav_put_int32_t_array(buf, 120, s32_array, 3);
+ _mav_put_float_array(buf, 132, f_array, 3);
+ _mav_put_uint16_t_array(buf, 148, u16_array, 3);
+ _mav_put_int16_t_array(buf, 154, s16_array, 3);
+ _mav_put_char_array(buf, 161, s, 10);
+ _mav_put_uint8_t_array(buf, 173, u8_array, 3);
+ _mav_put_int8_t_array(buf, 176, s8_array, 3);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, buf, 179, 103);
+#else
+ mavlink_test_types_t packet;
+ packet.u64 = u64;
+ packet.s64 = s64;
+ packet.d = d;
+ packet.u32 = u32;
+ packet.s32 = s32;
+ packet.f = f;
+ packet.u16 = u16;
+ packet.s16 = s16;
+ packet.c = c;
+ packet.u8 = u8;
+ packet.s8 = s8;
+ mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3);
+ mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3);
+ mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3);
+ mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3);
+ mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3);
+ mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3);
+ mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3);
+ mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3);
+ 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.s8_array, s8_array, sizeof(int8_t)*3);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, (const char *)&packet, 179, 103);
+#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, 160);
+}
+
+/**
+ * @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, 161);
+}
+
+/**
+ * @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, 171);
+}
+
+/**
+ * @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, 144);
+}
+
+/**
+ * @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, 96);
+}
+
+/**
+ * @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, 0);
+}
+
+/**
+ * @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, 172);
+}
+
+/**
+ * @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, 146);
+}
+
+/**
+ * @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, 100);
+}
+
+/**
+ * @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, 8);
+}
+
+/**
+ * @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, 104);
+}
+
+/**
+ * @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, 16);
+}
+
+/**
+ * @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, 173);
+}
+
+/**
+ * @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, 148);
+}
+
+/**
+ * @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, 108);
+}
+
+/**
+ * @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, 24);
+}
+
+/**
+ * @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, 176);
+}
+
+/**
+ * @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, 154);
+}
+
+/**
+ * @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, 120);
+}
+
+/**
+ * @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, 48);
+}
+
+/**
+ * @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, 132);
+}
+
+/**
+ * @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, 72);
+}
+
+/**
+ * @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->u64 = mavlink_msg_test_types_get_u64(msg);
+ test_types->s64 = mavlink_msg_test_types_get_s64(msg);
+ test_types->d = mavlink_msg_test_types_get_d(msg);
+ mavlink_msg_test_types_get_u64_array(msg, test_types->u64_array);
+ mavlink_msg_test_types_get_s64_array(msg, test_types->s64_array);
+ mavlink_msg_test_types_get_d_array(msg, test_types->d_array);
+ test_types->u32 = mavlink_msg_test_types_get_u32(msg);
+ test_types->s32 = mavlink_msg_test_types_get_s32(msg);
+ test_types->f = mavlink_msg_test_types_get_f(msg);
+ mavlink_msg_test_types_get_u32_array(msg, test_types->u32_array);
+ mavlink_msg_test_types_get_s32_array(msg, test_types->s32_array);
+ mavlink_msg_test_types_get_f_array(msg, test_types->f_array);
+ test_types->u16 = mavlink_msg_test_types_get_u16(msg);
+ test_types->s16 = mavlink_msg_test_types_get_s16(msg);
+ mavlink_msg_test_types_get_u16_array(msg, test_types->u16_array);
+ mavlink_msg_test_types_get_s16_array(msg, test_types->s16_array);
+ 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->s8 = mavlink_msg_test_types_get_s8(msg);
+ mavlink_msg_test_types_get_u8_array(msg, test_types->u8_array);
+ mavlink_msg_test_types_get_s8_array(msg, test_types->s8_array);
+#else
+ memcpy(test_types, _MAV_PAYLOAD(msg), 179);
+#endif
+}
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/test.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/test.h
new file mode 100644
index 000000000..4dc04f889
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/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 {103, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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_v1.0/test/testsuite.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/testsuite.h
new file mode 100644
index 000000000..658e1ae07
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/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 = {
+ 93372036854775807ULL,
+ 93372036854776311LL,
+ 235.0,
+ { 93372036854777319, 93372036854777320, 93372036854777321 },
+ { 93372036854778831, 93372036854778832, 93372036854778833 },
+ { 627.0, 628.0, 629.0 },
+ 963502456,
+ 963502664,
+ 745.0,
+ { 963503080, 963503081, 963503082 },
+ { 963503704, 963503705, 963503706 },
+ { 941.0, 942.0, 943.0 },
+ 24723,
+ 24827,
+ { 24931, 24932, 24933 },
+ { 25243, 25244, 25245 },
+ 'E',
+ "FGHIJKLMN",
+ 198,
+ 9,
+ { 76, 77, 78 },
+ { 21, 22, 23 },
+ };
+ mavlink_test_types_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.u64 = packet_in.u64;
+ packet1.s64 = packet_in.s64;
+ packet1.d = packet_in.d;
+ packet1.u32 = packet_in.u32;
+ packet1.s32 = packet_in.s32;
+ packet1.f = packet_in.f;
+ packet1.u16 = packet_in.u16;
+ packet1.s16 = packet_in.s16;
+ packet1.c = packet_in.c;
+ packet1.u8 = packet_in.u8;
+ packet1.s8 = packet_in.s8;
+
+ mav_array_memcpy(packet1.u64_array, packet_in.u64_array, sizeof(uint64_t)*3);
+ mav_array_memcpy(packet1.s64_array, packet_in.s64_array, sizeof(int64_t)*3);
+ mav_array_memcpy(packet1.d_array, packet_in.d_array, sizeof(double)*3);
+ mav_array_memcpy(packet1.u32_array, packet_in.u32_array, sizeof(uint32_t)*3);
+ mav_array_memcpy(packet1.s32_array, packet_in.s32_array, sizeof(int32_t)*3);
+ mav_array_memcpy(packet1.f_array, packet_in.f_array, sizeof(float)*3);
+ mav_array_memcpy(packet1.u16_array, packet_in.u16_array, sizeof(uint16_t)*3);
+ mav_array_memcpy(packet1.s16_array, packet_in.s16_array, sizeof(int16_t)*3);
+ 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.s8_array, packet_in.s8_array, sizeof(int8_t)*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_v1.0/test/version.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/version.h
new file mode 100644
index 000000000..867641e21
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/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:58 2012"
+#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
+#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 179
+
+#endif // MAVLINK_VERSION_H
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/src_v1.0/pixhawk/pixhawk.pb.cc b/mavlink/share/pyshared/pymavlink/generator/C/src_v1.0/pixhawk/pixhawk.pb.cc
new file mode 100644
index 000000000..e984f512a
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/src_v1.0/pixhawk/pixhawk.pb.cc
@@ -0,0 +1,5431 @@
+// Generated by the protocol buffer compiler. DO NOT EDIT!
+
+#define INTERNAL_SUPPRESS_PROTOBUF_FIELD_DEPRECATION
+#include "pixhawk.pb.h"
+
+#include <algorithm>
+
+#include <google/protobuf/stubs/once.h>
+#include <google/protobuf/io/coded_stream.h>
+#include <google/protobuf/wire_format_lite_inl.h>
+#include <google/protobuf/descriptor.h>
+#include <google/protobuf/reflection_ops.h>
+#include <google/protobuf/wire_format.h>
+// @@protoc_insertion_point(includes)
+
+namespace px {
+
+namespace {
+
+const ::google::protobuf::Descriptor* HeaderInfo_descriptor_ = NULL;
+const ::google::protobuf::internal::GeneratedMessageReflection*
+ HeaderInfo_reflection_ = NULL;
+const ::google::protobuf::Descriptor* GLOverlay_descriptor_ = NULL;
+const ::google::protobuf::internal::GeneratedMessageReflection*
+ GLOverlay_reflection_ = NULL;
+const ::google::protobuf::EnumDescriptor* GLOverlay_CoordinateFrameType_descriptor_ = NULL;
+const ::google::protobuf::EnumDescriptor* GLOverlay_Mode_descriptor_ = NULL;
+const ::google::protobuf::EnumDescriptor* GLOverlay_Identifier_descriptor_ = NULL;
+const ::google::protobuf::Descriptor* Obstacle_descriptor_ = NULL;
+const ::google::protobuf::internal::GeneratedMessageReflection*
+ Obstacle_reflection_ = NULL;
+const ::google::protobuf::Descriptor* ObstacleList_descriptor_ = NULL;
+const ::google::protobuf::internal::GeneratedMessageReflection*
+ ObstacleList_reflection_ = NULL;
+const ::google::protobuf::Descriptor* ObstacleMap_descriptor_ = NULL;
+const ::google::protobuf::internal::GeneratedMessageReflection*
+ ObstacleMap_reflection_ = NULL;
+const ::google::protobuf::Descriptor* Path_descriptor_ = NULL;
+const ::google::protobuf::internal::GeneratedMessageReflection*
+ Path_reflection_ = NULL;
+const ::google::protobuf::Descriptor* PointCloudXYZI_descriptor_ = NULL;
+const ::google::protobuf::internal::GeneratedMessageReflection*
+ PointCloudXYZI_reflection_ = NULL;
+const ::google::protobuf::Descriptor* PointCloudXYZI_PointXYZI_descriptor_ = NULL;
+const ::google::protobuf::internal::GeneratedMessageReflection*
+ PointCloudXYZI_PointXYZI_reflection_ = NULL;
+const ::google::protobuf::Descriptor* PointCloudXYZRGB_descriptor_ = NULL;
+const ::google::protobuf::internal::GeneratedMessageReflection*
+ PointCloudXYZRGB_reflection_ = NULL;
+const ::google::protobuf::Descriptor* PointCloudXYZRGB_PointXYZRGB_descriptor_ = NULL;
+const ::google::protobuf::internal::GeneratedMessageReflection*
+ PointCloudXYZRGB_PointXYZRGB_reflection_ = NULL;
+const ::google::protobuf::Descriptor* RGBDImage_descriptor_ = NULL;
+const ::google::protobuf::internal::GeneratedMessageReflection*
+ RGBDImage_reflection_ = NULL;
+const ::google::protobuf::Descriptor* Waypoint_descriptor_ = NULL;
+const ::google::protobuf::internal::GeneratedMessageReflection*
+ Waypoint_reflection_ = NULL;
+
+} // namespace
+
+
+void protobuf_AssignDesc_pixhawk_2eproto() {
+ protobuf_AddDesc_pixhawk_2eproto();
+ const ::google::protobuf::FileDescriptor* file =
+ ::google::protobuf::DescriptorPool::generated_pool()->FindFileByName(
+ "pixhawk.proto");
+ GOOGLE_CHECK(file != NULL);
+ HeaderInfo_descriptor_ = file->message_type(0);
+ static const int HeaderInfo_offsets_[3] = {
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, source_sysid_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, source_compid_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, timestamp_),
+ };
+ HeaderInfo_reflection_ =
+ new ::google::protobuf::internal::GeneratedMessageReflection(
+ HeaderInfo_descriptor_,
+ HeaderInfo::default_instance_,
+ HeaderInfo_offsets_,
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, _has_bits_[0]),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, _unknown_fields_),
+ -1,
+ ::google::protobuf::DescriptorPool::generated_pool(),
+ ::google::protobuf::MessageFactory::generated_factory(),
+ sizeof(HeaderInfo));
+ GLOverlay_descriptor_ = file->message_type(1);
+ static const int GLOverlay_offsets_[7] = {
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, header_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, name_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, coordinateframetype_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, origin_x_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, origin_y_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, origin_z_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, data_),
+ };
+ GLOverlay_reflection_ =
+ new ::google::protobuf::internal::GeneratedMessageReflection(
+ GLOverlay_descriptor_,
+ GLOverlay::default_instance_,
+ GLOverlay_offsets_,
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, _has_bits_[0]),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, _unknown_fields_),
+ -1,
+ ::google::protobuf::DescriptorPool::generated_pool(),
+ ::google::protobuf::MessageFactory::generated_factory(),
+ sizeof(GLOverlay));
+ GLOverlay_CoordinateFrameType_descriptor_ = GLOverlay_descriptor_->enum_type(0);
+ GLOverlay_Mode_descriptor_ = GLOverlay_descriptor_->enum_type(1);
+ GLOverlay_Identifier_descriptor_ = GLOverlay_descriptor_->enum_type(2);
+ Obstacle_descriptor_ = file->message_type(2);
+ static const int Obstacle_offsets_[6] = {
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, x_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, y_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, z_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, length_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, width_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, height_),
+ };
+ Obstacle_reflection_ =
+ new ::google::protobuf::internal::GeneratedMessageReflection(
+ Obstacle_descriptor_,
+ Obstacle::default_instance_,
+ Obstacle_offsets_,
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, _has_bits_[0]),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, _unknown_fields_),
+ -1,
+ ::google::protobuf::DescriptorPool::generated_pool(),
+ ::google::protobuf::MessageFactory::generated_factory(),
+ sizeof(Obstacle));
+ ObstacleList_descriptor_ = file->message_type(3);
+ static const int ObstacleList_offsets_[2] = {
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, header_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, obstacles_),
+ };
+ ObstacleList_reflection_ =
+ new ::google::protobuf::internal::GeneratedMessageReflection(
+ ObstacleList_descriptor_,
+ ObstacleList::default_instance_,
+ ObstacleList_offsets_,
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, _has_bits_[0]),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, _unknown_fields_),
+ -1,
+ ::google::protobuf::DescriptorPool::generated_pool(),
+ ::google::protobuf::MessageFactory::generated_factory(),
+ sizeof(ObstacleList));
+ ObstacleMap_descriptor_ = file->message_type(4);
+ static const int ObstacleMap_offsets_[10] = {
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, header_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, type_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, resolution_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, rows_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, cols_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, mapr0_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, mapc0_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, arrayr0_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, arrayc0_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, data_),
+ };
+ ObstacleMap_reflection_ =
+ new ::google::protobuf::internal::GeneratedMessageReflection(
+ ObstacleMap_descriptor_,
+ ObstacleMap::default_instance_,
+ ObstacleMap_offsets_,
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, _has_bits_[0]),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, _unknown_fields_),
+ -1,
+ ::google::protobuf::DescriptorPool::generated_pool(),
+ ::google::protobuf::MessageFactory::generated_factory(),
+ sizeof(ObstacleMap));
+ Path_descriptor_ = file->message_type(5);
+ static const int Path_offsets_[2] = {
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, header_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, waypoints_),
+ };
+ Path_reflection_ =
+ new ::google::protobuf::internal::GeneratedMessageReflection(
+ Path_descriptor_,
+ Path::default_instance_,
+ Path_offsets_,
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, _has_bits_[0]),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, _unknown_fields_),
+ -1,
+ ::google::protobuf::DescriptorPool::generated_pool(),
+ ::google::protobuf::MessageFactory::generated_factory(),
+ sizeof(Path));
+ PointCloudXYZI_descriptor_ = file->message_type(6);
+ static const int PointCloudXYZI_offsets_[2] = {
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, header_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, points_),
+ };
+ PointCloudXYZI_reflection_ =
+ new ::google::protobuf::internal::GeneratedMessageReflection(
+ PointCloudXYZI_descriptor_,
+ PointCloudXYZI::default_instance_,
+ PointCloudXYZI_offsets_,
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, _has_bits_[0]),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, _unknown_fields_),
+ -1,
+ ::google::protobuf::DescriptorPool::generated_pool(),
+ ::google::protobuf::MessageFactory::generated_factory(),
+ sizeof(PointCloudXYZI));
+ PointCloudXYZI_PointXYZI_descriptor_ = PointCloudXYZI_descriptor_->nested_type(0);
+ static const int PointCloudXYZI_PointXYZI_offsets_[4] = {
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, x_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, y_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, z_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, intensity_),
+ };
+ PointCloudXYZI_PointXYZI_reflection_ =
+ new ::google::protobuf::internal::GeneratedMessageReflection(
+ PointCloudXYZI_PointXYZI_descriptor_,
+ PointCloudXYZI_PointXYZI::default_instance_,
+ PointCloudXYZI_PointXYZI_offsets_,
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, _has_bits_[0]),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, _unknown_fields_),
+ -1,
+ ::google::protobuf::DescriptorPool::generated_pool(),
+ ::google::protobuf::MessageFactory::generated_factory(),
+ sizeof(PointCloudXYZI_PointXYZI));
+ PointCloudXYZRGB_descriptor_ = file->message_type(7);
+ static const int PointCloudXYZRGB_offsets_[2] = {
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, header_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, points_),
+ };
+ PointCloudXYZRGB_reflection_ =
+ new ::google::protobuf::internal::GeneratedMessageReflection(
+ PointCloudXYZRGB_descriptor_,
+ PointCloudXYZRGB::default_instance_,
+ PointCloudXYZRGB_offsets_,
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, _has_bits_[0]),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, _unknown_fields_),
+ -1,
+ ::google::protobuf::DescriptorPool::generated_pool(),
+ ::google::protobuf::MessageFactory::generated_factory(),
+ sizeof(PointCloudXYZRGB));
+ PointCloudXYZRGB_PointXYZRGB_descriptor_ = PointCloudXYZRGB_descriptor_->nested_type(0);
+ static const int PointCloudXYZRGB_PointXYZRGB_offsets_[4] = {
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, x_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, y_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, z_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, rgb_),
+ };
+ PointCloudXYZRGB_PointXYZRGB_reflection_ =
+ new ::google::protobuf::internal::GeneratedMessageReflection(
+ PointCloudXYZRGB_PointXYZRGB_descriptor_,
+ PointCloudXYZRGB_PointXYZRGB::default_instance_,
+ PointCloudXYZRGB_PointXYZRGB_offsets_,
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, _has_bits_[0]),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, _unknown_fields_),
+ -1,
+ ::google::protobuf::DescriptorPool::generated_pool(),
+ ::google::protobuf::MessageFactory::generated_factory(),
+ sizeof(PointCloudXYZRGB_PointXYZRGB));
+ RGBDImage_descriptor_ = file->message_type(8);
+ static const int RGBDImage_offsets_[21] = {
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, header_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, cols_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, rows_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, step1_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, type1_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, imagedata1_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, step2_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, type2_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, imagedata2_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, camera_config_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, camera_type_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, roll_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, pitch_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, yaw_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, lon_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, lat_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, alt_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, ground_x_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, ground_y_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, ground_z_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, camera_matrix_),
+ };
+ RGBDImage_reflection_ =
+ new ::google::protobuf::internal::GeneratedMessageReflection(
+ RGBDImage_descriptor_,
+ RGBDImage::default_instance_,
+ RGBDImage_offsets_,
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, _has_bits_[0]),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, _unknown_fields_),
+ -1,
+ ::google::protobuf::DescriptorPool::generated_pool(),
+ ::google::protobuf::MessageFactory::generated_factory(),
+ sizeof(RGBDImage));
+ Waypoint_descriptor_ = file->message_type(9);
+ static const int Waypoint_offsets_[6] = {
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, x_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, y_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, z_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, roll_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, pitch_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, yaw_),
+ };
+ Waypoint_reflection_ =
+ new ::google::protobuf::internal::GeneratedMessageReflection(
+ Waypoint_descriptor_,
+ Waypoint::default_instance_,
+ Waypoint_offsets_,
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, _has_bits_[0]),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, _unknown_fields_),
+ -1,
+ ::google::protobuf::DescriptorPool::generated_pool(),
+ ::google::protobuf::MessageFactory::generated_factory(),
+ sizeof(Waypoint));
+}
+
+namespace {
+
+GOOGLE_PROTOBUF_DECLARE_ONCE(protobuf_AssignDescriptors_once_);
+inline void protobuf_AssignDescriptorsOnce() {
+ ::google::protobuf::GoogleOnceInit(&protobuf_AssignDescriptors_once_,
+ &protobuf_AssignDesc_pixhawk_2eproto);
+}
+
+void protobuf_RegisterTypes(const ::std::string&) {
+ protobuf_AssignDescriptorsOnce();
+ ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
+ HeaderInfo_descriptor_, &HeaderInfo::default_instance());
+ ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
+ GLOverlay_descriptor_, &GLOverlay::default_instance());
+ ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
+ Obstacle_descriptor_, &Obstacle::default_instance());
+ ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
+ ObstacleList_descriptor_, &ObstacleList::default_instance());
+ ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
+ ObstacleMap_descriptor_, &ObstacleMap::default_instance());
+ ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
+ Path_descriptor_, &Path::default_instance());
+ ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
+ PointCloudXYZI_descriptor_, &PointCloudXYZI::default_instance());
+ ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
+ PointCloudXYZI_PointXYZI_descriptor_, &PointCloudXYZI_PointXYZI::default_instance());
+ ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
+ PointCloudXYZRGB_descriptor_, &PointCloudXYZRGB::default_instance());
+ ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
+ PointCloudXYZRGB_PointXYZRGB_descriptor_, &PointCloudXYZRGB_PointXYZRGB::default_instance());
+ ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
+ RGBDImage_descriptor_, &RGBDImage::default_instance());
+ ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
+ Waypoint_descriptor_, &Waypoint::default_instance());
+}
+
+} // namespace
+
+void protobuf_ShutdownFile_pixhawk_2eproto() {
+ delete HeaderInfo::default_instance_;
+ delete HeaderInfo_reflection_;
+ delete GLOverlay::default_instance_;
+ delete GLOverlay_reflection_;
+ delete Obstacle::default_instance_;
+ delete Obstacle_reflection_;
+ delete ObstacleList::default_instance_;
+ delete ObstacleList_reflection_;
+ delete ObstacleMap::default_instance_;
+ delete ObstacleMap_reflection_;
+ delete Path::default_instance_;
+ delete Path_reflection_;
+ delete PointCloudXYZI::default_instance_;
+ delete PointCloudXYZI_reflection_;
+ delete PointCloudXYZI_PointXYZI::default_instance_;
+ delete PointCloudXYZI_PointXYZI_reflection_;
+ delete PointCloudXYZRGB::default_instance_;
+ delete PointCloudXYZRGB_reflection_;
+ delete PointCloudXYZRGB_PointXYZRGB::default_instance_;
+ delete PointCloudXYZRGB_PointXYZRGB_reflection_;
+ delete RGBDImage::default_instance_;
+ delete RGBDImage_reflection_;
+ delete Waypoint::default_instance_;
+ delete Waypoint_reflection_;
+}
+
+void protobuf_AddDesc_pixhawk_2eproto() {
+ static bool already_here = false;
+ if (already_here) return;
+ already_here = true;
+ GOOGLE_PROTOBUF_VERIFY_VERSION;
+
+ ::google::protobuf::DescriptorPool::InternalAddGeneratedFile(
+ "\n\rpixhawk.proto\022\002px\"L\n\nHeaderInfo\022\024\n\014sou"
+ "rce_sysid\030\001 \002(\005\022\025\n\rsource_compid\030\002 \002(\005\022\021"
+ "\n\ttimestamp\030\003 \002(\001\"\377\004\n\tGLOverlay\022\036\n\006heade"
+ "r\030\001 \002(\0132\016.px.HeaderInfo\022\014\n\004name\030\002 \001(\t\022>\n"
+ "\023coordinateFrameType\030\003 \001(\0162!.px.GLOverla"
+ "y.CoordinateFrameType\022\020\n\010origin_x\030\004 \001(\001\022"
+ "\020\n\010origin_y\030\005 \001(\001\022\020\n\010origin_z\030\006 \001(\001\022\014\n\004d"
+ "ata\030\007 \001(\014\",\n\023CoordinateFrameType\022\n\n\006GLOB"
+ "AL\020\000\022\t\n\005LOCAL\020\001\"\333\001\n\004Mode\022\n\n\006POINTS\020\000\022\t\n\005"
+ "LINES\020\001\022\016\n\nLINE_STRIP\020\002\022\r\n\tLINE_LOOP\020\003\022\r"
+ "\n\tTRIANGLES\020\004\022\022\n\016TRIANGLE_STRIP\020\005\022\020\n\014TRI"
+ "ANGLE_FAN\020\006\022\t\n\005QUADS\020\007\022\016\n\nQUAD_STRIP\020\010\022\013"
+ "\n\007POLYGON\020\t\022\020\n\014SOLID_CIRCLE\020\n\022\017\n\013WIRE_CI"
+ "RCLE\020\013\022\016\n\nSOLID_CUBE\020\014\022\r\n\tWIRE_CUBE\020\r\"\263\001"
+ "\n\nIdentifier\022\007\n\003END\020\016\022\014\n\010VERTEX2F\020\017\022\014\n\010V"
+ "ERTEX3F\020\020\022\013\n\007ROTATEF\020\021\022\016\n\nTRANSLATEF\020\022\022\n"
+ "\n\006SCALEF\020\023\022\017\n\013PUSH_MATRIX\020\024\022\016\n\nPOP_MATRI"
+ "X\020\025\022\013\n\007COLOR3F\020\026\022\013\n\007COLOR4F\020\027\022\r\n\tPOINTSI"
+ "ZE\020\030\022\r\n\tLINEWIDTH\020\031\"Z\n\010Obstacle\022\t\n\001x\030\001 \001"
+ "(\002\022\t\n\001y\030\002 \001(\002\022\t\n\001z\030\003 \001(\002\022\016\n\006length\030\004 \001(\002"
+ "\022\r\n\005width\030\005 \001(\002\022\016\n\006height\030\006 \001(\002\"O\n\014Obsta"
+ "cleList\022\036\n\006header\030\001 \002(\0132\016.px.HeaderInfo\022"
+ "\037\n\tobstacles\030\002 \003(\0132\014.px.Obstacle\"\271\001\n\013Obs"
+ "tacleMap\022\036\n\006header\030\001 \002(\0132\016.px.HeaderInfo"
+ "\022\014\n\004type\030\002 \002(\005\022\022\n\nresolution\030\003 \001(\002\022\014\n\004ro"
+ "ws\030\004 \001(\005\022\014\n\004cols\030\005 \001(\005\022\r\n\005mapR0\030\006 \001(\005\022\r\n"
+ "\005mapC0\030\007 \001(\005\022\017\n\007arrayR0\030\010 \001(\005\022\017\n\007arrayC0"
+ "\030\t \001(\005\022\014\n\004data\030\n \001(\014\"G\n\004Path\022\036\n\006header\030\001"
+ " \002(\0132\016.px.HeaderInfo\022\037\n\twaypoints\030\002 \003(\0132"
+ "\014.px.Waypoint\"\237\001\n\016PointCloudXYZI\022\036\n\006head"
+ "er\030\001 \002(\0132\016.px.HeaderInfo\022,\n\006points\030\002 \003(\013"
+ "2\034.px.PointCloudXYZI.PointXYZI\032\?\n\tPointX"
+ "YZI\022\t\n\001x\030\001 \002(\002\022\t\n\001y\030\002 \002(\002\022\t\n\001z\030\003 \002(\002\022\021\n\t"
+ "intensity\030\004 \002(\002\"\241\001\n\020PointCloudXYZRGB\022\036\n\006"
+ "header\030\001 \002(\0132\016.px.HeaderInfo\0220\n\006points\030\002"
+ " \003(\0132 .px.PointCloudXYZRGB.PointXYZRGB\032;"
+ "\n\013PointXYZRGB\022\t\n\001x\030\001 \002(\002\022\t\n\001y\030\002 \002(\002\022\t\n\001z"
+ "\030\003 \002(\002\022\013\n\003rgb\030\004 \002(\002\"\365\002\n\tRGBDImage\022\036\n\006hea"
+ "der\030\001 \002(\0132\016.px.HeaderInfo\022\014\n\004cols\030\002 \002(\r\022"
+ "\014\n\004rows\030\003 \002(\r\022\r\n\005step1\030\004 \002(\r\022\r\n\005type1\030\005 "
+ "\002(\r\022\022\n\nimageData1\030\006 \002(\014\022\r\n\005step2\030\007 \002(\r\022\r"
+ "\n\005type2\030\010 \002(\r\022\022\n\nimageData2\030\t \002(\014\022\025\n\rcam"
+ "era_config\030\n \001(\r\022\023\n\013camera_type\030\013 \001(\r\022\014\n"
+ "\004roll\030\014 \001(\002\022\r\n\005pitch\030\r \001(\002\022\013\n\003yaw\030\016 \001(\002\022"
+ "\013\n\003lon\030\017 \001(\002\022\013\n\003lat\030\020 \001(\002\022\013\n\003alt\030\021 \001(\002\022\020"
+ "\n\010ground_x\030\022 \001(\002\022\020\n\010ground_y\030\023 \001(\002\022\020\n\010gr"
+ "ound_z\030\024 \001(\002\022\025\n\rcamera_matrix\030\025 \003(\002\"U\n\010W"
+ "aypoint\022\t\n\001x\030\001 \002(\001\022\t\n\001y\030\002 \002(\001\022\t\n\001z\030\003 \001(\001"
+ "\022\014\n\004roll\030\004 \001(\001\022\r\n\005pitch\030\005 \001(\001\022\013\n\003yaw\030\006 \001"
+ "(\001", 1962);
+ ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile(
+ "pixhawk.proto", &protobuf_RegisterTypes);
+ HeaderInfo::default_instance_ = new HeaderInfo();
+ GLOverlay::default_instance_ = new GLOverlay();
+ Obstacle::default_instance_ = new Obstacle();
+ ObstacleList::default_instance_ = new ObstacleList();
+ ObstacleMap::default_instance_ = new ObstacleMap();
+ Path::default_instance_ = new Path();
+ PointCloudXYZI::default_instance_ = new PointCloudXYZI();
+ PointCloudXYZI_PointXYZI::default_instance_ = new PointCloudXYZI_PointXYZI();
+ PointCloudXYZRGB::default_instance_ = new PointCloudXYZRGB();
+ PointCloudXYZRGB_PointXYZRGB::default_instance_ = new PointCloudXYZRGB_PointXYZRGB();
+ RGBDImage::default_instance_ = new RGBDImage();
+ Waypoint::default_instance_ = new Waypoint();
+ HeaderInfo::default_instance_->InitAsDefaultInstance();
+ GLOverlay::default_instance_->InitAsDefaultInstance();
+ Obstacle::default_instance_->InitAsDefaultInstance();
+ ObstacleList::default_instance_->InitAsDefaultInstance();
+ ObstacleMap::default_instance_->InitAsDefaultInstance();
+ Path::default_instance_->InitAsDefaultInstance();
+ PointCloudXYZI::default_instance_->InitAsDefaultInstance();
+ PointCloudXYZI_PointXYZI::default_instance_->InitAsDefaultInstance();
+ PointCloudXYZRGB::default_instance_->InitAsDefaultInstance();
+ PointCloudXYZRGB_PointXYZRGB::default_instance_->InitAsDefaultInstance();
+ RGBDImage::default_instance_->InitAsDefaultInstance();
+ Waypoint::default_instance_->InitAsDefaultInstance();
+ ::google::protobuf::internal::OnShutdown(&protobuf_ShutdownFile_pixhawk_2eproto);
+}
+
+// Force AddDescriptors() to be called at static initialization time.
+struct StaticDescriptorInitializer_pixhawk_2eproto {
+ StaticDescriptorInitializer_pixhawk_2eproto() {
+ protobuf_AddDesc_pixhawk_2eproto();
+ }
+} static_descriptor_initializer_pixhawk_2eproto_;
+
+
+// ===================================================================
+
+#ifndef _MSC_VER
+const int HeaderInfo::kSourceSysidFieldNumber;
+const int HeaderInfo::kSourceCompidFieldNumber;
+const int HeaderInfo::kTimestampFieldNumber;
+#endif // !_MSC_VER
+
+HeaderInfo::HeaderInfo()
+ : ::google::protobuf::Message() {
+ SharedCtor();
+}
+
+void HeaderInfo::InitAsDefaultInstance() {
+}
+
+HeaderInfo::HeaderInfo(const HeaderInfo& from)
+ : ::google::protobuf::Message() {
+ SharedCtor();
+ MergeFrom(from);
+}
+
+void HeaderInfo::SharedCtor() {
+ _cached_size_ = 0;
+ source_sysid_ = 0;
+ source_compid_ = 0;
+ timestamp_ = 0;
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+}
+
+HeaderInfo::~HeaderInfo() {
+ SharedDtor();
+}
+
+void HeaderInfo::SharedDtor() {
+ if (this != default_instance_) {
+ }
+}
+
+void HeaderInfo::SetCachedSize(int size) const {
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+}
+const ::google::protobuf::Descriptor* HeaderInfo::descriptor() {
+ protobuf_AssignDescriptorsOnce();
+ return HeaderInfo_descriptor_;
+}
+
+const HeaderInfo& HeaderInfo::default_instance() {
+ if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
+}
+
+HeaderInfo* HeaderInfo::default_instance_ = NULL;
+
+HeaderInfo* HeaderInfo::New() const {
+ return new HeaderInfo;
+}
+
+void HeaderInfo::Clear() {
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ source_sysid_ = 0;
+ source_compid_ = 0;
+ timestamp_ = 0;
+ }
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+ mutable_unknown_fields()->Clear();
+}
+
+bool HeaderInfo::MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input) {
+#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
+ ::google::protobuf::uint32 tag;
+ while ((tag = input->ReadTag()) != 0) {
+ switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
+ // required int32 source_sysid = 1;
+ case 1: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>(
+ input, &source_sysid_)));
+ set_has_source_sysid();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(16)) goto parse_source_compid;
+ break;
+ }
+
+ // required int32 source_compid = 2;
+ case 2: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ parse_source_compid:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>(
+ input, &source_compid_)));
+ set_has_source_compid();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(25)) goto parse_timestamp;
+ break;
+ }
+
+ // required double timestamp = 3;
+ case 3: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
+ parse_timestamp:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
+ input, &timestamp_)));
+ set_has_timestamp();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectAtEnd()) return true;
+ break;
+ }
+
+ default: {
+ handle_uninterpreted:
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
+ return true;
+ }
+ DO_(::google::protobuf::internal::WireFormat::SkipField(
+ input, tag, mutable_unknown_fields()));
+ break;
+ }
+ }
+ }
+ return true;
+#undef DO_
+}
+
+void HeaderInfo::SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const {
+ // required int32 source_sysid = 1;
+ if (has_source_sysid()) {
+ ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->source_sysid(), output);
+ }
+
+ // required int32 source_compid = 2;
+ if (has_source_compid()) {
+ ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->source_compid(), output);
+ }
+
+ // required double timestamp = 3;
+ if (has_timestamp()) {
+ ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->timestamp(), output);
+ }
+
+ if (!unknown_fields().empty()) {
+ ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
+ unknown_fields(), output);
+ }
+}
+
+::google::protobuf::uint8* HeaderInfo::SerializeWithCachedSizesToArray(
+ ::google::protobuf::uint8* target) const {
+ // required int32 source_sysid = 1;
+ if (has_source_sysid()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->source_sysid(), target);
+ }
+
+ // required int32 source_compid = 2;
+ if (has_source_compid()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->source_compid(), target);
+ }
+
+ // required double timestamp = 3;
+ if (has_timestamp()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->timestamp(), target);
+ }
+
+ if (!unknown_fields().empty()) {
+ target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
+ unknown_fields(), target);
+ }
+ return target;
+}
+
+int HeaderInfo::ByteSize() const {
+ int total_size = 0;
+
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ // required int32 source_sysid = 1;
+ if (has_source_sysid()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::Int32Size(
+ this->source_sysid());
+ }
+
+ // required int32 source_compid = 2;
+ if (has_source_compid()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::Int32Size(
+ this->source_compid());
+ }
+
+ // required double timestamp = 3;
+ if (has_timestamp()) {
+ total_size += 1 + 8;
+ }
+
+ }
+ if (!unknown_fields().empty()) {
+ total_size +=
+ ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
+ unknown_fields());
+ }
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = total_size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+ return total_size;
+}
+
+void HeaderInfo::MergeFrom(const ::google::protobuf::Message& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ const HeaderInfo* source =
+ ::google::protobuf::internal::dynamic_cast_if_available<const HeaderInfo*>(
+ &from);
+ if (source == NULL) {
+ ::google::protobuf::internal::ReflectionOps::Merge(from, this);
+ } else {
+ MergeFrom(*source);
+ }
+}
+
+void HeaderInfo::MergeFrom(const HeaderInfo& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (from.has_source_sysid()) {
+ set_source_sysid(from.source_sysid());
+ }
+ if (from.has_source_compid()) {
+ set_source_compid(from.source_compid());
+ }
+ if (from.has_timestamp()) {
+ set_timestamp(from.timestamp());
+ }
+ }
+ mutable_unknown_fields()->MergeFrom(from.unknown_fields());
+}
+
+void HeaderInfo::CopyFrom(const ::google::protobuf::Message& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+void HeaderInfo::CopyFrom(const HeaderInfo& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+bool HeaderInfo::IsInitialized() const {
+ if ((_has_bits_[0] & 0x00000007) != 0x00000007) return false;
+
+ return true;
+}
+
+void HeaderInfo::Swap(HeaderInfo* other) {
+ if (other != this) {
+ std::swap(source_sysid_, other->source_sysid_);
+ std::swap(source_compid_, other->source_compid_);
+ std::swap(timestamp_, other->timestamp_);
+ std::swap(_has_bits_[0], other->_has_bits_[0]);
+ _unknown_fields_.Swap(&other->_unknown_fields_);
+ std::swap(_cached_size_, other->_cached_size_);
+ }
+}
+
+::google::protobuf::Metadata HeaderInfo::GetMetadata() const {
+ protobuf_AssignDescriptorsOnce();
+ ::google::protobuf::Metadata metadata;
+ metadata.descriptor = HeaderInfo_descriptor_;
+ metadata.reflection = HeaderInfo_reflection_;
+ return metadata;
+}
+
+
+// ===================================================================
+
+const ::google::protobuf::EnumDescriptor* GLOverlay_CoordinateFrameType_descriptor() {
+ protobuf_AssignDescriptorsOnce();
+ return GLOverlay_CoordinateFrameType_descriptor_;
+}
+bool GLOverlay_CoordinateFrameType_IsValid(int value) {
+ switch(value) {
+ case 0:
+ case 1:
+ return true;
+ default:
+ return false;
+ }
+}
+
+#ifndef _MSC_VER
+const GLOverlay_CoordinateFrameType GLOverlay::GLOBAL;
+const GLOverlay_CoordinateFrameType GLOverlay::LOCAL;
+const GLOverlay_CoordinateFrameType GLOverlay::CoordinateFrameType_MIN;
+const GLOverlay_CoordinateFrameType GLOverlay::CoordinateFrameType_MAX;
+const int GLOverlay::CoordinateFrameType_ARRAYSIZE;
+#endif // _MSC_VER
+const ::google::protobuf::EnumDescriptor* GLOverlay_Mode_descriptor() {
+ protobuf_AssignDescriptorsOnce();
+ return GLOverlay_Mode_descriptor_;
+}
+bool GLOverlay_Mode_IsValid(int value) {
+ switch(value) {
+ case 0:
+ case 1:
+ case 2:
+ case 3:
+ case 4:
+ case 5:
+ case 6:
+ case 7:
+ case 8:
+ case 9:
+ case 10:
+ case 11:
+ case 12:
+ case 13:
+ return true;
+ default:
+ return false;
+ }
+}
+
+#ifndef _MSC_VER
+const GLOverlay_Mode GLOverlay::POINTS;
+const GLOverlay_Mode GLOverlay::LINES;
+const GLOverlay_Mode GLOverlay::LINE_STRIP;
+const GLOverlay_Mode GLOverlay::LINE_LOOP;
+const GLOverlay_Mode GLOverlay::TRIANGLES;
+const GLOverlay_Mode GLOverlay::TRIANGLE_STRIP;
+const GLOverlay_Mode GLOverlay::TRIANGLE_FAN;
+const GLOverlay_Mode GLOverlay::QUADS;
+const GLOverlay_Mode GLOverlay::QUAD_STRIP;
+const GLOverlay_Mode GLOverlay::POLYGON;
+const GLOverlay_Mode GLOverlay::SOLID_CIRCLE;
+const GLOverlay_Mode GLOverlay::WIRE_CIRCLE;
+const GLOverlay_Mode GLOverlay::SOLID_CUBE;
+const GLOverlay_Mode GLOverlay::WIRE_CUBE;
+const GLOverlay_Mode GLOverlay::Mode_MIN;
+const GLOverlay_Mode GLOverlay::Mode_MAX;
+const int GLOverlay::Mode_ARRAYSIZE;
+#endif // _MSC_VER
+const ::google::protobuf::EnumDescriptor* GLOverlay_Identifier_descriptor() {
+ protobuf_AssignDescriptorsOnce();
+ return GLOverlay_Identifier_descriptor_;
+}
+bool GLOverlay_Identifier_IsValid(int value) {
+ switch(value) {
+ case 14:
+ case 15:
+ case 16:
+ case 17:
+ case 18:
+ case 19:
+ case 20:
+ case 21:
+ case 22:
+ case 23:
+ case 24:
+ case 25:
+ return true;
+ default:
+ return false;
+ }
+}
+
+#ifndef _MSC_VER
+const GLOverlay_Identifier GLOverlay::END;
+const GLOverlay_Identifier GLOverlay::VERTEX2F;
+const GLOverlay_Identifier GLOverlay::VERTEX3F;
+const GLOverlay_Identifier GLOverlay::ROTATEF;
+const GLOverlay_Identifier GLOverlay::TRANSLATEF;
+const GLOverlay_Identifier GLOverlay::SCALEF;
+const GLOverlay_Identifier GLOverlay::PUSH_MATRIX;
+const GLOverlay_Identifier GLOverlay::POP_MATRIX;
+const GLOverlay_Identifier GLOverlay::COLOR3F;
+const GLOverlay_Identifier GLOverlay::COLOR4F;
+const GLOverlay_Identifier GLOverlay::POINTSIZE;
+const GLOverlay_Identifier GLOverlay::LINEWIDTH;
+const GLOverlay_Identifier GLOverlay::Identifier_MIN;
+const GLOverlay_Identifier GLOverlay::Identifier_MAX;
+const int GLOverlay::Identifier_ARRAYSIZE;
+#endif // _MSC_VER
+#ifndef _MSC_VER
+const int GLOverlay::kHeaderFieldNumber;
+const int GLOverlay::kNameFieldNumber;
+const int GLOverlay::kCoordinateFrameTypeFieldNumber;
+const int GLOverlay::kOriginXFieldNumber;
+const int GLOverlay::kOriginYFieldNumber;
+const int GLOverlay::kOriginZFieldNumber;
+const int GLOverlay::kDataFieldNumber;
+#endif // !_MSC_VER
+
+GLOverlay::GLOverlay()
+ : ::google::protobuf::Message() {
+ SharedCtor();
+}
+
+void GLOverlay::InitAsDefaultInstance() {
+ header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance());
+}
+
+GLOverlay::GLOverlay(const GLOverlay& from)
+ : ::google::protobuf::Message() {
+ SharedCtor();
+ MergeFrom(from);
+}
+
+void GLOverlay::SharedCtor() {
+ _cached_size_ = 0;
+ header_ = NULL;
+ name_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
+ coordinateframetype_ = 0;
+ origin_x_ = 0;
+ origin_y_ = 0;
+ origin_z_ = 0;
+ data_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+}
+
+GLOverlay::~GLOverlay() {
+ SharedDtor();
+}
+
+void GLOverlay::SharedDtor() {
+ if (name_ != &::google::protobuf::internal::kEmptyString) {
+ delete name_;
+ }
+ if (data_ != &::google::protobuf::internal::kEmptyString) {
+ delete data_;
+ }
+ if (this != default_instance_) {
+ delete header_;
+ }
+}
+
+void GLOverlay::SetCachedSize(int size) const {
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+}
+const ::google::protobuf::Descriptor* GLOverlay::descriptor() {
+ protobuf_AssignDescriptorsOnce();
+ return GLOverlay_descriptor_;
+}
+
+const GLOverlay& GLOverlay::default_instance() {
+ if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
+}
+
+GLOverlay* GLOverlay::default_instance_ = NULL;
+
+GLOverlay* GLOverlay::New() const {
+ return new GLOverlay;
+}
+
+void GLOverlay::Clear() {
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (has_header()) {
+ if (header_ != NULL) header_->::px::HeaderInfo::Clear();
+ }
+ if (has_name()) {
+ if (name_ != &::google::protobuf::internal::kEmptyString) {
+ name_->clear();
+ }
+ }
+ coordinateframetype_ = 0;
+ origin_x_ = 0;
+ origin_y_ = 0;
+ origin_z_ = 0;
+ if (has_data()) {
+ if (data_ != &::google::protobuf::internal::kEmptyString) {
+ data_->clear();
+ }
+ }
+ }
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+ mutable_unknown_fields()->Clear();
+}
+
+bool GLOverlay::MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input) {
+#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
+ ::google::protobuf::uint32 tag;
+ while ((tag = input->ReadTag()) != 0) {
+ switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
+ // required .px.HeaderInfo header = 1;
+ case 1: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
+ DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
+ input, mutable_header()));
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(18)) goto parse_name;
+ break;
+ }
+
+ // optional string name = 2;
+ case 2: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
+ parse_name:
+ DO_(::google::protobuf::internal::WireFormatLite::ReadString(
+ input, this->mutable_name()));
+ ::google::protobuf::internal::WireFormat::VerifyUTF8String(
+ this->name().data(), this->name().length(),
+ ::google::protobuf::internal::WireFormat::PARSE);
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(24)) goto parse_coordinateFrameType;
+ break;
+ }
+
+ // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3;
+ case 3: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ parse_coordinateFrameType:
+ int value;
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>(
+ input, &value)));
+ if (::px::GLOverlay_CoordinateFrameType_IsValid(value)) {
+ set_coordinateframetype(static_cast< ::px::GLOverlay_CoordinateFrameType >(value));
+ } else {
+ mutable_unknown_fields()->AddVarint(3, value);
+ }
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(33)) goto parse_origin_x;
+ break;
+ }
+
+ // optional double origin_x = 4;
+ case 4: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
+ parse_origin_x:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
+ input, &origin_x_)));
+ set_has_origin_x();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(41)) goto parse_origin_y;
+ break;
+ }
+
+ // optional double origin_y = 5;
+ case 5: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
+ parse_origin_y:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
+ input, &origin_y_)));
+ set_has_origin_y();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(49)) goto parse_origin_z;
+ break;
+ }
+
+ // optional double origin_z = 6;
+ case 6: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
+ parse_origin_z:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
+ input, &origin_z_)));
+ set_has_origin_z();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(58)) goto parse_data;
+ break;
+ }
+
+ // optional bytes data = 7;
+ case 7: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
+ parse_data:
+ DO_(::google::protobuf::internal::WireFormatLite::ReadBytes(
+ input, this->mutable_data()));
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectAtEnd()) return true;
+ break;
+ }
+
+ default: {
+ handle_uninterpreted:
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
+ return true;
+ }
+ DO_(::google::protobuf::internal::WireFormat::SkipField(
+ input, tag, mutable_unknown_fields()));
+ break;
+ }
+ }
+ }
+ return true;
+#undef DO_
+}
+
+void GLOverlay::SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
+ 1, this->header(), output);
+ }
+
+ // optional string name = 2;
+ if (has_name()) {
+ ::google::protobuf::internal::WireFormat::VerifyUTF8String(
+ this->name().data(), this->name().length(),
+ ::google::protobuf::internal::WireFormat::SERIALIZE);
+ ::google::protobuf::internal::WireFormatLite::WriteString(
+ 2, this->name(), output);
+ }
+
+ // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3;
+ if (has_coordinateframetype()) {
+ ::google::protobuf::internal::WireFormatLite::WriteEnum(
+ 3, this->coordinateframetype(), output);
+ }
+
+ // optional double origin_x = 4;
+ if (has_origin_x()) {
+ ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->origin_x(), output);
+ }
+
+ // optional double origin_y = 5;
+ if (has_origin_y()) {
+ ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->origin_y(), output);
+ }
+
+ // optional double origin_z = 6;
+ if (has_origin_z()) {
+ ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->origin_z(), output);
+ }
+
+ // optional bytes data = 7;
+ if (has_data()) {
+ ::google::protobuf::internal::WireFormatLite::WriteBytes(
+ 7, this->data(), output);
+ }
+
+ if (!unknown_fields().empty()) {
+ ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
+ unknown_fields(), output);
+ }
+}
+
+::google::protobuf::uint8* GLOverlay::SerializeWithCachedSizesToArray(
+ ::google::protobuf::uint8* target) const {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ target = ::google::protobuf::internal::WireFormatLite::
+ WriteMessageNoVirtualToArray(
+ 1, this->header(), target);
+ }
+
+ // optional string name = 2;
+ if (has_name()) {
+ ::google::protobuf::internal::WireFormat::VerifyUTF8String(
+ this->name().data(), this->name().length(),
+ ::google::protobuf::internal::WireFormat::SERIALIZE);
+ target =
+ ::google::protobuf::internal::WireFormatLite::WriteStringToArray(
+ 2, this->name(), target);
+ }
+
+ // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3;
+ if (has_coordinateframetype()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray(
+ 3, this->coordinateframetype(), target);
+ }
+
+ // optional double origin_x = 4;
+ if (has_origin_x()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->origin_x(), target);
+ }
+
+ // optional double origin_y = 5;
+ if (has_origin_y()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->origin_y(), target);
+ }
+
+ // optional double origin_z = 6;
+ if (has_origin_z()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->origin_z(), target);
+ }
+
+ // optional bytes data = 7;
+ if (has_data()) {
+ target =
+ ::google::protobuf::internal::WireFormatLite::WriteBytesToArray(
+ 7, this->data(), target);
+ }
+
+ if (!unknown_fields().empty()) {
+ target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
+ unknown_fields(), target);
+ }
+ return target;
+}
+
+int GLOverlay::ByteSize() const {
+ int total_size = 0;
+
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ this->header());
+ }
+
+ // optional string name = 2;
+ if (has_name()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::StringSize(
+ this->name());
+ }
+
+ // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3;
+ if (has_coordinateframetype()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::EnumSize(this->coordinateframetype());
+ }
+
+ // optional double origin_x = 4;
+ if (has_origin_x()) {
+ total_size += 1 + 8;
+ }
+
+ // optional double origin_y = 5;
+ if (has_origin_y()) {
+ total_size += 1 + 8;
+ }
+
+ // optional double origin_z = 6;
+ if (has_origin_z()) {
+ total_size += 1 + 8;
+ }
+
+ // optional bytes data = 7;
+ if (has_data()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::BytesSize(
+ this->data());
+ }
+
+ }
+ if (!unknown_fields().empty()) {
+ total_size +=
+ ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
+ unknown_fields());
+ }
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = total_size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+ return total_size;
+}
+
+void GLOverlay::MergeFrom(const ::google::protobuf::Message& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ const GLOverlay* source =
+ ::google::protobuf::internal::dynamic_cast_if_available<const GLOverlay*>(
+ &from);
+ if (source == NULL) {
+ ::google::protobuf::internal::ReflectionOps::Merge(from, this);
+ } else {
+ MergeFrom(*source);
+ }
+}
+
+void GLOverlay::MergeFrom(const GLOverlay& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (from.has_header()) {
+ mutable_header()->::px::HeaderInfo::MergeFrom(from.header());
+ }
+ if (from.has_name()) {
+ set_name(from.name());
+ }
+ if (from.has_coordinateframetype()) {
+ set_coordinateframetype(from.coordinateframetype());
+ }
+ if (from.has_origin_x()) {
+ set_origin_x(from.origin_x());
+ }
+ if (from.has_origin_y()) {
+ set_origin_y(from.origin_y());
+ }
+ if (from.has_origin_z()) {
+ set_origin_z(from.origin_z());
+ }
+ if (from.has_data()) {
+ set_data(from.data());
+ }
+ }
+ mutable_unknown_fields()->MergeFrom(from.unknown_fields());
+}
+
+void GLOverlay::CopyFrom(const ::google::protobuf::Message& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+void GLOverlay::CopyFrom(const GLOverlay& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+bool GLOverlay::IsInitialized() const {
+ if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false;
+
+ if (has_header()) {
+ if (!this->header().IsInitialized()) return false;
+ }
+ return true;
+}
+
+void GLOverlay::Swap(GLOverlay* other) {
+ if (other != this) {
+ std::swap(header_, other->header_);
+ std::swap(name_, other->name_);
+ std::swap(coordinateframetype_, other->coordinateframetype_);
+ std::swap(origin_x_, other->origin_x_);
+ std::swap(origin_y_, other->origin_y_);
+ std::swap(origin_z_, other->origin_z_);
+ std::swap(data_, other->data_);
+ std::swap(_has_bits_[0], other->_has_bits_[0]);
+ _unknown_fields_.Swap(&other->_unknown_fields_);
+ std::swap(_cached_size_, other->_cached_size_);
+ }
+}
+
+::google::protobuf::Metadata GLOverlay::GetMetadata() const {
+ protobuf_AssignDescriptorsOnce();
+ ::google::protobuf::Metadata metadata;
+ metadata.descriptor = GLOverlay_descriptor_;
+ metadata.reflection = GLOverlay_reflection_;
+ return metadata;
+}
+
+
+// ===================================================================
+
+#ifndef _MSC_VER
+const int Obstacle::kXFieldNumber;
+const int Obstacle::kYFieldNumber;
+const int Obstacle::kZFieldNumber;
+const int Obstacle::kLengthFieldNumber;
+const int Obstacle::kWidthFieldNumber;
+const int Obstacle::kHeightFieldNumber;
+#endif // !_MSC_VER
+
+Obstacle::Obstacle()
+ : ::google::protobuf::Message() {
+ SharedCtor();
+}
+
+void Obstacle::InitAsDefaultInstance() {
+}
+
+Obstacle::Obstacle(const Obstacle& from)
+ : ::google::protobuf::Message() {
+ SharedCtor();
+ MergeFrom(from);
+}
+
+void Obstacle::SharedCtor() {
+ _cached_size_ = 0;
+ x_ = 0;
+ y_ = 0;
+ z_ = 0;
+ length_ = 0;
+ width_ = 0;
+ height_ = 0;
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+}
+
+Obstacle::~Obstacle() {
+ SharedDtor();
+}
+
+void Obstacle::SharedDtor() {
+ if (this != default_instance_) {
+ }
+}
+
+void Obstacle::SetCachedSize(int size) const {
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+}
+const ::google::protobuf::Descriptor* Obstacle::descriptor() {
+ protobuf_AssignDescriptorsOnce();
+ return Obstacle_descriptor_;
+}
+
+const Obstacle& Obstacle::default_instance() {
+ if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
+}
+
+Obstacle* Obstacle::default_instance_ = NULL;
+
+Obstacle* Obstacle::New() const {
+ return new Obstacle;
+}
+
+void Obstacle::Clear() {
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ x_ = 0;
+ y_ = 0;
+ z_ = 0;
+ length_ = 0;
+ width_ = 0;
+ height_ = 0;
+ }
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+ mutable_unknown_fields()->Clear();
+}
+
+bool Obstacle::MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input) {
+#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
+ ::google::protobuf::uint32 tag;
+ while ((tag = input->ReadTag()) != 0) {
+ switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
+ // optional float x = 1;
+ case 1: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &x_)));
+ set_has_x();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(21)) goto parse_y;
+ break;
+ }
+
+ // optional float y = 2;
+ case 2: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_y:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &y_)));
+ set_has_y();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(29)) goto parse_z;
+ break;
+ }
+
+ // optional float z = 3;
+ case 3: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_z:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &z_)));
+ set_has_z();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(37)) goto parse_length;
+ break;
+ }
+
+ // optional float length = 4;
+ case 4: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_length:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &length_)));
+ set_has_length();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(45)) goto parse_width;
+ break;
+ }
+
+ // optional float width = 5;
+ case 5: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_width:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &width_)));
+ set_has_width();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(53)) goto parse_height;
+ break;
+ }
+
+ // optional float height = 6;
+ case 6: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_height:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &height_)));
+ set_has_height();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectAtEnd()) return true;
+ break;
+ }
+
+ default: {
+ handle_uninterpreted:
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
+ return true;
+ }
+ DO_(::google::protobuf::internal::WireFormat::SkipField(
+ input, tag, mutable_unknown_fields()));
+ break;
+ }
+ }
+ }
+ return true;
+#undef DO_
+}
+
+void Obstacle::SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const {
+ // optional float x = 1;
+ if (has_x()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->x(), output);
+ }
+
+ // optional float y = 2;
+ if (has_y()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->y(), output);
+ }
+
+ // optional float z = 3;
+ if (has_z()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->z(), output);
+ }
+
+ // optional float length = 4;
+ if (has_length()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->length(), output);
+ }
+
+ // optional float width = 5;
+ if (has_width()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(5, this->width(), output);
+ }
+
+ // optional float height = 6;
+ if (has_height()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(6, this->height(), output);
+ }
+
+ if (!unknown_fields().empty()) {
+ ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
+ unknown_fields(), output);
+ }
+}
+
+::google::protobuf::uint8* Obstacle::SerializeWithCachedSizesToArray(
+ ::google::protobuf::uint8* target) const {
+ // optional float x = 1;
+ if (has_x()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->x(), target);
+ }
+
+ // optional float y = 2;
+ if (has_y()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->y(), target);
+ }
+
+ // optional float z = 3;
+ if (has_z()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->z(), target);
+ }
+
+ // optional float length = 4;
+ if (has_length()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->length(), target);
+ }
+
+ // optional float width = 5;
+ if (has_width()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(5, this->width(), target);
+ }
+
+ // optional float height = 6;
+ if (has_height()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(6, this->height(), target);
+ }
+
+ if (!unknown_fields().empty()) {
+ target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
+ unknown_fields(), target);
+ }
+ return target;
+}
+
+int Obstacle::ByteSize() const {
+ int total_size = 0;
+
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ // optional float x = 1;
+ if (has_x()) {
+ total_size += 1 + 4;
+ }
+
+ // optional float y = 2;
+ if (has_y()) {
+ total_size += 1 + 4;
+ }
+
+ // optional float z = 3;
+ if (has_z()) {
+ total_size += 1 + 4;
+ }
+
+ // optional float length = 4;
+ if (has_length()) {
+ total_size += 1 + 4;
+ }
+
+ // optional float width = 5;
+ if (has_width()) {
+ total_size += 1 + 4;
+ }
+
+ // optional float height = 6;
+ if (has_height()) {
+ total_size += 1 + 4;
+ }
+
+ }
+ if (!unknown_fields().empty()) {
+ total_size +=
+ ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
+ unknown_fields());
+ }
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = total_size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+ return total_size;
+}
+
+void Obstacle::MergeFrom(const ::google::protobuf::Message& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ const Obstacle* source =
+ ::google::protobuf::internal::dynamic_cast_if_available<const Obstacle*>(
+ &from);
+ if (source == NULL) {
+ ::google::protobuf::internal::ReflectionOps::Merge(from, this);
+ } else {
+ MergeFrom(*source);
+ }
+}
+
+void Obstacle::MergeFrom(const Obstacle& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (from.has_x()) {
+ set_x(from.x());
+ }
+ if (from.has_y()) {
+ set_y(from.y());
+ }
+ if (from.has_z()) {
+ set_z(from.z());
+ }
+ if (from.has_length()) {
+ set_length(from.length());
+ }
+ if (from.has_width()) {
+ set_width(from.width());
+ }
+ if (from.has_height()) {
+ set_height(from.height());
+ }
+ }
+ mutable_unknown_fields()->MergeFrom(from.unknown_fields());
+}
+
+void Obstacle::CopyFrom(const ::google::protobuf::Message& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+void Obstacle::CopyFrom(const Obstacle& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+bool Obstacle::IsInitialized() const {
+
+ return true;
+}
+
+void Obstacle::Swap(Obstacle* other) {
+ if (other != this) {
+ std::swap(x_, other->x_);
+ std::swap(y_, other->y_);
+ std::swap(z_, other->z_);
+ std::swap(length_, other->length_);
+ std::swap(width_, other->width_);
+ std::swap(height_, other->height_);
+ std::swap(_has_bits_[0], other->_has_bits_[0]);
+ _unknown_fields_.Swap(&other->_unknown_fields_);
+ std::swap(_cached_size_, other->_cached_size_);
+ }
+}
+
+::google::protobuf::Metadata Obstacle::GetMetadata() const {
+ protobuf_AssignDescriptorsOnce();
+ ::google::protobuf::Metadata metadata;
+ metadata.descriptor = Obstacle_descriptor_;
+ metadata.reflection = Obstacle_reflection_;
+ return metadata;
+}
+
+
+// ===================================================================
+
+#ifndef _MSC_VER
+const int ObstacleList::kHeaderFieldNumber;
+const int ObstacleList::kObstaclesFieldNumber;
+#endif // !_MSC_VER
+
+ObstacleList::ObstacleList()
+ : ::google::protobuf::Message() {
+ SharedCtor();
+}
+
+void ObstacleList::InitAsDefaultInstance() {
+ header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance());
+}
+
+ObstacleList::ObstacleList(const ObstacleList& from)
+ : ::google::protobuf::Message() {
+ SharedCtor();
+ MergeFrom(from);
+}
+
+void ObstacleList::SharedCtor() {
+ _cached_size_ = 0;
+ header_ = NULL;
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+}
+
+ObstacleList::~ObstacleList() {
+ SharedDtor();
+}
+
+void ObstacleList::SharedDtor() {
+ if (this != default_instance_) {
+ delete header_;
+ }
+}
+
+void ObstacleList::SetCachedSize(int size) const {
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+}
+const ::google::protobuf::Descriptor* ObstacleList::descriptor() {
+ protobuf_AssignDescriptorsOnce();
+ return ObstacleList_descriptor_;
+}
+
+const ObstacleList& ObstacleList::default_instance() {
+ if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
+}
+
+ObstacleList* ObstacleList::default_instance_ = NULL;
+
+ObstacleList* ObstacleList::New() const {
+ return new ObstacleList;
+}
+
+void ObstacleList::Clear() {
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (has_header()) {
+ if (header_ != NULL) header_->::px::HeaderInfo::Clear();
+ }
+ }
+ obstacles_.Clear();
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+ mutable_unknown_fields()->Clear();
+}
+
+bool ObstacleList::MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input) {
+#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
+ ::google::protobuf::uint32 tag;
+ while ((tag = input->ReadTag()) != 0) {
+ switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
+ // required .px.HeaderInfo header = 1;
+ case 1: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
+ DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
+ input, mutable_header()));
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(18)) goto parse_obstacles;
+ break;
+ }
+
+ // repeated .px.Obstacle obstacles = 2;
+ case 2: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
+ parse_obstacles:
+ DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
+ input, add_obstacles()));
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(18)) goto parse_obstacles;
+ if (input->ExpectAtEnd()) return true;
+ break;
+ }
+
+ default: {
+ handle_uninterpreted:
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
+ return true;
+ }
+ DO_(::google::protobuf::internal::WireFormat::SkipField(
+ input, tag, mutable_unknown_fields()));
+ break;
+ }
+ }
+ }
+ return true;
+#undef DO_
+}
+
+void ObstacleList::SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
+ 1, this->header(), output);
+ }
+
+ // repeated .px.Obstacle obstacles = 2;
+ for (int i = 0; i < this->obstacles_size(); i++) {
+ ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
+ 2, this->obstacles(i), output);
+ }
+
+ if (!unknown_fields().empty()) {
+ ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
+ unknown_fields(), output);
+ }
+}
+
+::google::protobuf::uint8* ObstacleList::SerializeWithCachedSizesToArray(
+ ::google::protobuf::uint8* target) const {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ target = ::google::protobuf::internal::WireFormatLite::
+ WriteMessageNoVirtualToArray(
+ 1, this->header(), target);
+ }
+
+ // repeated .px.Obstacle obstacles = 2;
+ for (int i = 0; i < this->obstacles_size(); i++) {
+ target = ::google::protobuf::internal::WireFormatLite::
+ WriteMessageNoVirtualToArray(
+ 2, this->obstacles(i), target);
+ }
+
+ if (!unknown_fields().empty()) {
+ target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
+ unknown_fields(), target);
+ }
+ return target;
+}
+
+int ObstacleList::ByteSize() const {
+ int total_size = 0;
+
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ this->header());
+ }
+
+ }
+ // repeated .px.Obstacle obstacles = 2;
+ total_size += 1 * this->obstacles_size();
+ for (int i = 0; i < this->obstacles_size(); i++) {
+ total_size +=
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ this->obstacles(i));
+ }
+
+ if (!unknown_fields().empty()) {
+ total_size +=
+ ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
+ unknown_fields());
+ }
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = total_size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+ return total_size;
+}
+
+void ObstacleList::MergeFrom(const ::google::protobuf::Message& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ const ObstacleList* source =
+ ::google::protobuf::internal::dynamic_cast_if_available<const ObstacleList*>(
+ &from);
+ if (source == NULL) {
+ ::google::protobuf::internal::ReflectionOps::Merge(from, this);
+ } else {
+ MergeFrom(*source);
+ }
+}
+
+void ObstacleList::MergeFrom(const ObstacleList& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ obstacles_.MergeFrom(from.obstacles_);
+ if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (from.has_header()) {
+ mutable_header()->::px::HeaderInfo::MergeFrom(from.header());
+ }
+ }
+ mutable_unknown_fields()->MergeFrom(from.unknown_fields());
+}
+
+void ObstacleList::CopyFrom(const ::google::protobuf::Message& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+void ObstacleList::CopyFrom(const ObstacleList& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+bool ObstacleList::IsInitialized() const {
+ if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false;
+
+ if (has_header()) {
+ if (!this->header().IsInitialized()) return false;
+ }
+ return true;
+}
+
+void ObstacleList::Swap(ObstacleList* other) {
+ if (other != this) {
+ std::swap(header_, other->header_);
+ obstacles_.Swap(&other->obstacles_);
+ std::swap(_has_bits_[0], other->_has_bits_[0]);
+ _unknown_fields_.Swap(&other->_unknown_fields_);
+ std::swap(_cached_size_, other->_cached_size_);
+ }
+}
+
+::google::protobuf::Metadata ObstacleList::GetMetadata() const {
+ protobuf_AssignDescriptorsOnce();
+ ::google::protobuf::Metadata metadata;
+ metadata.descriptor = ObstacleList_descriptor_;
+ metadata.reflection = ObstacleList_reflection_;
+ return metadata;
+}
+
+
+// ===================================================================
+
+#ifndef _MSC_VER
+const int ObstacleMap::kHeaderFieldNumber;
+const int ObstacleMap::kTypeFieldNumber;
+const int ObstacleMap::kResolutionFieldNumber;
+const int ObstacleMap::kRowsFieldNumber;
+const int ObstacleMap::kColsFieldNumber;
+const int ObstacleMap::kMapR0FieldNumber;
+const int ObstacleMap::kMapC0FieldNumber;
+const int ObstacleMap::kArrayR0FieldNumber;
+const int ObstacleMap::kArrayC0FieldNumber;
+const int ObstacleMap::kDataFieldNumber;
+#endif // !_MSC_VER
+
+ObstacleMap::ObstacleMap()
+ : ::google::protobuf::Message() {
+ SharedCtor();
+}
+
+void ObstacleMap::InitAsDefaultInstance() {
+ header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance());
+}
+
+ObstacleMap::ObstacleMap(const ObstacleMap& from)
+ : ::google::protobuf::Message() {
+ SharedCtor();
+ MergeFrom(from);
+}
+
+void ObstacleMap::SharedCtor() {
+ _cached_size_ = 0;
+ header_ = NULL;
+ type_ = 0;
+ resolution_ = 0;
+ rows_ = 0;
+ cols_ = 0;
+ mapr0_ = 0;
+ mapc0_ = 0;
+ arrayr0_ = 0;
+ arrayc0_ = 0;
+ data_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+}
+
+ObstacleMap::~ObstacleMap() {
+ SharedDtor();
+}
+
+void ObstacleMap::SharedDtor() {
+ if (data_ != &::google::protobuf::internal::kEmptyString) {
+ delete data_;
+ }
+ if (this != default_instance_) {
+ delete header_;
+ }
+}
+
+void ObstacleMap::SetCachedSize(int size) const {
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+}
+const ::google::protobuf::Descriptor* ObstacleMap::descriptor() {
+ protobuf_AssignDescriptorsOnce();
+ return ObstacleMap_descriptor_;
+}
+
+const ObstacleMap& ObstacleMap::default_instance() {
+ if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
+}
+
+ObstacleMap* ObstacleMap::default_instance_ = NULL;
+
+ObstacleMap* ObstacleMap::New() const {
+ return new ObstacleMap;
+}
+
+void ObstacleMap::Clear() {
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (has_header()) {
+ if (header_ != NULL) header_->::px::HeaderInfo::Clear();
+ }
+ type_ = 0;
+ resolution_ = 0;
+ rows_ = 0;
+ cols_ = 0;
+ mapr0_ = 0;
+ mapc0_ = 0;
+ arrayr0_ = 0;
+ }
+ if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) {
+ arrayc0_ = 0;
+ if (has_data()) {
+ if (data_ != &::google::protobuf::internal::kEmptyString) {
+ data_->clear();
+ }
+ }
+ }
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+ mutable_unknown_fields()->Clear();
+}
+
+bool ObstacleMap::MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input) {
+#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
+ ::google::protobuf::uint32 tag;
+ while ((tag = input->ReadTag()) != 0) {
+ switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
+ // required .px.HeaderInfo header = 1;
+ case 1: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
+ DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
+ input, mutable_header()));
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(16)) goto parse_type;
+ break;
+ }
+
+ // required int32 type = 2;
+ case 2: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ parse_type:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>(
+ input, &type_)));
+ set_has_type();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(29)) goto parse_resolution;
+ break;
+ }
+
+ // optional float resolution = 3;
+ case 3: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_resolution:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &resolution_)));
+ set_has_resolution();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(32)) goto parse_rows;
+ break;
+ }
+
+ // optional int32 rows = 4;
+ case 4: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ parse_rows:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>(
+ input, &rows_)));
+ set_has_rows();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(40)) goto parse_cols;
+ break;
+ }
+
+ // optional int32 cols = 5;
+ case 5: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ parse_cols:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>(
+ input, &cols_)));
+ set_has_cols();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(48)) goto parse_mapR0;
+ break;
+ }
+
+ // optional int32 mapR0 = 6;
+ case 6: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ parse_mapR0:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>(
+ input, &mapr0_)));
+ set_has_mapr0();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(56)) goto parse_mapC0;
+ break;
+ }
+
+ // optional int32 mapC0 = 7;
+ case 7: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ parse_mapC0:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>(
+ input, &mapc0_)));
+ set_has_mapc0();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(64)) goto parse_arrayR0;
+ break;
+ }
+
+ // optional int32 arrayR0 = 8;
+ case 8: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ parse_arrayR0:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>(
+ input, &arrayr0_)));
+ set_has_arrayr0();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(72)) goto parse_arrayC0;
+ break;
+ }
+
+ // optional int32 arrayC0 = 9;
+ case 9: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ parse_arrayC0:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>(
+ input, &arrayc0_)));
+ set_has_arrayc0();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(82)) goto parse_data;
+ break;
+ }
+
+ // optional bytes data = 10;
+ case 10: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
+ parse_data:
+ DO_(::google::protobuf::internal::WireFormatLite::ReadBytes(
+ input, this->mutable_data()));
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectAtEnd()) return true;
+ break;
+ }
+
+ default: {
+ handle_uninterpreted:
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
+ return true;
+ }
+ DO_(::google::protobuf::internal::WireFormat::SkipField(
+ input, tag, mutable_unknown_fields()));
+ break;
+ }
+ }
+ }
+ return true;
+#undef DO_
+}
+
+void ObstacleMap::SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
+ 1, this->header(), output);
+ }
+
+ // required int32 type = 2;
+ if (has_type()) {
+ ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->type(), output);
+ }
+
+ // optional float resolution = 3;
+ if (has_resolution()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->resolution(), output);
+ }
+
+ // optional int32 rows = 4;
+ if (has_rows()) {
+ ::google::protobuf::internal::WireFormatLite::WriteInt32(4, this->rows(), output);
+ }
+
+ // optional int32 cols = 5;
+ if (has_cols()) {
+ ::google::protobuf::internal::WireFormatLite::WriteInt32(5, this->cols(), output);
+ }
+
+ // optional int32 mapR0 = 6;
+ if (has_mapr0()) {
+ ::google::protobuf::internal::WireFormatLite::WriteInt32(6, this->mapr0(), output);
+ }
+
+ // optional int32 mapC0 = 7;
+ if (has_mapc0()) {
+ ::google::protobuf::internal::WireFormatLite::WriteInt32(7, this->mapc0(), output);
+ }
+
+ // optional int32 arrayR0 = 8;
+ if (has_arrayr0()) {
+ ::google::protobuf::internal::WireFormatLite::WriteInt32(8, this->arrayr0(), output);
+ }
+
+ // optional int32 arrayC0 = 9;
+ if (has_arrayc0()) {
+ ::google::protobuf::internal::WireFormatLite::WriteInt32(9, this->arrayc0(), output);
+ }
+
+ // optional bytes data = 10;
+ if (has_data()) {
+ ::google::protobuf::internal::WireFormatLite::WriteBytes(
+ 10, this->data(), output);
+ }
+
+ if (!unknown_fields().empty()) {
+ ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
+ unknown_fields(), output);
+ }
+}
+
+::google::protobuf::uint8* ObstacleMap::SerializeWithCachedSizesToArray(
+ ::google::protobuf::uint8* target) const {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ target = ::google::protobuf::internal::WireFormatLite::
+ WriteMessageNoVirtualToArray(
+ 1, this->header(), target);
+ }
+
+ // required int32 type = 2;
+ if (has_type()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->type(), target);
+ }
+
+ // optional float resolution = 3;
+ if (has_resolution()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->resolution(), target);
+ }
+
+ // optional int32 rows = 4;
+ if (has_rows()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(4, this->rows(), target);
+ }
+
+ // optional int32 cols = 5;
+ if (has_cols()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(5, this->cols(), target);
+ }
+
+ // optional int32 mapR0 = 6;
+ if (has_mapr0()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(6, this->mapr0(), target);
+ }
+
+ // optional int32 mapC0 = 7;
+ if (has_mapc0()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(7, this->mapc0(), target);
+ }
+
+ // optional int32 arrayR0 = 8;
+ if (has_arrayr0()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(8, this->arrayr0(), target);
+ }
+
+ // optional int32 arrayC0 = 9;
+ if (has_arrayc0()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(9, this->arrayc0(), target);
+ }
+
+ // optional bytes data = 10;
+ if (has_data()) {
+ target =
+ ::google::protobuf::internal::WireFormatLite::WriteBytesToArray(
+ 10, this->data(), target);
+ }
+
+ if (!unknown_fields().empty()) {
+ target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
+ unknown_fields(), target);
+ }
+ return target;
+}
+
+int ObstacleMap::ByteSize() const {
+ int total_size = 0;
+
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ this->header());
+ }
+
+ // required int32 type = 2;
+ if (has_type()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::Int32Size(
+ this->type());
+ }
+
+ // optional float resolution = 3;
+ if (has_resolution()) {
+ total_size += 1 + 4;
+ }
+
+ // optional int32 rows = 4;
+ if (has_rows()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::Int32Size(
+ this->rows());
+ }
+
+ // optional int32 cols = 5;
+ if (has_cols()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::Int32Size(
+ this->cols());
+ }
+
+ // optional int32 mapR0 = 6;
+ if (has_mapr0()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::Int32Size(
+ this->mapr0());
+ }
+
+ // optional int32 mapC0 = 7;
+ if (has_mapc0()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::Int32Size(
+ this->mapc0());
+ }
+
+ // optional int32 arrayR0 = 8;
+ if (has_arrayr0()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::Int32Size(
+ this->arrayr0());
+ }
+
+ }
+ if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) {
+ // optional int32 arrayC0 = 9;
+ if (has_arrayc0()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::Int32Size(
+ this->arrayc0());
+ }
+
+ // optional bytes data = 10;
+ if (has_data()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::BytesSize(
+ this->data());
+ }
+
+ }
+ if (!unknown_fields().empty()) {
+ total_size +=
+ ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
+ unknown_fields());
+ }
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = total_size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+ return total_size;
+}
+
+void ObstacleMap::MergeFrom(const ::google::protobuf::Message& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ const ObstacleMap* source =
+ ::google::protobuf::internal::dynamic_cast_if_available<const ObstacleMap*>(
+ &from);
+ if (source == NULL) {
+ ::google::protobuf::internal::ReflectionOps::Merge(from, this);
+ } else {
+ MergeFrom(*source);
+ }
+}
+
+void ObstacleMap::MergeFrom(const ObstacleMap& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (from.has_header()) {
+ mutable_header()->::px::HeaderInfo::MergeFrom(from.header());
+ }
+ if (from.has_type()) {
+ set_type(from.type());
+ }
+ if (from.has_resolution()) {
+ set_resolution(from.resolution());
+ }
+ if (from.has_rows()) {
+ set_rows(from.rows());
+ }
+ if (from.has_cols()) {
+ set_cols(from.cols());
+ }
+ if (from.has_mapr0()) {
+ set_mapr0(from.mapr0());
+ }
+ if (from.has_mapc0()) {
+ set_mapc0(from.mapc0());
+ }
+ if (from.has_arrayr0()) {
+ set_arrayr0(from.arrayr0());
+ }
+ }
+ if (from._has_bits_[8 / 32] & (0xffu << (8 % 32))) {
+ if (from.has_arrayc0()) {
+ set_arrayc0(from.arrayc0());
+ }
+ if (from.has_data()) {
+ set_data(from.data());
+ }
+ }
+ mutable_unknown_fields()->MergeFrom(from.unknown_fields());
+}
+
+void ObstacleMap::CopyFrom(const ::google::protobuf::Message& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+void ObstacleMap::CopyFrom(const ObstacleMap& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+bool ObstacleMap::IsInitialized() const {
+ if ((_has_bits_[0] & 0x00000003) != 0x00000003) return false;
+
+ if (has_header()) {
+ if (!this->header().IsInitialized()) return false;
+ }
+ return true;
+}
+
+void ObstacleMap::Swap(ObstacleMap* other) {
+ if (other != this) {
+ std::swap(header_, other->header_);
+ std::swap(type_, other->type_);
+ std::swap(resolution_, other->resolution_);
+ std::swap(rows_, other->rows_);
+ std::swap(cols_, other->cols_);
+ std::swap(mapr0_, other->mapr0_);
+ std::swap(mapc0_, other->mapc0_);
+ std::swap(arrayr0_, other->arrayr0_);
+ std::swap(arrayc0_, other->arrayc0_);
+ std::swap(data_, other->data_);
+ std::swap(_has_bits_[0], other->_has_bits_[0]);
+ _unknown_fields_.Swap(&other->_unknown_fields_);
+ std::swap(_cached_size_, other->_cached_size_);
+ }
+}
+
+::google::protobuf::Metadata ObstacleMap::GetMetadata() const {
+ protobuf_AssignDescriptorsOnce();
+ ::google::protobuf::Metadata metadata;
+ metadata.descriptor = ObstacleMap_descriptor_;
+ metadata.reflection = ObstacleMap_reflection_;
+ return metadata;
+}
+
+
+// ===================================================================
+
+#ifndef _MSC_VER
+const int Path::kHeaderFieldNumber;
+const int Path::kWaypointsFieldNumber;
+#endif // !_MSC_VER
+
+Path::Path()
+ : ::google::protobuf::Message() {
+ SharedCtor();
+}
+
+void Path::InitAsDefaultInstance() {
+ header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance());
+}
+
+Path::Path(const Path& from)
+ : ::google::protobuf::Message() {
+ SharedCtor();
+ MergeFrom(from);
+}
+
+void Path::SharedCtor() {
+ _cached_size_ = 0;
+ header_ = NULL;
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+}
+
+Path::~Path() {
+ SharedDtor();
+}
+
+void Path::SharedDtor() {
+ if (this != default_instance_) {
+ delete header_;
+ }
+}
+
+void Path::SetCachedSize(int size) const {
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+}
+const ::google::protobuf::Descriptor* Path::descriptor() {
+ protobuf_AssignDescriptorsOnce();
+ return Path_descriptor_;
+}
+
+const Path& Path::default_instance() {
+ if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
+}
+
+Path* Path::default_instance_ = NULL;
+
+Path* Path::New() const {
+ return new Path;
+}
+
+void Path::Clear() {
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (has_header()) {
+ if (header_ != NULL) header_->::px::HeaderInfo::Clear();
+ }
+ }
+ waypoints_.Clear();
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+ mutable_unknown_fields()->Clear();
+}
+
+bool Path::MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input) {
+#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
+ ::google::protobuf::uint32 tag;
+ while ((tag = input->ReadTag()) != 0) {
+ switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
+ // required .px.HeaderInfo header = 1;
+ case 1: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
+ DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
+ input, mutable_header()));
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(18)) goto parse_waypoints;
+ break;
+ }
+
+ // repeated .px.Waypoint waypoints = 2;
+ case 2: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
+ parse_waypoints:
+ DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
+ input, add_waypoints()));
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(18)) goto parse_waypoints;
+ if (input->ExpectAtEnd()) return true;
+ break;
+ }
+
+ default: {
+ handle_uninterpreted:
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
+ return true;
+ }
+ DO_(::google::protobuf::internal::WireFormat::SkipField(
+ input, tag, mutable_unknown_fields()));
+ break;
+ }
+ }
+ }
+ return true;
+#undef DO_
+}
+
+void Path::SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
+ 1, this->header(), output);
+ }
+
+ // repeated .px.Waypoint waypoints = 2;
+ for (int i = 0; i < this->waypoints_size(); i++) {
+ ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
+ 2, this->waypoints(i), output);
+ }
+
+ if (!unknown_fields().empty()) {
+ ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
+ unknown_fields(), output);
+ }
+}
+
+::google::protobuf::uint8* Path::SerializeWithCachedSizesToArray(
+ ::google::protobuf::uint8* target) const {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ target = ::google::protobuf::internal::WireFormatLite::
+ WriteMessageNoVirtualToArray(
+ 1, this->header(), target);
+ }
+
+ // repeated .px.Waypoint waypoints = 2;
+ for (int i = 0; i < this->waypoints_size(); i++) {
+ target = ::google::protobuf::internal::WireFormatLite::
+ WriteMessageNoVirtualToArray(
+ 2, this->waypoints(i), target);
+ }
+
+ if (!unknown_fields().empty()) {
+ target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
+ unknown_fields(), target);
+ }
+ return target;
+}
+
+int Path::ByteSize() const {
+ int total_size = 0;
+
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ this->header());
+ }
+
+ }
+ // repeated .px.Waypoint waypoints = 2;
+ total_size += 1 * this->waypoints_size();
+ for (int i = 0; i < this->waypoints_size(); i++) {
+ total_size +=
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ this->waypoints(i));
+ }
+
+ if (!unknown_fields().empty()) {
+ total_size +=
+ ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
+ unknown_fields());
+ }
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = total_size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+ return total_size;
+}
+
+void Path::MergeFrom(const ::google::protobuf::Message& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ const Path* source =
+ ::google::protobuf::internal::dynamic_cast_if_available<const Path*>(
+ &from);
+ if (source == NULL) {
+ ::google::protobuf::internal::ReflectionOps::Merge(from, this);
+ } else {
+ MergeFrom(*source);
+ }
+}
+
+void Path::MergeFrom(const Path& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ waypoints_.MergeFrom(from.waypoints_);
+ if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (from.has_header()) {
+ mutable_header()->::px::HeaderInfo::MergeFrom(from.header());
+ }
+ }
+ mutable_unknown_fields()->MergeFrom(from.unknown_fields());
+}
+
+void Path::CopyFrom(const ::google::protobuf::Message& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+void Path::CopyFrom(const Path& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+bool Path::IsInitialized() const {
+ if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false;
+
+ if (has_header()) {
+ if (!this->header().IsInitialized()) return false;
+ }
+ for (int i = 0; i < waypoints_size(); i++) {
+ if (!this->waypoints(i).IsInitialized()) return false;
+ }
+ return true;
+}
+
+void Path::Swap(Path* other) {
+ if (other != this) {
+ std::swap(header_, other->header_);
+ waypoints_.Swap(&other->waypoints_);
+ std::swap(_has_bits_[0], other->_has_bits_[0]);
+ _unknown_fields_.Swap(&other->_unknown_fields_);
+ std::swap(_cached_size_, other->_cached_size_);
+ }
+}
+
+::google::protobuf::Metadata Path::GetMetadata() const {
+ protobuf_AssignDescriptorsOnce();
+ ::google::protobuf::Metadata metadata;
+ metadata.descriptor = Path_descriptor_;
+ metadata.reflection = Path_reflection_;
+ return metadata;
+}
+
+
+// ===================================================================
+
+#ifndef _MSC_VER
+const int PointCloudXYZI_PointXYZI::kXFieldNumber;
+const int PointCloudXYZI_PointXYZI::kYFieldNumber;
+const int PointCloudXYZI_PointXYZI::kZFieldNumber;
+const int PointCloudXYZI_PointXYZI::kIntensityFieldNumber;
+#endif // !_MSC_VER
+
+PointCloudXYZI_PointXYZI::PointCloudXYZI_PointXYZI()
+ : ::google::protobuf::Message() {
+ SharedCtor();
+}
+
+void PointCloudXYZI_PointXYZI::InitAsDefaultInstance() {
+}
+
+PointCloudXYZI_PointXYZI::PointCloudXYZI_PointXYZI(const PointCloudXYZI_PointXYZI& from)
+ : ::google::protobuf::Message() {
+ SharedCtor();
+ MergeFrom(from);
+}
+
+void PointCloudXYZI_PointXYZI::SharedCtor() {
+ _cached_size_ = 0;
+ x_ = 0;
+ y_ = 0;
+ z_ = 0;
+ intensity_ = 0;
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+}
+
+PointCloudXYZI_PointXYZI::~PointCloudXYZI_PointXYZI() {
+ SharedDtor();
+}
+
+void PointCloudXYZI_PointXYZI::SharedDtor() {
+ if (this != default_instance_) {
+ }
+}
+
+void PointCloudXYZI_PointXYZI::SetCachedSize(int size) const {
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+}
+const ::google::protobuf::Descriptor* PointCloudXYZI_PointXYZI::descriptor() {
+ protobuf_AssignDescriptorsOnce();
+ return PointCloudXYZI_PointXYZI_descriptor_;
+}
+
+const PointCloudXYZI_PointXYZI& PointCloudXYZI_PointXYZI::default_instance() {
+ if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
+}
+
+PointCloudXYZI_PointXYZI* PointCloudXYZI_PointXYZI::default_instance_ = NULL;
+
+PointCloudXYZI_PointXYZI* PointCloudXYZI_PointXYZI::New() const {
+ return new PointCloudXYZI_PointXYZI;
+}
+
+void PointCloudXYZI_PointXYZI::Clear() {
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ x_ = 0;
+ y_ = 0;
+ z_ = 0;
+ intensity_ = 0;
+ }
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+ mutable_unknown_fields()->Clear();
+}
+
+bool PointCloudXYZI_PointXYZI::MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input) {
+#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
+ ::google::protobuf::uint32 tag;
+ while ((tag = input->ReadTag()) != 0) {
+ switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
+ // required float x = 1;
+ case 1: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &x_)));
+ set_has_x();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(21)) goto parse_y;
+ break;
+ }
+
+ // required float y = 2;
+ case 2: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_y:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &y_)));
+ set_has_y();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(29)) goto parse_z;
+ break;
+ }
+
+ // required float z = 3;
+ case 3: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_z:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &z_)));
+ set_has_z();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(37)) goto parse_intensity;
+ break;
+ }
+
+ // required float intensity = 4;
+ case 4: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_intensity:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &intensity_)));
+ set_has_intensity();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectAtEnd()) return true;
+ break;
+ }
+
+ default: {
+ handle_uninterpreted:
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
+ return true;
+ }
+ DO_(::google::protobuf::internal::WireFormat::SkipField(
+ input, tag, mutable_unknown_fields()));
+ break;
+ }
+ }
+ }
+ return true;
+#undef DO_
+}
+
+void PointCloudXYZI_PointXYZI::SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const {
+ // required float x = 1;
+ if (has_x()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->x(), output);
+ }
+
+ // required float y = 2;
+ if (has_y()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->y(), output);
+ }
+
+ // required float z = 3;
+ if (has_z()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->z(), output);
+ }
+
+ // required float intensity = 4;
+ if (has_intensity()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->intensity(), output);
+ }
+
+ if (!unknown_fields().empty()) {
+ ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
+ unknown_fields(), output);
+ }
+}
+
+::google::protobuf::uint8* PointCloudXYZI_PointXYZI::SerializeWithCachedSizesToArray(
+ ::google::protobuf::uint8* target) const {
+ // required float x = 1;
+ if (has_x()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->x(), target);
+ }
+
+ // required float y = 2;
+ if (has_y()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->y(), target);
+ }
+
+ // required float z = 3;
+ if (has_z()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->z(), target);
+ }
+
+ // required float intensity = 4;
+ if (has_intensity()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->intensity(), target);
+ }
+
+ if (!unknown_fields().empty()) {
+ target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
+ unknown_fields(), target);
+ }
+ return target;
+}
+
+int PointCloudXYZI_PointXYZI::ByteSize() const {
+ int total_size = 0;
+
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ // required float x = 1;
+ if (has_x()) {
+ total_size += 1 + 4;
+ }
+
+ // required float y = 2;
+ if (has_y()) {
+ total_size += 1 + 4;
+ }
+
+ // required float z = 3;
+ if (has_z()) {
+ total_size += 1 + 4;
+ }
+
+ // required float intensity = 4;
+ if (has_intensity()) {
+ total_size += 1 + 4;
+ }
+
+ }
+ if (!unknown_fields().empty()) {
+ total_size +=
+ ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
+ unknown_fields());
+ }
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = total_size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+ return total_size;
+}
+
+void PointCloudXYZI_PointXYZI::MergeFrom(const ::google::protobuf::Message& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ const PointCloudXYZI_PointXYZI* source =
+ ::google::protobuf::internal::dynamic_cast_if_available<const PointCloudXYZI_PointXYZI*>(
+ &from);
+ if (source == NULL) {
+ ::google::protobuf::internal::ReflectionOps::Merge(from, this);
+ } else {
+ MergeFrom(*source);
+ }
+}
+
+void PointCloudXYZI_PointXYZI::MergeFrom(const PointCloudXYZI_PointXYZI& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (from.has_x()) {
+ set_x(from.x());
+ }
+ if (from.has_y()) {
+ set_y(from.y());
+ }
+ if (from.has_z()) {
+ set_z(from.z());
+ }
+ if (from.has_intensity()) {
+ set_intensity(from.intensity());
+ }
+ }
+ mutable_unknown_fields()->MergeFrom(from.unknown_fields());
+}
+
+void PointCloudXYZI_PointXYZI::CopyFrom(const ::google::protobuf::Message& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+void PointCloudXYZI_PointXYZI::CopyFrom(const PointCloudXYZI_PointXYZI& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+bool PointCloudXYZI_PointXYZI::IsInitialized() const {
+ if ((_has_bits_[0] & 0x0000000f) != 0x0000000f) return false;
+
+ return true;
+}
+
+void PointCloudXYZI_PointXYZI::Swap(PointCloudXYZI_PointXYZI* other) {
+ if (other != this) {
+ std::swap(x_, other->x_);
+ std::swap(y_, other->y_);
+ std::swap(z_, other->z_);
+ std::swap(intensity_, other->intensity_);
+ std::swap(_has_bits_[0], other->_has_bits_[0]);
+ _unknown_fields_.Swap(&other->_unknown_fields_);
+ std::swap(_cached_size_, other->_cached_size_);
+ }
+}
+
+::google::protobuf::Metadata PointCloudXYZI_PointXYZI::GetMetadata() const {
+ protobuf_AssignDescriptorsOnce();
+ ::google::protobuf::Metadata metadata;
+ metadata.descriptor = PointCloudXYZI_PointXYZI_descriptor_;
+ metadata.reflection = PointCloudXYZI_PointXYZI_reflection_;
+ return metadata;
+}
+
+
+// -------------------------------------------------------------------
+
+#ifndef _MSC_VER
+const int PointCloudXYZI::kHeaderFieldNumber;
+const int PointCloudXYZI::kPointsFieldNumber;
+#endif // !_MSC_VER
+
+PointCloudXYZI::PointCloudXYZI()
+ : ::google::protobuf::Message() {
+ SharedCtor();
+}
+
+void PointCloudXYZI::InitAsDefaultInstance() {
+ header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance());
+}
+
+PointCloudXYZI::PointCloudXYZI(const PointCloudXYZI& from)
+ : ::google::protobuf::Message() {
+ SharedCtor();
+ MergeFrom(from);
+}
+
+void PointCloudXYZI::SharedCtor() {
+ _cached_size_ = 0;
+ header_ = NULL;
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+}
+
+PointCloudXYZI::~PointCloudXYZI() {
+ SharedDtor();
+}
+
+void PointCloudXYZI::SharedDtor() {
+ if (this != default_instance_) {
+ delete header_;
+ }
+}
+
+void PointCloudXYZI::SetCachedSize(int size) const {
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+}
+const ::google::protobuf::Descriptor* PointCloudXYZI::descriptor() {
+ protobuf_AssignDescriptorsOnce();
+ return PointCloudXYZI_descriptor_;
+}
+
+const PointCloudXYZI& PointCloudXYZI::default_instance() {
+ if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
+}
+
+PointCloudXYZI* PointCloudXYZI::default_instance_ = NULL;
+
+PointCloudXYZI* PointCloudXYZI::New() const {
+ return new PointCloudXYZI;
+}
+
+void PointCloudXYZI::Clear() {
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (has_header()) {
+ if (header_ != NULL) header_->::px::HeaderInfo::Clear();
+ }
+ }
+ points_.Clear();
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+ mutable_unknown_fields()->Clear();
+}
+
+bool PointCloudXYZI::MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input) {
+#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
+ ::google::protobuf::uint32 tag;
+ while ((tag = input->ReadTag()) != 0) {
+ switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
+ // required .px.HeaderInfo header = 1;
+ case 1: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
+ DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
+ input, mutable_header()));
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(18)) goto parse_points;
+ break;
+ }
+
+ // repeated .px.PointCloudXYZI.PointXYZI points = 2;
+ case 2: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
+ parse_points:
+ DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
+ input, add_points()));
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(18)) goto parse_points;
+ if (input->ExpectAtEnd()) return true;
+ break;
+ }
+
+ default: {
+ handle_uninterpreted:
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
+ return true;
+ }
+ DO_(::google::protobuf::internal::WireFormat::SkipField(
+ input, tag, mutable_unknown_fields()));
+ break;
+ }
+ }
+ }
+ return true;
+#undef DO_
+}
+
+void PointCloudXYZI::SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
+ 1, this->header(), output);
+ }
+
+ // repeated .px.PointCloudXYZI.PointXYZI points = 2;
+ for (int i = 0; i < this->points_size(); i++) {
+ ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
+ 2, this->points(i), output);
+ }
+
+ if (!unknown_fields().empty()) {
+ ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
+ unknown_fields(), output);
+ }
+}
+
+::google::protobuf::uint8* PointCloudXYZI::SerializeWithCachedSizesToArray(
+ ::google::protobuf::uint8* target) const {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ target = ::google::protobuf::internal::WireFormatLite::
+ WriteMessageNoVirtualToArray(
+ 1, this->header(), target);
+ }
+
+ // repeated .px.PointCloudXYZI.PointXYZI points = 2;
+ for (int i = 0; i < this->points_size(); i++) {
+ target = ::google::protobuf::internal::WireFormatLite::
+ WriteMessageNoVirtualToArray(
+ 2, this->points(i), target);
+ }
+
+ if (!unknown_fields().empty()) {
+ target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
+ unknown_fields(), target);
+ }
+ return target;
+}
+
+int PointCloudXYZI::ByteSize() const {
+ int total_size = 0;
+
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ this->header());
+ }
+
+ }
+ // repeated .px.PointCloudXYZI.PointXYZI points = 2;
+ total_size += 1 * this->points_size();
+ for (int i = 0; i < this->points_size(); i++) {
+ total_size +=
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ this->points(i));
+ }
+
+ if (!unknown_fields().empty()) {
+ total_size +=
+ ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
+ unknown_fields());
+ }
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = total_size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+ return total_size;
+}
+
+void PointCloudXYZI::MergeFrom(const ::google::protobuf::Message& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ const PointCloudXYZI* source =
+ ::google::protobuf::internal::dynamic_cast_if_available<const PointCloudXYZI*>(
+ &from);
+ if (source == NULL) {
+ ::google::protobuf::internal::ReflectionOps::Merge(from, this);
+ } else {
+ MergeFrom(*source);
+ }
+}
+
+void PointCloudXYZI::MergeFrom(const PointCloudXYZI& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ points_.MergeFrom(from.points_);
+ if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (from.has_header()) {
+ mutable_header()->::px::HeaderInfo::MergeFrom(from.header());
+ }
+ }
+ mutable_unknown_fields()->MergeFrom(from.unknown_fields());
+}
+
+void PointCloudXYZI::CopyFrom(const ::google::protobuf::Message& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+void PointCloudXYZI::CopyFrom(const PointCloudXYZI& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+bool PointCloudXYZI::IsInitialized() const {
+ if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false;
+
+ if (has_header()) {
+ if (!this->header().IsInitialized()) return false;
+ }
+ for (int i = 0; i < points_size(); i++) {
+ if (!this->points(i).IsInitialized()) return false;
+ }
+ return true;
+}
+
+void PointCloudXYZI::Swap(PointCloudXYZI* other) {
+ if (other != this) {
+ std::swap(header_, other->header_);
+ points_.Swap(&other->points_);
+ std::swap(_has_bits_[0], other->_has_bits_[0]);
+ _unknown_fields_.Swap(&other->_unknown_fields_);
+ std::swap(_cached_size_, other->_cached_size_);
+ }
+}
+
+::google::protobuf::Metadata PointCloudXYZI::GetMetadata() const {
+ protobuf_AssignDescriptorsOnce();
+ ::google::protobuf::Metadata metadata;
+ metadata.descriptor = PointCloudXYZI_descriptor_;
+ metadata.reflection = PointCloudXYZI_reflection_;
+ return metadata;
+}
+
+
+// ===================================================================
+
+#ifndef _MSC_VER
+const int PointCloudXYZRGB_PointXYZRGB::kXFieldNumber;
+const int PointCloudXYZRGB_PointXYZRGB::kYFieldNumber;
+const int PointCloudXYZRGB_PointXYZRGB::kZFieldNumber;
+const int PointCloudXYZRGB_PointXYZRGB::kRgbFieldNumber;
+#endif // !_MSC_VER
+
+PointCloudXYZRGB_PointXYZRGB::PointCloudXYZRGB_PointXYZRGB()
+ : ::google::protobuf::Message() {
+ SharedCtor();
+}
+
+void PointCloudXYZRGB_PointXYZRGB::InitAsDefaultInstance() {
+}
+
+PointCloudXYZRGB_PointXYZRGB::PointCloudXYZRGB_PointXYZRGB(const PointCloudXYZRGB_PointXYZRGB& from)
+ : ::google::protobuf::Message() {
+ SharedCtor();
+ MergeFrom(from);
+}
+
+void PointCloudXYZRGB_PointXYZRGB::SharedCtor() {
+ _cached_size_ = 0;
+ x_ = 0;
+ y_ = 0;
+ z_ = 0;
+ rgb_ = 0;
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+}
+
+PointCloudXYZRGB_PointXYZRGB::~PointCloudXYZRGB_PointXYZRGB() {
+ SharedDtor();
+}
+
+void PointCloudXYZRGB_PointXYZRGB::SharedDtor() {
+ if (this != default_instance_) {
+ }
+}
+
+void PointCloudXYZRGB_PointXYZRGB::SetCachedSize(int size) const {
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+}
+const ::google::protobuf::Descriptor* PointCloudXYZRGB_PointXYZRGB::descriptor() {
+ protobuf_AssignDescriptorsOnce();
+ return PointCloudXYZRGB_PointXYZRGB_descriptor_;
+}
+
+const PointCloudXYZRGB_PointXYZRGB& PointCloudXYZRGB_PointXYZRGB::default_instance() {
+ if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
+}
+
+PointCloudXYZRGB_PointXYZRGB* PointCloudXYZRGB_PointXYZRGB::default_instance_ = NULL;
+
+PointCloudXYZRGB_PointXYZRGB* PointCloudXYZRGB_PointXYZRGB::New() const {
+ return new PointCloudXYZRGB_PointXYZRGB;
+}
+
+void PointCloudXYZRGB_PointXYZRGB::Clear() {
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ x_ = 0;
+ y_ = 0;
+ z_ = 0;
+ rgb_ = 0;
+ }
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+ mutable_unknown_fields()->Clear();
+}
+
+bool PointCloudXYZRGB_PointXYZRGB::MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input) {
+#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
+ ::google::protobuf::uint32 tag;
+ while ((tag = input->ReadTag()) != 0) {
+ switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
+ // required float x = 1;
+ case 1: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &x_)));
+ set_has_x();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(21)) goto parse_y;
+ break;
+ }
+
+ // required float y = 2;
+ case 2: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_y:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &y_)));
+ set_has_y();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(29)) goto parse_z;
+ break;
+ }
+
+ // required float z = 3;
+ case 3: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_z:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &z_)));
+ set_has_z();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(37)) goto parse_rgb;
+ break;
+ }
+
+ // required float rgb = 4;
+ case 4: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_rgb:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &rgb_)));
+ set_has_rgb();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectAtEnd()) return true;
+ break;
+ }
+
+ default: {
+ handle_uninterpreted:
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
+ return true;
+ }
+ DO_(::google::protobuf::internal::WireFormat::SkipField(
+ input, tag, mutable_unknown_fields()));
+ break;
+ }
+ }
+ }
+ return true;
+#undef DO_
+}
+
+void PointCloudXYZRGB_PointXYZRGB::SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const {
+ // required float x = 1;
+ if (has_x()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->x(), output);
+ }
+
+ // required float y = 2;
+ if (has_y()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->y(), output);
+ }
+
+ // required float z = 3;
+ if (has_z()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->z(), output);
+ }
+
+ // required float rgb = 4;
+ if (has_rgb()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->rgb(), output);
+ }
+
+ if (!unknown_fields().empty()) {
+ ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
+ unknown_fields(), output);
+ }
+}
+
+::google::protobuf::uint8* PointCloudXYZRGB_PointXYZRGB::SerializeWithCachedSizesToArray(
+ ::google::protobuf::uint8* target) const {
+ // required float x = 1;
+ if (has_x()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->x(), target);
+ }
+
+ // required float y = 2;
+ if (has_y()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->y(), target);
+ }
+
+ // required float z = 3;
+ if (has_z()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->z(), target);
+ }
+
+ // required float rgb = 4;
+ if (has_rgb()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->rgb(), target);
+ }
+
+ if (!unknown_fields().empty()) {
+ target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
+ unknown_fields(), target);
+ }
+ return target;
+}
+
+int PointCloudXYZRGB_PointXYZRGB::ByteSize() const {
+ int total_size = 0;
+
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ // required float x = 1;
+ if (has_x()) {
+ total_size += 1 + 4;
+ }
+
+ // required float y = 2;
+ if (has_y()) {
+ total_size += 1 + 4;
+ }
+
+ // required float z = 3;
+ if (has_z()) {
+ total_size += 1 + 4;
+ }
+
+ // required float rgb = 4;
+ if (has_rgb()) {
+ total_size += 1 + 4;
+ }
+
+ }
+ if (!unknown_fields().empty()) {
+ total_size +=
+ ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
+ unknown_fields());
+ }
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = total_size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+ return total_size;
+}
+
+void PointCloudXYZRGB_PointXYZRGB::MergeFrom(const ::google::protobuf::Message& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ const PointCloudXYZRGB_PointXYZRGB* source =
+ ::google::protobuf::internal::dynamic_cast_if_available<const PointCloudXYZRGB_PointXYZRGB*>(
+ &from);
+ if (source == NULL) {
+ ::google::protobuf::internal::ReflectionOps::Merge(from, this);
+ } else {
+ MergeFrom(*source);
+ }
+}
+
+void PointCloudXYZRGB_PointXYZRGB::MergeFrom(const PointCloudXYZRGB_PointXYZRGB& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (from.has_x()) {
+ set_x(from.x());
+ }
+ if (from.has_y()) {
+ set_y(from.y());
+ }
+ if (from.has_z()) {
+ set_z(from.z());
+ }
+ if (from.has_rgb()) {
+ set_rgb(from.rgb());
+ }
+ }
+ mutable_unknown_fields()->MergeFrom(from.unknown_fields());
+}
+
+void PointCloudXYZRGB_PointXYZRGB::CopyFrom(const ::google::protobuf::Message& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+void PointCloudXYZRGB_PointXYZRGB::CopyFrom(const PointCloudXYZRGB_PointXYZRGB& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+bool PointCloudXYZRGB_PointXYZRGB::IsInitialized() const {
+ if ((_has_bits_[0] & 0x0000000f) != 0x0000000f) return false;
+
+ return true;
+}
+
+void PointCloudXYZRGB_PointXYZRGB::Swap(PointCloudXYZRGB_PointXYZRGB* other) {
+ if (other != this) {
+ std::swap(x_, other->x_);
+ std::swap(y_, other->y_);
+ std::swap(z_, other->z_);
+ std::swap(rgb_, other->rgb_);
+ std::swap(_has_bits_[0], other->_has_bits_[0]);
+ _unknown_fields_.Swap(&other->_unknown_fields_);
+ std::swap(_cached_size_, other->_cached_size_);
+ }
+}
+
+::google::protobuf::Metadata PointCloudXYZRGB_PointXYZRGB::GetMetadata() const {
+ protobuf_AssignDescriptorsOnce();
+ ::google::protobuf::Metadata metadata;
+ metadata.descriptor = PointCloudXYZRGB_PointXYZRGB_descriptor_;
+ metadata.reflection = PointCloudXYZRGB_PointXYZRGB_reflection_;
+ return metadata;
+}
+
+
+// -------------------------------------------------------------------
+
+#ifndef _MSC_VER
+const int PointCloudXYZRGB::kHeaderFieldNumber;
+const int PointCloudXYZRGB::kPointsFieldNumber;
+#endif // !_MSC_VER
+
+PointCloudXYZRGB::PointCloudXYZRGB()
+ : ::google::protobuf::Message() {
+ SharedCtor();
+}
+
+void PointCloudXYZRGB::InitAsDefaultInstance() {
+ header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance());
+}
+
+PointCloudXYZRGB::PointCloudXYZRGB(const PointCloudXYZRGB& from)
+ : ::google::protobuf::Message() {
+ SharedCtor();
+ MergeFrom(from);
+}
+
+void PointCloudXYZRGB::SharedCtor() {
+ _cached_size_ = 0;
+ header_ = NULL;
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+}
+
+PointCloudXYZRGB::~PointCloudXYZRGB() {
+ SharedDtor();
+}
+
+void PointCloudXYZRGB::SharedDtor() {
+ if (this != default_instance_) {
+ delete header_;
+ }
+}
+
+void PointCloudXYZRGB::SetCachedSize(int size) const {
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+}
+const ::google::protobuf::Descriptor* PointCloudXYZRGB::descriptor() {
+ protobuf_AssignDescriptorsOnce();
+ return PointCloudXYZRGB_descriptor_;
+}
+
+const PointCloudXYZRGB& PointCloudXYZRGB::default_instance() {
+ if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
+}
+
+PointCloudXYZRGB* PointCloudXYZRGB::default_instance_ = NULL;
+
+PointCloudXYZRGB* PointCloudXYZRGB::New() const {
+ return new PointCloudXYZRGB;
+}
+
+void PointCloudXYZRGB::Clear() {
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (has_header()) {
+ if (header_ != NULL) header_->::px::HeaderInfo::Clear();
+ }
+ }
+ points_.Clear();
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+ mutable_unknown_fields()->Clear();
+}
+
+bool PointCloudXYZRGB::MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input) {
+#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
+ ::google::protobuf::uint32 tag;
+ while ((tag = input->ReadTag()) != 0) {
+ switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
+ // required .px.HeaderInfo header = 1;
+ case 1: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
+ DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
+ input, mutable_header()));
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(18)) goto parse_points;
+ break;
+ }
+
+ // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2;
+ case 2: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
+ parse_points:
+ DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
+ input, add_points()));
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(18)) goto parse_points;
+ if (input->ExpectAtEnd()) return true;
+ break;
+ }
+
+ default: {
+ handle_uninterpreted:
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
+ return true;
+ }
+ DO_(::google::protobuf::internal::WireFormat::SkipField(
+ input, tag, mutable_unknown_fields()));
+ break;
+ }
+ }
+ }
+ return true;
+#undef DO_
+}
+
+void PointCloudXYZRGB::SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
+ 1, this->header(), output);
+ }
+
+ // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2;
+ for (int i = 0; i < this->points_size(); i++) {
+ ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
+ 2, this->points(i), output);
+ }
+
+ if (!unknown_fields().empty()) {
+ ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
+ unknown_fields(), output);
+ }
+}
+
+::google::protobuf::uint8* PointCloudXYZRGB::SerializeWithCachedSizesToArray(
+ ::google::protobuf::uint8* target) const {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ target = ::google::protobuf::internal::WireFormatLite::
+ WriteMessageNoVirtualToArray(
+ 1, this->header(), target);
+ }
+
+ // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2;
+ for (int i = 0; i < this->points_size(); i++) {
+ target = ::google::protobuf::internal::WireFormatLite::
+ WriteMessageNoVirtualToArray(
+ 2, this->points(i), target);
+ }
+
+ if (!unknown_fields().empty()) {
+ target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
+ unknown_fields(), target);
+ }
+ return target;
+}
+
+int PointCloudXYZRGB::ByteSize() const {
+ int total_size = 0;
+
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ this->header());
+ }
+
+ }
+ // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2;
+ total_size += 1 * this->points_size();
+ for (int i = 0; i < this->points_size(); i++) {
+ total_size +=
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ this->points(i));
+ }
+
+ if (!unknown_fields().empty()) {
+ total_size +=
+ ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
+ unknown_fields());
+ }
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = total_size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+ return total_size;
+}
+
+void PointCloudXYZRGB::MergeFrom(const ::google::protobuf::Message& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ const PointCloudXYZRGB* source =
+ ::google::protobuf::internal::dynamic_cast_if_available<const PointCloudXYZRGB*>(
+ &from);
+ if (source == NULL) {
+ ::google::protobuf::internal::ReflectionOps::Merge(from, this);
+ } else {
+ MergeFrom(*source);
+ }
+}
+
+void PointCloudXYZRGB::MergeFrom(const PointCloudXYZRGB& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ points_.MergeFrom(from.points_);
+ if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (from.has_header()) {
+ mutable_header()->::px::HeaderInfo::MergeFrom(from.header());
+ }
+ }
+ mutable_unknown_fields()->MergeFrom(from.unknown_fields());
+}
+
+void PointCloudXYZRGB::CopyFrom(const ::google::protobuf::Message& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+void PointCloudXYZRGB::CopyFrom(const PointCloudXYZRGB& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+bool PointCloudXYZRGB::IsInitialized() const {
+ if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false;
+
+ if (has_header()) {
+ if (!this->header().IsInitialized()) return false;
+ }
+ for (int i = 0; i < points_size(); i++) {
+ if (!this->points(i).IsInitialized()) return false;
+ }
+ return true;
+}
+
+void PointCloudXYZRGB::Swap(PointCloudXYZRGB* other) {
+ if (other != this) {
+ std::swap(header_, other->header_);
+ points_.Swap(&other->points_);
+ std::swap(_has_bits_[0], other->_has_bits_[0]);
+ _unknown_fields_.Swap(&other->_unknown_fields_);
+ std::swap(_cached_size_, other->_cached_size_);
+ }
+}
+
+::google::protobuf::Metadata PointCloudXYZRGB::GetMetadata() const {
+ protobuf_AssignDescriptorsOnce();
+ ::google::protobuf::Metadata metadata;
+ metadata.descriptor = PointCloudXYZRGB_descriptor_;
+ metadata.reflection = PointCloudXYZRGB_reflection_;
+ return metadata;
+}
+
+
+// ===================================================================
+
+#ifndef _MSC_VER
+const int RGBDImage::kHeaderFieldNumber;
+const int RGBDImage::kColsFieldNumber;
+const int RGBDImage::kRowsFieldNumber;
+const int RGBDImage::kStep1FieldNumber;
+const int RGBDImage::kType1FieldNumber;
+const int RGBDImage::kImageData1FieldNumber;
+const int RGBDImage::kStep2FieldNumber;
+const int RGBDImage::kType2FieldNumber;
+const int RGBDImage::kImageData2FieldNumber;
+const int RGBDImage::kCameraConfigFieldNumber;
+const int RGBDImage::kCameraTypeFieldNumber;
+const int RGBDImage::kRollFieldNumber;
+const int RGBDImage::kPitchFieldNumber;
+const int RGBDImage::kYawFieldNumber;
+const int RGBDImage::kLonFieldNumber;
+const int RGBDImage::kLatFieldNumber;
+const int RGBDImage::kAltFieldNumber;
+const int RGBDImage::kGroundXFieldNumber;
+const int RGBDImage::kGroundYFieldNumber;
+const int RGBDImage::kGroundZFieldNumber;
+const int RGBDImage::kCameraMatrixFieldNumber;
+#endif // !_MSC_VER
+
+RGBDImage::RGBDImage()
+ : ::google::protobuf::Message() {
+ SharedCtor();
+}
+
+void RGBDImage::InitAsDefaultInstance() {
+ header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance());
+}
+
+RGBDImage::RGBDImage(const RGBDImage& from)
+ : ::google::protobuf::Message() {
+ SharedCtor();
+ MergeFrom(from);
+}
+
+void RGBDImage::SharedCtor() {
+ _cached_size_ = 0;
+ header_ = NULL;
+ cols_ = 0u;
+ rows_ = 0u;
+ step1_ = 0u;
+ type1_ = 0u;
+ imagedata1_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
+ step2_ = 0u;
+ type2_ = 0u;
+ imagedata2_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString);
+ camera_config_ = 0u;
+ camera_type_ = 0u;
+ roll_ = 0;
+ pitch_ = 0;
+ yaw_ = 0;
+ lon_ = 0;
+ lat_ = 0;
+ alt_ = 0;
+ ground_x_ = 0;
+ ground_y_ = 0;
+ ground_z_ = 0;
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+}
+
+RGBDImage::~RGBDImage() {
+ SharedDtor();
+}
+
+void RGBDImage::SharedDtor() {
+ if (imagedata1_ != &::google::protobuf::internal::kEmptyString) {
+ delete imagedata1_;
+ }
+ if (imagedata2_ != &::google::protobuf::internal::kEmptyString) {
+ delete imagedata2_;
+ }
+ if (this != default_instance_) {
+ delete header_;
+ }
+}
+
+void RGBDImage::SetCachedSize(int size) const {
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+}
+const ::google::protobuf::Descriptor* RGBDImage::descriptor() {
+ protobuf_AssignDescriptorsOnce();
+ return RGBDImage_descriptor_;
+}
+
+const RGBDImage& RGBDImage::default_instance() {
+ if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
+}
+
+RGBDImage* RGBDImage::default_instance_ = NULL;
+
+RGBDImage* RGBDImage::New() const {
+ return new RGBDImage;
+}
+
+void RGBDImage::Clear() {
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (has_header()) {
+ if (header_ != NULL) header_->::px::HeaderInfo::Clear();
+ }
+ cols_ = 0u;
+ rows_ = 0u;
+ step1_ = 0u;
+ type1_ = 0u;
+ if (has_imagedata1()) {
+ if (imagedata1_ != &::google::protobuf::internal::kEmptyString) {
+ imagedata1_->clear();
+ }
+ }
+ step2_ = 0u;
+ type2_ = 0u;
+ }
+ if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) {
+ if (has_imagedata2()) {
+ if (imagedata2_ != &::google::protobuf::internal::kEmptyString) {
+ imagedata2_->clear();
+ }
+ }
+ camera_config_ = 0u;
+ camera_type_ = 0u;
+ roll_ = 0;
+ pitch_ = 0;
+ yaw_ = 0;
+ lon_ = 0;
+ lat_ = 0;
+ }
+ if (_has_bits_[16 / 32] & (0xffu << (16 % 32))) {
+ alt_ = 0;
+ ground_x_ = 0;
+ ground_y_ = 0;
+ ground_z_ = 0;
+ }
+ camera_matrix_.Clear();
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+ mutable_unknown_fields()->Clear();
+}
+
+bool RGBDImage::MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input) {
+#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
+ ::google::protobuf::uint32 tag;
+ while ((tag = input->ReadTag()) != 0) {
+ switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
+ // required .px.HeaderInfo header = 1;
+ case 1: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
+ DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
+ input, mutable_header()));
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(16)) goto parse_cols;
+ break;
+ }
+
+ // required uint32 cols = 2;
+ case 2: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ parse_cols:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>(
+ input, &cols_)));
+ set_has_cols();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(24)) goto parse_rows;
+ break;
+ }
+
+ // required uint32 rows = 3;
+ case 3: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ parse_rows:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>(
+ input, &rows_)));
+ set_has_rows();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(32)) goto parse_step1;
+ break;
+ }
+
+ // required uint32 step1 = 4;
+ case 4: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ parse_step1:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>(
+ input, &step1_)));
+ set_has_step1();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(40)) goto parse_type1;
+ break;
+ }
+
+ // required uint32 type1 = 5;
+ case 5: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ parse_type1:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>(
+ input, &type1_)));
+ set_has_type1();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(50)) goto parse_imageData1;
+ break;
+ }
+
+ // required bytes imageData1 = 6;
+ case 6: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
+ parse_imageData1:
+ DO_(::google::protobuf::internal::WireFormatLite::ReadBytes(
+ input, this->mutable_imagedata1()));
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(56)) goto parse_step2;
+ break;
+ }
+
+ // required uint32 step2 = 7;
+ case 7: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ parse_step2:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>(
+ input, &step2_)));
+ set_has_step2();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(64)) goto parse_type2;
+ break;
+ }
+
+ // required uint32 type2 = 8;
+ case 8: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ parse_type2:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>(
+ input, &type2_)));
+ set_has_type2();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(74)) goto parse_imageData2;
+ break;
+ }
+
+ // required bytes imageData2 = 9;
+ case 9: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
+ parse_imageData2:
+ DO_(::google::protobuf::internal::WireFormatLite::ReadBytes(
+ input, this->mutable_imagedata2()));
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(80)) goto parse_camera_config;
+ break;
+ }
+
+ // optional uint32 camera_config = 10;
+ case 10: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ parse_camera_config:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>(
+ input, &camera_config_)));
+ set_has_camera_config();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(88)) goto parse_camera_type;
+ break;
+ }
+
+ // optional uint32 camera_type = 11;
+ case 11: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ parse_camera_type:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>(
+ input, &camera_type_)));
+ set_has_camera_type();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(101)) goto parse_roll;
+ break;
+ }
+
+ // optional float roll = 12;
+ case 12: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_roll:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &roll_)));
+ set_has_roll();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(109)) goto parse_pitch;
+ break;
+ }
+
+ // optional float pitch = 13;
+ case 13: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_pitch:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &pitch_)));
+ set_has_pitch();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(117)) goto parse_yaw;
+ break;
+ }
+
+ // optional float yaw = 14;
+ case 14: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_yaw:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &yaw_)));
+ set_has_yaw();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(125)) goto parse_lon;
+ break;
+ }
+
+ // optional float lon = 15;
+ case 15: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_lon:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &lon_)));
+ set_has_lon();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(133)) goto parse_lat;
+ break;
+ }
+
+ // optional float lat = 16;
+ case 16: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_lat:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &lat_)));
+ set_has_lat();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(141)) goto parse_alt;
+ break;
+ }
+
+ // optional float alt = 17;
+ case 17: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_alt:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &alt_)));
+ set_has_alt();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(149)) goto parse_ground_x;
+ break;
+ }
+
+ // optional float ground_x = 18;
+ case 18: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_ground_x:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &ground_x_)));
+ set_has_ground_x();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(157)) goto parse_ground_y;
+ break;
+ }
+
+ // optional float ground_y = 19;
+ case 19: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_ground_y:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &ground_y_)));
+ set_has_ground_y();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(165)) goto parse_ground_z;
+ break;
+ }
+
+ // optional float ground_z = 20;
+ case 20: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_ground_z:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, &ground_z_)));
+ set_has_ground_z();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(173)) goto parse_camera_matrix;
+ break;
+ }
+
+ // repeated float camera_matrix = 21;
+ case 21: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
+ parse_camera_matrix:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitive<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ 2, 173, input, this->mutable_camera_matrix())));
+ } else if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag)
+ == ::google::protobuf::internal::WireFormatLite::
+ WIRETYPE_LENGTH_DELIMITED) {
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitiveNoInline<
+ float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
+ input, this->mutable_camera_matrix())));
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(173)) goto parse_camera_matrix;
+ if (input->ExpectAtEnd()) return true;
+ break;
+ }
+
+ default: {
+ handle_uninterpreted:
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
+ return true;
+ }
+ DO_(::google::protobuf::internal::WireFormat::SkipField(
+ input, tag, mutable_unknown_fields()));
+ break;
+ }
+ }
+ }
+ return true;
+#undef DO_
+}
+
+void RGBDImage::SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
+ 1, this->header(), output);
+ }
+
+ // required uint32 cols = 2;
+ if (has_cols()) {
+ ::google::protobuf::internal::WireFormatLite::WriteUInt32(2, this->cols(), output);
+ }
+
+ // required uint32 rows = 3;
+ if (has_rows()) {
+ ::google::protobuf::internal::WireFormatLite::WriteUInt32(3, this->rows(), output);
+ }
+
+ // required uint32 step1 = 4;
+ if (has_step1()) {
+ ::google::protobuf::internal::WireFormatLite::WriteUInt32(4, this->step1(), output);
+ }
+
+ // required uint32 type1 = 5;
+ if (has_type1()) {
+ ::google::protobuf::internal::WireFormatLite::WriteUInt32(5, this->type1(), output);
+ }
+
+ // required bytes imageData1 = 6;
+ if (has_imagedata1()) {
+ ::google::protobuf::internal::WireFormatLite::WriteBytes(
+ 6, this->imagedata1(), output);
+ }
+
+ // required uint32 step2 = 7;
+ if (has_step2()) {
+ ::google::protobuf::internal::WireFormatLite::WriteUInt32(7, this->step2(), output);
+ }
+
+ // required uint32 type2 = 8;
+ if (has_type2()) {
+ ::google::protobuf::internal::WireFormatLite::WriteUInt32(8, this->type2(), output);
+ }
+
+ // required bytes imageData2 = 9;
+ if (has_imagedata2()) {
+ ::google::protobuf::internal::WireFormatLite::WriteBytes(
+ 9, this->imagedata2(), output);
+ }
+
+ // optional uint32 camera_config = 10;
+ if (has_camera_config()) {
+ ::google::protobuf::internal::WireFormatLite::WriteUInt32(10, this->camera_config(), output);
+ }
+
+ // optional uint32 camera_type = 11;
+ if (has_camera_type()) {
+ ::google::protobuf::internal::WireFormatLite::WriteUInt32(11, this->camera_type(), output);
+ }
+
+ // optional float roll = 12;
+ if (has_roll()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(12, this->roll(), output);
+ }
+
+ // optional float pitch = 13;
+ if (has_pitch()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(13, this->pitch(), output);
+ }
+
+ // optional float yaw = 14;
+ if (has_yaw()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(14, this->yaw(), output);
+ }
+
+ // optional float lon = 15;
+ if (has_lon()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(15, this->lon(), output);
+ }
+
+ // optional float lat = 16;
+ if (has_lat()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(16, this->lat(), output);
+ }
+
+ // optional float alt = 17;
+ if (has_alt()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(17, this->alt(), output);
+ }
+
+ // optional float ground_x = 18;
+ if (has_ground_x()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(18, this->ground_x(), output);
+ }
+
+ // optional float ground_y = 19;
+ if (has_ground_y()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(19, this->ground_y(), output);
+ }
+
+ // optional float ground_z = 20;
+ if (has_ground_z()) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(20, this->ground_z(), output);
+ }
+
+ // repeated float camera_matrix = 21;
+ for (int i = 0; i < this->camera_matrix_size(); i++) {
+ ::google::protobuf::internal::WireFormatLite::WriteFloat(
+ 21, this->camera_matrix(i), output);
+ }
+
+ if (!unknown_fields().empty()) {
+ ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
+ unknown_fields(), output);
+ }
+}
+
+::google::protobuf::uint8* RGBDImage::SerializeWithCachedSizesToArray(
+ ::google::protobuf::uint8* target) const {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ target = ::google::protobuf::internal::WireFormatLite::
+ WriteMessageNoVirtualToArray(
+ 1, this->header(), target);
+ }
+
+ // required uint32 cols = 2;
+ if (has_cols()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(2, this->cols(), target);
+ }
+
+ // required uint32 rows = 3;
+ if (has_rows()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(3, this->rows(), target);
+ }
+
+ // required uint32 step1 = 4;
+ if (has_step1()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(4, this->step1(), target);
+ }
+
+ // required uint32 type1 = 5;
+ if (has_type1()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(5, this->type1(), target);
+ }
+
+ // required bytes imageData1 = 6;
+ if (has_imagedata1()) {
+ target =
+ ::google::protobuf::internal::WireFormatLite::WriteBytesToArray(
+ 6, this->imagedata1(), target);
+ }
+
+ // required uint32 step2 = 7;
+ if (has_step2()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(7, this->step2(), target);
+ }
+
+ // required uint32 type2 = 8;
+ if (has_type2()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(8, this->type2(), target);
+ }
+
+ // required bytes imageData2 = 9;
+ if (has_imagedata2()) {
+ target =
+ ::google::protobuf::internal::WireFormatLite::WriteBytesToArray(
+ 9, this->imagedata2(), target);
+ }
+
+ // optional uint32 camera_config = 10;
+ if (has_camera_config()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(10, this->camera_config(), target);
+ }
+
+ // optional uint32 camera_type = 11;
+ if (has_camera_type()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(11, this->camera_type(), target);
+ }
+
+ // optional float roll = 12;
+ if (has_roll()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(12, this->roll(), target);
+ }
+
+ // optional float pitch = 13;
+ if (has_pitch()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(13, this->pitch(), target);
+ }
+
+ // optional float yaw = 14;
+ if (has_yaw()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(14, this->yaw(), target);
+ }
+
+ // optional float lon = 15;
+ if (has_lon()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(15, this->lon(), target);
+ }
+
+ // optional float lat = 16;
+ if (has_lat()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(16, this->lat(), target);
+ }
+
+ // optional float alt = 17;
+ if (has_alt()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(17, this->alt(), target);
+ }
+
+ // optional float ground_x = 18;
+ if (has_ground_x()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(18, this->ground_x(), target);
+ }
+
+ // optional float ground_y = 19;
+ if (has_ground_y()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(19, this->ground_y(), target);
+ }
+
+ // optional float ground_z = 20;
+ if (has_ground_z()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(20, this->ground_z(), target);
+ }
+
+ // repeated float camera_matrix = 21;
+ for (int i = 0; i < this->camera_matrix_size(); i++) {
+ target = ::google::protobuf::internal::WireFormatLite::
+ WriteFloatToArray(21, this->camera_matrix(i), target);
+ }
+
+ if (!unknown_fields().empty()) {
+ target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
+ unknown_fields(), target);
+ }
+ return target;
+}
+
+int RGBDImage::ByteSize() const {
+ int total_size = 0;
+
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ // required .px.HeaderInfo header = 1;
+ if (has_header()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ this->header());
+ }
+
+ // required uint32 cols = 2;
+ if (has_cols()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::UInt32Size(
+ this->cols());
+ }
+
+ // required uint32 rows = 3;
+ if (has_rows()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::UInt32Size(
+ this->rows());
+ }
+
+ // required uint32 step1 = 4;
+ if (has_step1()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::UInt32Size(
+ this->step1());
+ }
+
+ // required uint32 type1 = 5;
+ if (has_type1()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::UInt32Size(
+ this->type1());
+ }
+
+ // required bytes imageData1 = 6;
+ if (has_imagedata1()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::BytesSize(
+ this->imagedata1());
+ }
+
+ // required uint32 step2 = 7;
+ if (has_step2()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::UInt32Size(
+ this->step2());
+ }
+
+ // required uint32 type2 = 8;
+ if (has_type2()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::UInt32Size(
+ this->type2());
+ }
+
+ }
+ if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) {
+ // required bytes imageData2 = 9;
+ if (has_imagedata2()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::BytesSize(
+ this->imagedata2());
+ }
+
+ // optional uint32 camera_config = 10;
+ if (has_camera_config()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::UInt32Size(
+ this->camera_config());
+ }
+
+ // optional uint32 camera_type = 11;
+ if (has_camera_type()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::UInt32Size(
+ this->camera_type());
+ }
+
+ // optional float roll = 12;
+ if (has_roll()) {
+ total_size += 1 + 4;
+ }
+
+ // optional float pitch = 13;
+ if (has_pitch()) {
+ total_size += 1 + 4;
+ }
+
+ // optional float yaw = 14;
+ if (has_yaw()) {
+ total_size += 1 + 4;
+ }
+
+ // optional float lon = 15;
+ if (has_lon()) {
+ total_size += 1 + 4;
+ }
+
+ // optional float lat = 16;
+ if (has_lat()) {
+ total_size += 2 + 4;
+ }
+
+ }
+ if (_has_bits_[16 / 32] & (0xffu << (16 % 32))) {
+ // optional float alt = 17;
+ if (has_alt()) {
+ total_size += 2 + 4;
+ }
+
+ // optional float ground_x = 18;
+ if (has_ground_x()) {
+ total_size += 2 + 4;
+ }
+
+ // optional float ground_y = 19;
+ if (has_ground_y()) {
+ total_size += 2 + 4;
+ }
+
+ // optional float ground_z = 20;
+ if (has_ground_z()) {
+ total_size += 2 + 4;
+ }
+
+ }
+ // repeated float camera_matrix = 21;
+ {
+ int data_size = 0;
+ data_size = 4 * this->camera_matrix_size();
+ total_size += 2 * this->camera_matrix_size() + data_size;
+ }
+
+ if (!unknown_fields().empty()) {
+ total_size +=
+ ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
+ unknown_fields());
+ }
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = total_size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+ return total_size;
+}
+
+void RGBDImage::MergeFrom(const ::google::protobuf::Message& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ const RGBDImage* source =
+ ::google::protobuf::internal::dynamic_cast_if_available<const RGBDImage*>(
+ &from);
+ if (source == NULL) {
+ ::google::protobuf::internal::ReflectionOps::Merge(from, this);
+ } else {
+ MergeFrom(*source);
+ }
+}
+
+void RGBDImage::MergeFrom(const RGBDImage& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ camera_matrix_.MergeFrom(from.camera_matrix_);
+ if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (from.has_header()) {
+ mutable_header()->::px::HeaderInfo::MergeFrom(from.header());
+ }
+ if (from.has_cols()) {
+ set_cols(from.cols());
+ }
+ if (from.has_rows()) {
+ set_rows(from.rows());
+ }
+ if (from.has_step1()) {
+ set_step1(from.step1());
+ }
+ if (from.has_type1()) {
+ set_type1(from.type1());
+ }
+ if (from.has_imagedata1()) {
+ set_imagedata1(from.imagedata1());
+ }
+ if (from.has_step2()) {
+ set_step2(from.step2());
+ }
+ if (from.has_type2()) {
+ set_type2(from.type2());
+ }
+ }
+ if (from._has_bits_[8 / 32] & (0xffu << (8 % 32))) {
+ if (from.has_imagedata2()) {
+ set_imagedata2(from.imagedata2());
+ }
+ if (from.has_camera_config()) {
+ set_camera_config(from.camera_config());
+ }
+ if (from.has_camera_type()) {
+ set_camera_type(from.camera_type());
+ }
+ if (from.has_roll()) {
+ set_roll(from.roll());
+ }
+ if (from.has_pitch()) {
+ set_pitch(from.pitch());
+ }
+ if (from.has_yaw()) {
+ set_yaw(from.yaw());
+ }
+ if (from.has_lon()) {
+ set_lon(from.lon());
+ }
+ if (from.has_lat()) {
+ set_lat(from.lat());
+ }
+ }
+ if (from._has_bits_[16 / 32] & (0xffu << (16 % 32))) {
+ if (from.has_alt()) {
+ set_alt(from.alt());
+ }
+ if (from.has_ground_x()) {
+ set_ground_x(from.ground_x());
+ }
+ if (from.has_ground_y()) {
+ set_ground_y(from.ground_y());
+ }
+ if (from.has_ground_z()) {
+ set_ground_z(from.ground_z());
+ }
+ }
+ mutable_unknown_fields()->MergeFrom(from.unknown_fields());
+}
+
+void RGBDImage::CopyFrom(const ::google::protobuf::Message& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+void RGBDImage::CopyFrom(const RGBDImage& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+bool RGBDImage::IsInitialized() const {
+ if ((_has_bits_[0] & 0x000001ff) != 0x000001ff) return false;
+
+ if (has_header()) {
+ if (!this->header().IsInitialized()) return false;
+ }
+ return true;
+}
+
+void RGBDImage::Swap(RGBDImage* other) {
+ if (other != this) {
+ std::swap(header_, other->header_);
+ std::swap(cols_, other->cols_);
+ std::swap(rows_, other->rows_);
+ std::swap(step1_, other->step1_);
+ std::swap(type1_, other->type1_);
+ std::swap(imagedata1_, other->imagedata1_);
+ std::swap(step2_, other->step2_);
+ std::swap(type2_, other->type2_);
+ std::swap(imagedata2_, other->imagedata2_);
+ std::swap(camera_config_, other->camera_config_);
+ std::swap(camera_type_, other->camera_type_);
+ std::swap(roll_, other->roll_);
+ std::swap(pitch_, other->pitch_);
+ std::swap(yaw_, other->yaw_);
+ std::swap(lon_, other->lon_);
+ std::swap(lat_, other->lat_);
+ std::swap(alt_, other->alt_);
+ std::swap(ground_x_, other->ground_x_);
+ std::swap(ground_y_, other->ground_y_);
+ std::swap(ground_z_, other->ground_z_);
+ camera_matrix_.Swap(&other->camera_matrix_);
+ std::swap(_has_bits_[0], other->_has_bits_[0]);
+ _unknown_fields_.Swap(&other->_unknown_fields_);
+ std::swap(_cached_size_, other->_cached_size_);
+ }
+}
+
+::google::protobuf::Metadata RGBDImage::GetMetadata() const {
+ protobuf_AssignDescriptorsOnce();
+ ::google::protobuf::Metadata metadata;
+ metadata.descriptor = RGBDImage_descriptor_;
+ metadata.reflection = RGBDImage_reflection_;
+ return metadata;
+}
+
+
+// ===================================================================
+
+#ifndef _MSC_VER
+const int Waypoint::kXFieldNumber;
+const int Waypoint::kYFieldNumber;
+const int Waypoint::kZFieldNumber;
+const int Waypoint::kRollFieldNumber;
+const int Waypoint::kPitchFieldNumber;
+const int Waypoint::kYawFieldNumber;
+#endif // !_MSC_VER
+
+Waypoint::Waypoint()
+ : ::google::protobuf::Message() {
+ SharedCtor();
+}
+
+void Waypoint::InitAsDefaultInstance() {
+}
+
+Waypoint::Waypoint(const Waypoint& from)
+ : ::google::protobuf::Message() {
+ SharedCtor();
+ MergeFrom(from);
+}
+
+void Waypoint::SharedCtor() {
+ _cached_size_ = 0;
+ x_ = 0;
+ y_ = 0;
+ z_ = 0;
+ roll_ = 0;
+ pitch_ = 0;
+ yaw_ = 0;
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+}
+
+Waypoint::~Waypoint() {
+ SharedDtor();
+}
+
+void Waypoint::SharedDtor() {
+ if (this != default_instance_) {
+ }
+}
+
+void Waypoint::SetCachedSize(int size) const {
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+}
+const ::google::protobuf::Descriptor* Waypoint::descriptor() {
+ protobuf_AssignDescriptorsOnce();
+ return Waypoint_descriptor_;
+}
+
+const Waypoint& Waypoint::default_instance() {
+ if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_;
+}
+
+Waypoint* Waypoint::default_instance_ = NULL;
+
+Waypoint* Waypoint::New() const {
+ return new Waypoint;
+}
+
+void Waypoint::Clear() {
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ x_ = 0;
+ y_ = 0;
+ z_ = 0;
+ roll_ = 0;
+ pitch_ = 0;
+ yaw_ = 0;
+ }
+ ::memset(_has_bits_, 0, sizeof(_has_bits_));
+ mutable_unknown_fields()->Clear();
+}
+
+bool Waypoint::MergePartialFromCodedStream(
+ ::google::protobuf::io::CodedInputStream* input) {
+#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
+ ::google::protobuf::uint32 tag;
+ while ((tag = input->ReadTag()) != 0) {
+ switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
+ // required double x = 1;
+ case 1: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
+ input, &x_)));
+ set_has_x();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(17)) goto parse_y;
+ break;
+ }
+
+ // required double y = 2;
+ case 2: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
+ parse_y:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
+ input, &y_)));
+ set_has_y();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(25)) goto parse_z;
+ break;
+ }
+
+ // optional double z = 3;
+ case 3: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
+ parse_z:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
+ input, &z_)));
+ set_has_z();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(33)) goto parse_roll;
+ break;
+ }
+
+ // optional double roll = 4;
+ case 4: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
+ parse_roll:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
+ input, &roll_)));
+ set_has_roll();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(41)) goto parse_pitch;
+ break;
+ }
+
+ // optional double pitch = 5;
+ case 5: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
+ parse_pitch:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
+ input, &pitch_)));
+ set_has_pitch();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectTag(49)) goto parse_yaw;
+ break;
+ }
+
+ // optional double yaw = 6;
+ case 6: {
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) {
+ parse_yaw:
+ DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
+ double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>(
+ input, &yaw_)));
+ set_has_yaw();
+ } else {
+ goto handle_uninterpreted;
+ }
+ if (input->ExpectAtEnd()) return true;
+ break;
+ }
+
+ default: {
+ handle_uninterpreted:
+ if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
+ return true;
+ }
+ DO_(::google::protobuf::internal::WireFormat::SkipField(
+ input, tag, mutable_unknown_fields()));
+ break;
+ }
+ }
+ }
+ return true;
+#undef DO_
+}
+
+void Waypoint::SerializeWithCachedSizes(
+ ::google::protobuf::io::CodedOutputStream* output) const {
+ // required double x = 1;
+ if (has_x()) {
+ ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->x(), output);
+ }
+
+ // required double y = 2;
+ if (has_y()) {
+ ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->y(), output);
+ }
+
+ // optional double z = 3;
+ if (has_z()) {
+ ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->z(), output);
+ }
+
+ // optional double roll = 4;
+ if (has_roll()) {
+ ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->roll(), output);
+ }
+
+ // optional double pitch = 5;
+ if (has_pitch()) {
+ ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->pitch(), output);
+ }
+
+ // optional double yaw = 6;
+ if (has_yaw()) {
+ ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->yaw(), output);
+ }
+
+ if (!unknown_fields().empty()) {
+ ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
+ unknown_fields(), output);
+ }
+}
+
+::google::protobuf::uint8* Waypoint::SerializeWithCachedSizesToArray(
+ ::google::protobuf::uint8* target) const {
+ // required double x = 1;
+ if (has_x()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->x(), target);
+ }
+
+ // required double y = 2;
+ if (has_y()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->y(), target);
+ }
+
+ // optional double z = 3;
+ if (has_z()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->z(), target);
+ }
+
+ // optional double roll = 4;
+ if (has_roll()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->roll(), target);
+ }
+
+ // optional double pitch = 5;
+ if (has_pitch()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->pitch(), target);
+ }
+
+ // optional double yaw = 6;
+ if (has_yaw()) {
+ target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->yaw(), target);
+ }
+
+ if (!unknown_fields().empty()) {
+ target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
+ unknown_fields(), target);
+ }
+ return target;
+}
+
+int Waypoint::ByteSize() const {
+ int total_size = 0;
+
+ if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ // required double x = 1;
+ if (has_x()) {
+ total_size += 1 + 8;
+ }
+
+ // required double y = 2;
+ if (has_y()) {
+ total_size += 1 + 8;
+ }
+
+ // optional double z = 3;
+ if (has_z()) {
+ total_size += 1 + 8;
+ }
+
+ // optional double roll = 4;
+ if (has_roll()) {
+ total_size += 1 + 8;
+ }
+
+ // optional double pitch = 5;
+ if (has_pitch()) {
+ total_size += 1 + 8;
+ }
+
+ // optional double yaw = 6;
+ if (has_yaw()) {
+ total_size += 1 + 8;
+ }
+
+ }
+ if (!unknown_fields().empty()) {
+ total_size +=
+ ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
+ unknown_fields());
+ }
+ GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
+ _cached_size_ = total_size;
+ GOOGLE_SAFE_CONCURRENT_WRITES_END();
+ return total_size;
+}
+
+void Waypoint::MergeFrom(const ::google::protobuf::Message& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ const Waypoint* source =
+ ::google::protobuf::internal::dynamic_cast_if_available<const Waypoint*>(
+ &from);
+ if (source == NULL) {
+ ::google::protobuf::internal::ReflectionOps::Merge(from, this);
+ } else {
+ MergeFrom(*source);
+ }
+}
+
+void Waypoint::MergeFrom(const Waypoint& from) {
+ GOOGLE_CHECK_NE(&from, this);
+ if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (from.has_x()) {
+ set_x(from.x());
+ }
+ if (from.has_y()) {
+ set_y(from.y());
+ }
+ if (from.has_z()) {
+ set_z(from.z());
+ }
+ if (from.has_roll()) {
+ set_roll(from.roll());
+ }
+ if (from.has_pitch()) {
+ set_pitch(from.pitch());
+ }
+ if (from.has_yaw()) {
+ set_yaw(from.yaw());
+ }
+ }
+ mutable_unknown_fields()->MergeFrom(from.unknown_fields());
+}
+
+void Waypoint::CopyFrom(const ::google::protobuf::Message& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+void Waypoint::CopyFrom(const Waypoint& from) {
+ if (&from == this) return;
+ Clear();
+ MergeFrom(from);
+}
+
+bool Waypoint::IsInitialized() const {
+ if ((_has_bits_[0] & 0x00000003) != 0x00000003) return false;
+
+ return true;
+}
+
+void Waypoint::Swap(Waypoint* other) {
+ if (other != this) {
+ std::swap(x_, other->x_);
+ std::swap(y_, other->y_);
+ std::swap(z_, other->z_);
+ std::swap(roll_, other->roll_);
+ std::swap(pitch_, other->pitch_);
+ std::swap(yaw_, other->yaw_);
+ std::swap(_has_bits_[0], other->_has_bits_[0]);
+ _unknown_fields_.Swap(&other->_unknown_fields_);
+ std::swap(_cached_size_, other->_cached_size_);
+ }
+}
+
+::google::protobuf::Metadata Waypoint::GetMetadata() const {
+ protobuf_AssignDescriptorsOnce();
+ ::google::protobuf::Metadata metadata;
+ metadata.descriptor = Waypoint_descriptor_;
+ metadata.reflection = Waypoint_reflection_;
+ return metadata;
+}
+
+
+// @@protoc_insertion_point(namespace_scope)
+
+} // namespace px
+
+// @@protoc_insertion_point(global_scope)
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/posix/.gitignore b/mavlink/share/pyshared/pymavlink/generator/C/test/posix/.gitignore
new file mode 100644
index 000000000..7c98650cc
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/test/posix/.gitignore
@@ -0,0 +1,3 @@
+/testmav0.9
+/testmav1.0
+/testmav1.0_nonstrict
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/posix/Makefile b/mavlink/share/pyshared/pymavlink/generator/C/test/posix/Makefile
new file mode 100644
index 000000000..693150fb7
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/test/posix/Makefile
@@ -0,0 +1,31 @@
+CFLAGS = -g -Wall -Werror -Os
+TESTPROTOCOL = common
+ALLPROTOCOLS = minimal test common pixhawk ardupilotmega slugs ualberta
+
+all:
+ for p in ${ALLPROTOCOLS}; do make -f Makefile build TESTPROTOCOL=$$p; done
+
+test:
+ for p in ${ALLPROTOCOLS}; do make -f Makefile testprogs TESTPROTOCOL=$$p || exit 1; done
+
+valgrindtest:
+ for p in ${ALLPROTOCOLS}; do make -f Makefile valgrindprogs TESTPROTOCOL=$$p || exit 1; done
+
+build: testmav0.9_${TESTPROTOCOL} testmav1.0_${TESTPROTOCOL}
+
+testprogs: testmav0.9_${TESTPROTOCOL} testmav1.0_${TESTPROTOCOL}
+ ./testmav0.9_${TESTPROTOCOL}
+ ./testmav1.0_${TESTPROTOCOL}
+
+valgrindprogs: testmav0.9_${TESTPROTOCOL} testmav1.0_${TESTPROTOCOL}
+ valgrind -q ./testmav0.9_${TESTPROTOCOL}
+ valgrind -q ./testmav1.0_${TESTPROTOCOL}
+
+clean:
+ rm -rf *.o *~ testmav1.0* testmav0.9*
+
+testmav1.0_${TESTPROTOCOL}: testmav.c
+ $(CC) $(CFLAGS) -I../../include_v1.0 -I../../include_v1.0/${TESTPROTOCOL} -o $@ testmav.c
+
+testmav0.9_${TESTPROTOCOL}: testmav.c
+ $(CC) $(CFLAGS) -I../../include_v0.9 -I../../include_v0.9/${TESTPROTOCOL} -o $@ testmav.c
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/posix/testmav.c b/mavlink/share/pyshared/pymavlink/generator/C/test/posix/testmav.c
new file mode 100644
index 000000000..2fd7fa378
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/test/posix/testmav.c
@@ -0,0 +1,159 @@
+/*
+ simple MAVLink testsuite for C
+ */
+#include <stdio.h>
+#include <stdlib.h>
+#include <stdint.h>
+#include <assert.h>
+#include <stddef.h>
+
+#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
+#define MAVLINK_COMM_NUM_BUFFERS 2
+
+// this trick allows us to make mavlink_message_t as small as possible
+// for this dialect, which saves some memory
+#include <version.h>
+#define MAVLINK_MAX_PAYLOAD_LEN MAVLINK_MAX_DIALECT_PAYLOAD_SIZE
+
+#include <mavlink_types.h>
+static mavlink_system_t mavlink_system = {42,11,};
+
+#define MAVLINK_ASSERT(x) assert(x)
+static void comm_send_ch(mavlink_channel_t chan, uint8_t c);
+
+static mavlink_message_t last_msg;
+
+#include <mavlink.h>
+#include <testsuite.h>
+
+static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS];
+
+static const unsigned message_lengths[] = MAVLINK_MESSAGE_LENGTHS;
+static unsigned error_count;
+
+static const mavlink_message_info_t message_info[256] = MAVLINK_MESSAGE_INFO;
+
+static void print_one_field(mavlink_message_t *msg, const mavlink_field_info_t *f, int idx)
+{
+#define PRINT_FORMAT(f, def) (f->print_format?f->print_format:def)
+ switch (f->type) {
+ case MAVLINK_TYPE_CHAR:
+ printf(PRINT_FORMAT(f, "%c"), _MAV_RETURN_char(msg, f->wire_offset+idx*1));
+ break;
+ case MAVLINK_TYPE_UINT8_T:
+ printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint8_t(msg, f->wire_offset+idx*1));
+ break;
+ case MAVLINK_TYPE_INT8_T:
+ printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int8_t(msg, f->wire_offset+idx*1));
+ break;
+ case MAVLINK_TYPE_UINT16_T:
+ printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint16_t(msg, f->wire_offset+idx*2));
+ break;
+ case MAVLINK_TYPE_INT16_T:
+ printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int16_t(msg, f->wire_offset+idx*2));
+ break;
+ case MAVLINK_TYPE_UINT32_T:
+ printf(PRINT_FORMAT(f, "%lu"), (unsigned long)_MAV_RETURN_uint32_t(msg, f->wire_offset+idx*4));
+ break;
+ case MAVLINK_TYPE_INT32_T:
+ printf(PRINT_FORMAT(f, "%ld"), (long)_MAV_RETURN_int32_t(msg, f->wire_offset+idx*4));
+ break;
+ case MAVLINK_TYPE_UINT64_T:
+ printf(PRINT_FORMAT(f, "%llu"), (unsigned long long)_MAV_RETURN_uint64_t(msg, f->wire_offset+idx*8));
+ break;
+ case MAVLINK_TYPE_INT64_T:
+ printf(PRINT_FORMAT(f, "%lld"), (long long)_MAV_RETURN_int64_t(msg, f->wire_offset+idx*8));
+ break;
+ case MAVLINK_TYPE_FLOAT:
+ printf(PRINT_FORMAT(f, "%f"), (double)_MAV_RETURN_float(msg, f->wire_offset+idx*4));
+ break;
+ case MAVLINK_TYPE_DOUBLE:
+ printf(PRINT_FORMAT(f, "%f"), _MAV_RETURN_double(msg, f->wire_offset+idx*8));
+ break;
+ }
+}
+
+static void print_field(mavlink_message_t *msg, const mavlink_field_info_t *f)
+{
+ printf("%s: ", f->name);
+ if (f->array_length == 0) {
+ print_one_field(msg, f, 0);
+ printf(" ");
+ } else {
+ unsigned i;
+ /* print an array */
+ if (f->type == MAVLINK_TYPE_CHAR) {
+ printf("'%.*s'", f->array_length,
+ f->wire_offset+(const char *)_MAV_PAYLOAD(msg));
+
+ } else {
+ printf("[ ");
+ for (i=0; i<f->array_length; i++) {
+ print_one_field(msg, f, i);
+ if (i < f->array_length) {
+ printf(", ");
+ }
+ }
+ printf("]");
+ }
+ }
+ printf(" ");
+}
+
+static void print_message(mavlink_message_t *msg)
+{
+ const mavlink_message_info_t *m = &message_info[msg->msgid];
+ const mavlink_field_info_t *f = m->fields;
+ unsigned i;
+ printf("%s { ", m->name);
+ for (i=0; i<m->num_fields; i++) {
+ print_field(msg, &f[i]);
+ }
+ printf("}\n");
+}
+
+static void comm_send_ch(mavlink_channel_t chan, uint8_t c)
+{
+ mavlink_status_t status;
+ if (mavlink_parse_char(chan, c, &last_msg, &status)) {
+ print_message(&last_msg);
+ chan_counts[chan]++;
+ /* channel 0 gets 3 messages per message, because of
+ the channel defaults for _pack() and _encode() */
+ if (chan == MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)(chan_counts[chan]*3)) {
+ printf("Channel 0 sequence mismatch error at packet %u (rx_seq=%u)\n",
+ chan_counts[chan], status.current_rx_seq);
+ error_count++;
+ } else if (chan > MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)chan_counts[chan]) {
+ printf("Channel %u sequence mismatch error at packet %u (rx_seq=%u)\n",
+ (unsigned)chan, chan_counts[chan], status.current_rx_seq);
+ error_count++;
+ }
+ if (message_lengths[last_msg.msgid] != last_msg.len) {
+ printf("Incorrect message length %u for message %u - expected %u\n",
+ (unsigned)last_msg.len, (unsigned)last_msg.msgid, message_lengths[last_msg.msgid]);
+ error_count++;
+ }
+ }
+ if (status.packet_rx_drop_count != 0) {
+ printf("Parse error at packet %u\n", chan_counts[chan]);
+ error_count++;
+ }
+}
+
+int main(void)
+{
+ mavlink_channel_t chan;
+ mavlink_test_all(11, 10, &last_msg);
+ for (chan=MAVLINK_COMM_0; chan<=MAVLINK_COMM_1; chan++) {
+ printf("Received %u messages on channel %u OK\n",
+ chan_counts[chan], (unsigned)chan);
+ }
+ if (error_count != 0) {
+ printf("Error count %u\n", error_count);
+ exit(1);
+ }
+ printf("No errors detected\n");
+ return 0;
+}
+
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.cpp b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.cpp
new file mode 100644
index 000000000..98b4abf05
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.cpp
@@ -0,0 +1,8 @@
+// stdafx.cpp : source file that includes just the standard includes
+// testmav.pch will be the pre-compiled header
+// stdafx.obj will contain the pre-compiled type information
+
+#include "stdafx.h"
+
+// TODO: reference any additional headers you need in STDAFX.H
+// and not in this file
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.h b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.h
new file mode 100644
index 000000000..47a0d0252
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.h
@@ -0,0 +1,15 @@
+// stdafx.h : include file for standard system include files,
+// or project specific include files that are used frequently, but
+// are changed infrequently
+//
+
+#pragma once
+
+#include "targetver.h"
+
+#include <stdio.h>
+#include <tchar.h>
+
+
+
+// TODO: reference additional headers your program requires here
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/targetver.h b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/targetver.h
new file mode 100644
index 000000000..90e767bfc
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/targetver.h
@@ -0,0 +1,8 @@
+#pragma once
+
+// Including SDKDDKVer.h defines the highest available Windows platform.
+
+// If you wish to build your application for a previous Windows platform, include WinSDKVer.h and
+// set the _WIN32_WINNT macro to the platform you wish to support before including SDKDDKVer.h.
+
+#include <SDKDDKVer.h>
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.cpp b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.cpp
new file mode 100644
index 000000000..aa83caced
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.cpp
@@ -0,0 +1,154 @@
+// testmav.cpp : Defines the entry point for the console application.
+//
+
+#include "stdafx.h"
+#include "stdio.h"
+#include "stdint.h"
+#include "stddef.h"
+#include "assert.h"
+
+
+#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
+#define MAVLINK_COMM_NUM_BUFFERS 2
+
+#include <mavlink_types.h>
+static mavlink_system_t mavlink_system = {42,11,};
+
+#define MAVLINK_ASSERT(x) assert(x)
+static void comm_send_ch(mavlink_channel_t chan, uint8_t c);
+
+static mavlink_message_t last_msg;
+
+#include <common/mavlink.h>
+#include <common/testsuite.h>
+
+static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS];
+
+static const unsigned message_lengths[] = MAVLINK_MESSAGE_LENGTHS;
+static unsigned error_count;
+
+static const mavlink_message_info_t message_info[256] = MAVLINK_MESSAGE_INFO;
+
+static void print_one_field(mavlink_message_t *msg, const mavlink_field_info_t *f, int idx)
+{
+#define PRINT_FORMAT(f, def) (f->print_format?f->print_format:def)
+ switch (f->type) {
+ case MAVLINK_TYPE_CHAR:
+ printf(PRINT_FORMAT(f, "%c"), _MAV_RETURN_char(msg, f->wire_offset+idx*1));
+ break;
+ case MAVLINK_TYPE_UINT8_T:
+ printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint8_t(msg, f->wire_offset+idx*1));
+ break;
+ case MAVLINK_TYPE_INT8_T:
+ printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int8_t(msg, f->wire_offset+idx*1));
+ break;
+ case MAVLINK_TYPE_UINT16_T:
+ printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint16_t(msg, f->wire_offset+idx*2));
+ break;
+ case MAVLINK_TYPE_INT16_T:
+ printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int16_t(msg, f->wire_offset+idx*2));
+ break;
+ case MAVLINK_TYPE_UINT32_T:
+ printf(PRINT_FORMAT(f, "%lu"), (unsigned long)_MAV_RETURN_uint32_t(msg, f->wire_offset+idx*4));
+ break;
+ case MAVLINK_TYPE_INT32_T:
+ printf(PRINT_FORMAT(f, "%ld"), (long)_MAV_RETURN_int32_t(msg, f->wire_offset+idx*4));
+ break;
+ case MAVLINK_TYPE_UINT64_T:
+ printf(PRINT_FORMAT(f, "%llu"), (unsigned long long)_MAV_RETURN_uint64_t(msg, f->wire_offset+idx*8));
+ break;
+ case MAVLINK_TYPE_INT64_T:
+ printf(PRINT_FORMAT(f, "%lld"), (long long)_MAV_RETURN_int64_t(msg, f->wire_offset+idx*8));
+ break;
+ case MAVLINK_TYPE_FLOAT:
+ printf(PRINT_FORMAT(f, "%f"), (double)_MAV_RETURN_float(msg, f->wire_offset+idx*4));
+ break;
+ case MAVLINK_TYPE_DOUBLE:
+ printf(PRINT_FORMAT(f, "%f"), _MAV_RETURN_double(msg, f->wire_offset+idx*8));
+ break;
+ }
+}
+
+static void print_field(mavlink_message_t *msg, const mavlink_field_info_t *f)
+{
+ printf("%s: ", f->name);
+ if (f->array_length == 0) {
+ print_one_field(msg, f, 0);
+ printf(" ");
+ } else {
+ unsigned i;
+ /* print an array */
+ if (f->type == MAVLINK_TYPE_CHAR) {
+ printf("'%.*s'", f->array_length,
+ f->wire_offset+(const char *)_MAV_PAYLOAD(msg));
+
+ } else {
+ printf("[ ");
+ for (i=0; i<f->array_length; i++) {
+ print_one_field(msg, f, i);
+ if (i < f->array_length) {
+ printf(", ");
+ }
+ }
+ printf("]");
+ }
+ }
+ printf(" ");
+}
+
+static void print_message(mavlink_message_t *msg)
+{
+ const mavlink_message_info_t *m = &message_info[msg->msgid];
+ const mavlink_field_info_t *f = m->fields;
+ unsigned i;
+ printf("%s { ", m->name);
+ for (i=0; i<m->num_fields; i++) {
+ print_field(msg, &f[i]);
+ }
+ printf("}\n");
+}
+
+static void comm_send_ch(mavlink_channel_t chan, uint8_t c)
+{
+ mavlink_status_t status;
+ if (mavlink_parse_char(chan, c, &last_msg, &status)) {
+ print_message(&last_msg);
+ chan_counts[chan]++;
+ /* channel 0 gets 3 messages per message, because of
+ the channel defaults for _pack() and _encode() */
+ if (chan == MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)(chan_counts[chan]*3)) {
+ printf("Channel 0 sequence mismatch error at packet %u (rx_seq=%u)\n",
+ chan_counts[chan], status.current_rx_seq);
+ error_count++;
+ } else if (chan > MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)chan_counts[chan]) {
+ printf("Channel %u sequence mismatch error at packet %u (rx_seq=%u)\n",
+ (unsigned)chan, chan_counts[chan], status.current_rx_seq);
+ error_count++;
+ }
+ if (message_lengths[last_msg.msgid] != last_msg.len) {
+ printf("Incorrect message length %u for message %u - expected %u\n",
+ (unsigned)last_msg.len, (unsigned)last_msg.msgid, message_lengths[last_msg.msgid]);
+ error_count++;
+ }
+ }
+ if (status.packet_rx_drop_count != 0) {
+ printf("Parse error at packet %u\n", chan_counts[chan]);
+ error_count++;
+ }
+}
+
+int _tmain(int argc, _TCHAR* argv[])
+{
+ int chan;
+ mavlink_test_all(11, 10, &last_msg);
+ for (chan=MAVLINK_COMM_0; chan<=MAVLINK_COMM_1; chan++) {
+ printf("Received %u messages on channel %u OK\n",
+ chan_counts[chan], (unsigned)chan);
+ }
+ if (error_count != 0) {
+ printf("Error count %u\n", error_count);
+ return(1);
+ }
+ printf("No errors detected\n");
+ return 0;
+}
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.sln b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.sln
new file mode 100644
index 000000000..37a305697
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.sln
@@ -0,0 +1,20 @@
+
+Microsoft Visual Studio Solution File, Format Version 11.00
+# Visual C++ Express 2010
+Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "testmav", "testmav\testmav.vcxproj", "{02C30EBC-DF41-4C36-B2F3-79BED7E6EF9F}"
+EndProject
+Global
+ GlobalSection(SolutionConfigurationPlatforms) = preSolution
+ Debug|Win32 = Debug|Win32
+ Release|Win32 = Release|Win32
+ EndGlobalSection
+ GlobalSection(ProjectConfigurationPlatforms) = postSolution
+ {02C30EBC-DF41-4C36-B2F3-79BED7E6EF9F}.Debug|Win32.ActiveCfg = Debug|Win32
+ {02C30EBC-DF41-4C36-B2F3-79BED7E6EF9F}.Debug|Win32.Build.0 = Debug|Win32
+ {02C30EBC-DF41-4C36-B2F3-79BED7E6EF9F}.Release|Win32.ActiveCfg = Release|Win32
+ {02C30EBC-DF41-4C36-B2F3-79BED7E6EF9F}.Release|Win32.Build.0 = Release|Win32
+ EndGlobalSection
+ GlobalSection(SolutionProperties) = preSolution
+ HideSolutionNode = FALSE
+ EndGlobalSection
+EndGlobal
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.suo b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.suo
new file mode 100644
index 000000000..9b2e18cff
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.suo
Binary files differ
diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.vcxproj b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.vcxproj
new file mode 100644
index 000000000..7181b3a41
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.vcxproj
@@ -0,0 +1,91 @@
+<?xml version="1.0" encoding="utf-8"?>
+<Project DefaultTargets="Build" ToolsVersion="4.0" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
+ <ItemGroup Label="ProjectConfigurations">
+ <ProjectConfiguration Include="Debug|Win32">
+ <Configuration>Debug</Configuration>
+ <Platform>Win32</Platform>
+ </ProjectConfiguration>
+ <ProjectConfiguration Include="Release|Win32">
+ <Configuration>Release</Configuration>
+ <Platform>Win32</Platform>
+ </ProjectConfiguration>
+ </ItemGroup>
+ <PropertyGroup Label="Globals">
+ <ProjectGuid>{02C30EBC-DF41-4C36-B2F3-79BED7E6EF9F}</ProjectGuid>
+ <Keyword>Win32Proj</Keyword>
+ <RootNamespace>testmav</RootNamespace>
+ </PropertyGroup>
+ <Import Project="$(VCTargetsPath)\Microsoft.Cpp.Default.props" />
+ <PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'" Label="Configuration">
+ <ConfigurationType>Application</ConfigurationType>
+ <UseDebugLibraries>true</UseDebugLibraries>
+ <CharacterSet>Unicode</CharacterSet>
+ </PropertyGroup>
+ <PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Release|Win32'" Label="Configuration">
+ <ConfigurationType>Application</ConfigurationType>
+ <UseDebugLibraries>false</UseDebugLibraries>
+ <WholeProgramOptimization>true</WholeProgramOptimization>
+ <CharacterSet>Unicode</CharacterSet>
+ </PropertyGroup>
+ <Import Project="$(VCTargetsPath)\Microsoft.Cpp.props" />
+ <ImportGroup Label="ExtensionSettings">
+ </ImportGroup>
+ <ImportGroup Label="PropertySheets" Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
+ <Import Project="$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props" Condition="exists('$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props')" Label="LocalAppDataPlatform" />
+ </ImportGroup>
+ <ImportGroup Label="PropertySheets" Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">
+ <Import Project="$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props" Condition="exists('$(UserRootDir)\Microsoft.Cpp.$(Platform).user.props')" Label="LocalAppDataPlatform" />
+ </ImportGroup>
+ <PropertyGroup Label="UserMacros" />
+ <PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
+ <LinkIncremental>true</LinkIncremental>
+ </PropertyGroup>
+ <PropertyGroup Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">
+ <LinkIncremental>false</LinkIncremental>
+ </PropertyGroup>
+ <ItemDefinitionGroup Condition="'$(Configuration)|$(Platform)'=='Debug|Win32'">
+ <ClCompile>
+ <PrecompiledHeader>
+ </PrecompiledHeader>
+ <WarningLevel>Level3</WarningLevel>
+ <Optimization>Disabled</Optimization>
+ <PreprocessorDefinitions>WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions)</PreprocessorDefinitions>
+ <AdditionalIncludeDirectories>E:\pymavlink\generator\C\include_v1.0</AdditionalIncludeDirectories>
+ </ClCompile>
+ <Link>
+ <SubSystem>Console</SubSystem>
+ <GenerateDebugInformation>true</GenerateDebugInformation>
+ </Link>
+ </ItemDefinitionGroup>
+ <ItemDefinitionGroup Condition="'$(Configuration)|$(Platform)'=='Release|Win32'">
+ <ClCompile>
+ <WarningLevel>Level3</WarningLevel>
+ <PrecompiledHeader>
+ </PrecompiledHeader>
+ <Optimization>MaxSpeed</Optimization>
+ <FunctionLevelLinking>true</FunctionLevelLinking>
+ <IntrinsicFunctions>true</IntrinsicFunctions>
+ <PreprocessorDefinitions>WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions)</PreprocessorDefinitions>
+ </ClCompile>
+ <Link>
+ <SubSystem>Console</SubSystem>
+ <GenerateDebugInformation>true</GenerateDebugInformation>
+ <EnableCOMDATFolding>true</EnableCOMDATFolding>
+ <OptimizeReferences>true</OptimizeReferences>
+ </Link>
+ </ItemDefinitionGroup>
+ <ItemGroup>
+ <None Include="ReadMe.txt" />
+ </ItemGroup>
+ <ItemGroup>
+ <ClInclude Include="stdafx.h" />
+ <ClInclude Include="targetver.h" />
+ </ItemGroup>
+ <ItemGroup>
+ <ClCompile Include="stdafx.cpp" />
+ <ClCompile Include="testmav.cpp" />
+ </ItemGroup>
+ <Import Project="$(VCTargetsPath)\Microsoft.Cpp.targets" />
+ <ImportGroup Label="ExtensionTargets">
+ </ImportGroup>
+</Project> \ No newline at end of file
diff --git a/mavlink/share/pyshared/pymavlink/generator/gen_MatrixPilot.py b/mavlink/share/pyshared/pymavlink/generator/gen_MatrixPilot.py
new file mode 100644
index 000000000..165c1b343
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/gen_MatrixPilot.py
@@ -0,0 +1,93 @@
+#!/usr/bin/env python
+'''
+Use mavgen.py matrixpilot.xml definitions to generate
+C and Python MAVLink routines for sending and parsing the protocol
+This python script is soley for MatrixPilot MAVLink impoementation
+
+Copyright Pete Hollands 2011
+Released under GNU GPL version 3 or later
+'''
+
+import os, sys, glob, re
+from shutil import copy
+from mavgen import mavgen
+
+# allow import from the parent directory, where mavutil.py is
+# Under Windows, this script must be run from a DOS command window
+sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
+
+class options:
+ """ a class to simulate the options of mavgen OptionsParser"""
+ def __init__(self, lang, output, wire_protocol):
+ self.language = lang
+ self.wire_protocol = wire_protocol
+ self.output = output
+
+def remove_include_files(target_directory):
+ search_pattern = target_directory+'/*.h'
+ print "search pattern is", search_pattern
+ files_to_remove = glob.glob(search_pattern)
+ for afile in files_to_remove :
+ try:
+ print "removing", afile
+ os.remove(afile)
+ except:
+ print "error while trying to remove", afile
+
+def copy_include_files(source_directory,target_directory):
+ search_pattern = source_directory+'/*.h'
+ files_to_copy = glob.glob(search_pattern)
+ for afile in files_to_copy:
+ basename = os.path.basename(afile)
+ print "Copying ...", basename
+ copy(afile, target_directory)
+
+protocol = "1.0"
+
+xml_directory = './message_definitions/v'+protocol
+print "xml_directory is", xml_directory
+xml_file_names = []
+xml_file_names.append(xml_directory+"/"+"matrixpilot.xml")
+
+for xml_file in xml_file_names:
+ print "xml file is ", xml_file
+ opts = options(lang = "C", output = "C/include_v"+protocol, \
+ wire_protocol=protocol)
+ args = []
+ args.append(xml_file)
+ mavgen(opts, args)
+ xml_file_base = os.path.basename(xml_file)
+ xml_file_base = re.sub("\.xml","", xml_file_base)
+ print "xml_file_base is", xml_file_base
+ opts = options(lang = "python", \
+ output="python/mavlink_"+xml_file_base+"_v"+protocol+".py", \
+ wire_protocol=protocol)
+ mavgen(opts,args)
+
+mavlink_directory_list = ["common","matrixpilot"]
+for mavlink_directory in mavlink_directory_list :
+ # Look specifically for MatrixPilot directory structure
+ target_directory = "../../../../MAVLink/include/"+mavlink_directory
+ source_directory = "C/include_v"+protocol+"/"+mavlink_directory
+ if os.access(source_directory, os.R_OK):
+ if os.access(target_directory, os.W_OK):
+ print "Preparing to copy over files..."
+ print "About to remove all files in",target_directory
+ print "OK to continue ?[Yes / No]: ",
+ line = sys.stdin.readline()
+ if line == "Yes\n" or line == "yes\n" \
+ or line == "Y\n" or line == "y\n":
+ print "passed"
+ remove_include_files(target_directory)
+ copy_include_files(source_directory,target_directory)
+ print "Finished copying over include files"
+ else :
+ print "Your answer is No. Exiting Program"
+ sys.exit()
+ else :
+ print "Cannot find " + target_directory + "in MatrixPilot"
+ sys.exit()
+ else:
+ print "Could not find files to copy at", source_directory
+ print "Exiting Program."
+ sys.exit()
diff --git a/mavlink/share/pyshared/pymavlink/generator/gen_all.py b/mavlink/share/pyshared/pymavlink/generator/gen_all.py
new file mode 100644
index 000000000..5b24f85cb
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/gen_all.py
@@ -0,0 +1,44 @@
+#!/usr/bin/env python
+
+'''
+Use mavgen.py on all available MAVLink XML definitions to generate
+C and Python MAVLink routines for sending and parsing the protocol
+
+Copyright Pete Hollands 2011
+Released under GNU GPL version 3 or later
+'''
+
+import os, sys, glob, re
+from mavgen import mavgen
+
+# allow import from the parent directory, where mavutil.py is
+sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
+
+class options:
+ """ a class to simulate the options of mavgen OptionsParser"""
+ def __init__(self, lang, output, wire_protocol):
+ self.language = lang
+ self.wire_protocol = wire_protocol
+ self.output = output
+
+protocols = [ '0.9', '1.0' ]
+
+for protocol in protocols :
+ xml_directory = './message_definitions/v'+protocol
+ print "xml_directory is", xml_directory
+ xml_file_names = glob.glob(xml_directory+'/*.xml')
+
+ for xml_file in xml_file_names:
+ print "xml file is ", xml_file
+ opts = options(lang = "C", output = "C/include_v"+protocol, \
+ wire_protocol=protocol)
+ args = []
+ args.append(xml_file)
+ mavgen(opts, args)
+ xml_file_base = os.path.basename(xml_file)
+ xml_file_base = re.sub("\.xml","", xml_file_base)
+ print "xml_file_base is", xml_file_base
+ opts = options(lang = "python", \
+ output="python/mavlink_"+xml_file_base+"_v"+protocol+".py", \
+ wire_protocol=protocol)
+ mavgen(opts,args)
diff --git a/mavlink/share/pyshared/pymavlink/generator/gen_all.sh b/mavlink/share/pyshared/pymavlink/generator/gen_all.sh
new file mode 100644
index 000000000..e8dafedc5
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/gen_all.sh
@@ -0,0 +1,12 @@
+#!/bin/sh
+
+for protocol in 0.9 1.0; do
+ for xml in message_definitions/v$protocol/*.xml; do
+ base=$(basename $xml .xml)
+ ./mavgen.py --lang=C --wire-protocol=$protocol --output=C/include_v$protocol $xml || exit 1
+ ./mavgen.py --lang=python --wire-protocol=$protocol --output=python/mavlink_${base}_v$protocol.py $xml || exit 1
+ done
+done
+
+cp -f python/mavlink_ardupilotmega_v0.9.py ../mavlink.py
+cp -f python/mavlink_ardupilotmega_v1.0.py ../mavlinkv10.py
diff --git a/mavlink/share/pyshared/pymavlink/generator/mavgen.py b/mavlink/share/pyshared/pymavlink/generator/mavgen.py
new file mode 100644
index 000000000..05f71f778
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/mavgen.py
@@ -0,0 +1,82 @@
+#!/usr/bin/env python
+'''
+parse a MAVLink protocol XML file and generate a python implementation
+
+Copyright Andrew Tridgell 2011
+Released under GNU GPL version 3 or later
+'''
+
+def mavgen(opts, args) :
+ """Generate mavlink message formatters and parsers (C and Python ) using options
+ and args where args are a list of xml files. This function allows python
+ scripts under Windows to control mavgen using the same interface as
+ shell scripts under Unix"""
+ import sys, textwrap, os
+
+ import mavparse
+ import mavgen_python
+ import mavgen_c
+
+ xml = []
+
+ for fname in args:
+ print("Parsing %s" % fname)
+ xml.append(mavparse.MAVXML(fname, opts.wire_protocol))
+
+ # expand includes
+ for x in xml[:]:
+ for i in x.include:
+ fname = os.path.join(os.path.dirname(x.filename), i)
+ print("Parsing %s" % fname)
+ xml.append(mavparse.MAVXML(fname, opts.wire_protocol))
+
+ # include message lengths and CRCs too
+ for idx in range(0, 256):
+ if x.message_lengths[idx] == 0:
+ x.message_lengths[idx] = xml[-1].message_lengths[idx]
+ x.message_crcs[idx] = xml[-1].message_crcs[idx]
+ x.message_names[idx] = xml[-1].message_names[idx]
+
+ # work out max payload size across all includes
+ largest_payload = 0
+ for x in xml:
+ if x.largest_payload > largest_payload:
+ largest_payload = x.largest_payload
+ for x in xml:
+ x.largest_payload = largest_payload
+
+ if mavparse.check_duplicates(xml):
+ sys.exit(1)
+
+ print("Found %u MAVLink message types in %u XML files" % (
+ mavparse.total_msgs(xml), len(xml)))
+
+ if opts.language == 'python':
+ mavgen_python.generate(opts.output, xml)
+ elif opts.language == 'C':
+ mavgen_c.generate(opts.output, xml)
+ else:
+ print("Unsupported language %s" % opts.language)
+
+
+if __name__=="__main__":
+ import sys, textwrap, os
+
+ from optparse import OptionParser
+
+ # allow import from the parent directory, where mavutil.py is
+ sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..'))
+
+ import mavparse
+ import mavgen_python
+ import mavgen_c
+
+ parser = OptionParser("%prog [options] <XML files>")
+ parser.add_option("-o", "--output", dest="output", default="mavlink", help="output directory.")
+ parser.add_option("--lang", dest="language", default="python", help="language of generated code: 'Python' or 'C' [default: %default]")
+ parser.add_option("--wire-protocol", dest="wire_protocol", default=mavparse.PROTOCOL_0_9, help="MAVLink protocol version: '0.9' or '1.0'. [default: %default]")
+ (opts, args) = parser.parse_args()
+
+ if len(args) < 1:
+ parser.error("You must supply at least one MAVLink XML protocol definition")
+ mavgen(opts, args)
diff --git a/mavlink/share/pyshared/pymavlink/generator/mavgen_c.py b/mavlink/share/pyshared/pymavlink/generator/mavgen_c.py
new file mode 100644
index 000000000..255919f0d
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/mavgen_c.py
@@ -0,0 +1,581 @@
+#!/usr/bin/env python
+'''
+parse a MAVLink protocol XML file and generate a C implementation
+
+Copyright Andrew Tridgell 2011
+Released under GNU GPL version 3 or later
+'''
+
+import sys, textwrap, os, time
+import mavparse, mavtemplate
+
+t = mavtemplate.MAVTemplate()
+
+def generate_version_h(directory, xml):
+ '''generate version.h'''
+ f = open(os.path.join(directory, "version.h"), mode='w')
+ t.write(f,'''
+/** @file
+ * @brief MAVLink comm protocol built from ${basename}.xml
+ * @see http://pixhawk.ethz.ch/software/mavlink
+ */
+#ifndef MAVLINK_VERSION_H
+#define MAVLINK_VERSION_H
+
+#define MAVLINK_BUILD_DATE "${parse_time}"
+#define MAVLINK_WIRE_PROTOCOL_VERSION "${wire_protocol_version}"
+#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE ${largest_payload}
+
+#endif // MAVLINK_VERSION_H
+''', xml)
+ f.close()
+
+def generate_mavlink_h(directory, xml):
+ '''generate mavlink.h'''
+ f = open(os.path.join(directory, "mavlink.h"), mode='w')
+ t.write(f,'''
+/** @file
+ * @brief MAVLink comm protocol built from ${basename}.xml
+ * @see http://pixhawk.ethz.ch/software/mavlink
+ */
+#ifndef MAVLINK_H
+#define MAVLINK_H
+
+#ifndef MAVLINK_STX
+#define MAVLINK_STX ${protocol_marker}
+#endif
+
+#ifndef MAVLINK_ENDIAN
+#define MAVLINK_ENDIAN ${mavlink_endian}
+#endif
+
+#ifndef MAVLINK_ALIGNED_FIELDS
+#define MAVLINK_ALIGNED_FIELDS ${aligned_fields_define}
+#endif
+
+#ifndef MAVLINK_CRC_EXTRA
+#define MAVLINK_CRC_EXTRA ${crc_extra_define}
+#endif
+
+#include "version.h"
+#include "${basename}.h"
+
+#endif // MAVLINK_H
+''', xml)
+ f.close()
+
+def generate_main_h(directory, xml):
+ '''generate main header per XML file'''
+ f = open(os.path.join(directory, xml.basename + ".h"), mode='w')
+ t.write(f, '''
+/** @file
+ * @brief MAVLink comm protocol generated from ${basename}.xml
+ * @see http://qgroundcontrol.org/mavlink/
+ */
+#ifndef ${basename_upper}_H
+#define ${basename_upper}_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+// MESSAGE LENGTHS AND CRCS
+
+#ifndef MAVLINK_MESSAGE_LENGTHS
+#define MAVLINK_MESSAGE_LENGTHS {${message_lengths_array}}
+#endif
+
+#ifndef MAVLINK_MESSAGE_CRCS
+#define MAVLINK_MESSAGE_CRCS {${message_crcs_array}}
+#endif
+
+#ifndef MAVLINK_MESSAGE_INFO
+#define MAVLINK_MESSAGE_INFO {${message_info_array}}
+#endif
+
+#include "../protocol.h"
+
+#define MAVLINK_ENABLED_${basename_upper}
+
+${{include_list:#include "../${base}/${base}.h"
+}}
+
+// MAVLINK VERSION
+
+#ifndef MAVLINK_VERSION
+#define MAVLINK_VERSION ${version}
+#endif
+
+#if (MAVLINK_VERSION == 0)
+#undef MAVLINK_VERSION
+#define MAVLINK_VERSION ${version}
+#endif
+
+// ENUM DEFINITIONS
+
+${{enum:
+/** @brief ${description} */
+#ifndef HAVE_ENUM_${name}
+#define HAVE_ENUM_${name}
+enum ${name}
+{
+${{entry: ${name}=${value}, /* ${description} |${{param:${description}| }} */
+}}
+};
+#endif
+}}
+
+// MESSAGE DEFINITIONS
+${{message:#include "./mavlink_msg_${name_lower}.h"
+}}
+
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+#endif // ${basename_upper}_H
+''', xml)
+
+ f.close()
+
+
+def generate_message_h(directory, m):
+ '''generate per-message header for a XML file'''
+ f = open(os.path.join(directory, 'mavlink_msg_%s.h' % m.name_lower), mode='w')
+ t.write(f, '''
+// MESSAGE ${name} PACKING
+
+#define MAVLINK_MSG_ID_${name} ${id}
+
+typedef struct __mavlink_${name_lower}_t
+{
+${{ordered_fields: ${type} ${name}${array_suffix}; ///< ${description}
+}}
+} mavlink_${name_lower}_t;
+
+#define MAVLINK_MSG_ID_${name}_LEN ${wire_length}
+#define MAVLINK_MSG_ID_${id}_LEN ${wire_length}
+
+${{array_fields:#define MAVLINK_MSG_${msg_name}_FIELD_${name_upper}_LEN ${array_length}
+}}
+
+#define MAVLINK_MESSAGE_INFO_${name} { \\
+ "${name}", \\
+ ${num_fields}, \\
+ { ${{ordered_fields: { "${name}", ${c_print_format}, MAVLINK_TYPE_${type_upper}, ${array_length}, ${wire_offset}, offsetof(mavlink_${name_lower}_t, ${name}) }, \\
+ }} } \\
+}
+
+
+/**
+ * @brief Pack a ${name_lower} 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
+ *
+${{arg_fields: * @param ${name} ${description}
+}}
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_${name_lower}_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ ${{arg_fields: ${array_const}${type} ${array_prefix}${name},}})
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[${wire_length}];
+${{scalar_fields: _mav_put_${type}(buf, ${wire_offset}, ${putname});
+}}
+${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length});
+}}
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, ${wire_length});
+#else
+ mavlink_${name_lower}_t packet;
+${{scalar_fields: packet.${name} = ${putname};
+}}
+${{array_fields: mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length});
+}}
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, ${wire_length});
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_${name};
+ return mavlink_finalize_message(msg, system_id, component_id, ${wire_length}${crc_extra_arg});
+}
+
+/**
+ * @brief Pack a ${name_lower} 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
+${{arg_fields: * @param ${name} ${description}
+}}
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_${name_lower}_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ ${{arg_fields:${array_const}${type} ${array_prefix}${name},}})
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[${wire_length}];
+${{scalar_fields: _mav_put_${type}(buf, ${wire_offset}, ${putname});
+}}
+${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length});
+}}
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, ${wire_length});
+#else
+ mavlink_${name_lower}_t packet;
+${{scalar_fields: packet.${name} = ${putname};
+}}
+${{array_fields: mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length});
+}}
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, ${wire_length});
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_${name};
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, ${wire_length}${crc_extra_arg});
+}
+
+/**
+ * @brief Encode a ${name_lower} 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 ${name_lower} C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_${name_lower}_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_${name_lower}_t* ${name_lower})
+{
+ return mavlink_msg_${name_lower}_pack(system_id, component_id, msg,${{arg_fields: ${name_lower}->${name},}});
+}
+
+/**
+ * @brief Send a ${name_lower} message
+ * @param chan MAVLink channel to send the message
+ *
+${{arg_fields: * @param ${name} ${description}
+}}
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_${name_lower}_send(mavlink_channel_t chan,${{arg_fields: ${array_const}${type} ${array_prefix}${name},}})
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[${wire_length}];
+${{scalar_fields: _mav_put_${type}(buf, ${wire_offset}, ${putname});
+}}
+${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length});
+}}
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_${name}, buf, ${wire_length}${crc_extra_arg});
+#else
+ mavlink_${name_lower}_t packet;
+${{scalar_fields: packet.${name} = ${putname};
+}}
+${{array_fields: mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length});
+}}
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_${name}, (const char *)&packet, ${wire_length}${crc_extra_arg});
+#endif
+}
+
+#endif
+
+// MESSAGE ${name} UNPACKING
+
+${{fields:
+/**
+ * @brief Get field ${name} from ${name_lower} message
+ *
+ * @return ${description}
+ */
+static inline ${return_type} mavlink_msg_${name_lower}_get_${name}(const mavlink_message_t* msg${get_arg})
+{
+ return _MAV_RETURN_${type}${array_tag}(msg, ${array_return_arg} ${wire_offset});
+}
+}}
+
+/**
+ * @brief Decode a ${name_lower} message into a struct
+ *
+ * @param msg The message to decode
+ * @param ${name_lower} C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_${name_lower}_decode(const mavlink_message_t* msg, mavlink_${name_lower}_t* ${name_lower})
+{
+#if MAVLINK_NEED_BYTE_SWAP
+${{ordered_fields: ${decode_left}mavlink_msg_${name_lower}_get_${name}(msg${decode_right});
+}}
+#else
+ memcpy(${name_lower}, _MAV_PAYLOAD(msg), ${wire_length});
+#endif
+}
+''', m)
+ f.close()
+
+
+def generate_testsuite_h(directory, xml):
+ '''generate testsuite.h per XML file'''
+ f = open(os.path.join(directory, "testsuite.h"), mode='w')
+ t.write(f, '''
+/** @file
+ * @brief MAVLink comm protocol testsuite generated from ${basename}.xml
+ * @see http://qgroundcontrol.org/mavlink/
+ */
+#ifndef ${basename_upper}_TESTSUITE_H
+#define ${basename_upper}_TESTSUITE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#ifndef MAVLINK_TEST_ALL
+#define MAVLINK_TEST_ALL
+${{include_list:static void mavlink_test_${base}(uint8_t, uint8_t, mavlink_message_t *last_msg);
+}}
+static void mavlink_test_${basename}(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)
+{
+${{include_list: mavlink_test_${base}(system_id, component_id, last_msg);
+}}
+ mavlink_test_${basename}(system_id, component_id, last_msg);
+}
+#endif
+
+${{include_list:#include "../${base}/testsuite.h"
+}}
+
+${{message:
+static void mavlink_test_${name_lower}(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_${name_lower}_t packet_in = {
+ ${{ordered_fields:${c_test_value},
+ }}};
+ mavlink_${name_lower}_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ ${{scalar_fields: packet1.${name} = packet_in.${name};
+ }}
+ ${{array_fields: mav_array_memcpy(packet1.${name}, packet_in.${name}, sizeof(${type})*${array_length});
+ }}
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_${name_lower}_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_${name_lower}_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_${name_lower}_pack(system_id, component_id, &msg ${{arg_fields:, packet1.${name} }});
+ mavlink_msg_${name_lower}_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_${name_lower}_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg ${{arg_fields:, packet1.${name} }});
+ mavlink_msg_${name_lower}_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_${name_lower}_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_${name_lower}_send(MAVLINK_COMM_1 ${{arg_fields:, packet1.${name} }});
+ mavlink_msg_${name_lower}_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+}}
+
+static void mavlink_test_${basename}(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+${{message: mavlink_test_${name_lower}(system_id, component_id, last_msg);
+}}
+}
+
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+#endif // ${basename_upper}_TESTSUITE_H
+''', xml)
+
+ f.close()
+
+def copy_fixed_headers(directory, xml):
+ '''copy the fixed protocol headers to the target directory'''
+ import shutil
+ hlist = [ 'protocol.h', 'mavlink_helpers.h', 'mavlink_types.h', 'checksum.h', 'mavlink_protobuf_manager.hpp' ]
+ basepath = os.path.dirname(os.path.realpath(__file__))
+ srcpath = os.path.join(basepath, 'C/include_v%s' % xml.wire_protocol_version)
+ print("Copying fixed headers")
+ for h in hlist:
+ if (not (h == 'mavlink_protobuf_manager.hpp' and xml.wire_protocol_version == '0.9')):
+ src = os.path.realpath(os.path.join(srcpath, h))
+ dest = os.path.realpath(os.path.join(directory, h))
+ if src == dest:
+ continue
+ shutil.copy(src, dest)
+ # XXX This is a hack - to be removed
+ if (xml.basename == 'pixhawk' and xml.wire_protocol_version == '1.0'):
+ h = 'pixhawk/pixhawk.pb.h'
+ src = os.path.realpath(os.path.join(srcpath, h))
+ dest = os.path.realpath(os.path.join(directory, h))
+ shutil.copy(src, dest)
+
+def copy_fixed_sources(directory, xml):
+ # XXX This is a hack - to be removed
+ import shutil
+ basepath = os.path.dirname(os.path.realpath(__file__))
+ srcpath = os.path.join(basepath, 'C/src_v%s' % xml.wire_protocol_version)
+ if (xml.basename == 'pixhawk' and xml.wire_protocol_version == '1.0'):
+ print("Copying fixed sources")
+ src = os.path.realpath(os.path.join(srcpath, 'pixhawk/pixhawk.pb.cc'))
+ dest = os.path.realpath(os.path.join(directory, '../../../share/mavlink/src/v%s/pixhawk/pixhawk.pb.cc' % xml.wire_protocol_version))
+ destdir = os.path.realpath(os.path.join(directory, '../../../share/mavlink/src/v%s/pixhawk' % xml.wire_protocol_version))
+ try:
+ os.makedirs(destdir)
+ except:
+ print("Not re-creating directory")
+ shutil.copy(src, dest)
+ print("Copied to"),
+ print(dest)
+
+class mav_include(object):
+ def __init__(self, base):
+ self.base = base
+
+def generate_one(basename, xml):
+ '''generate headers for one XML file'''
+
+ directory = os.path.join(basename, xml.basename)
+
+ print("Generating C implementation in directory %s" % directory)
+ mavparse.mkdir_p(directory)
+
+ if xml.little_endian:
+ xml.mavlink_endian = "MAVLINK_LITTLE_ENDIAN"
+ else:
+ xml.mavlink_endian = "MAVLINK_BIG_ENDIAN"
+
+ if xml.crc_extra:
+ xml.crc_extra_define = "1"
+ else:
+ xml.crc_extra_define = "0"
+
+ if xml.sort_fields:
+ xml.aligned_fields_define = "1"
+ else:
+ xml.aligned_fields_define = "0"
+
+ # work out the included headers
+ xml.include_list = []
+ for i in xml.include:
+ base = i[:-4]
+ xml.include_list.append(mav_include(base))
+
+ # form message lengths array
+ xml.message_lengths_array = ''
+ for mlen in xml.message_lengths:
+ xml.message_lengths_array += '%u, ' % mlen
+ xml.message_lengths_array = xml.message_lengths_array[:-2]
+
+ # and message CRCs array
+ xml.message_crcs_array = ''
+ for crc in xml.message_crcs:
+ xml.message_crcs_array += '%u, ' % crc
+ xml.message_crcs_array = xml.message_crcs_array[:-2]
+
+ # form message info array
+ xml.message_info_array = ''
+ for name in xml.message_names:
+ if name is not None:
+ xml.message_info_array += 'MAVLINK_MESSAGE_INFO_%s, ' % name
+ else:
+ # Several C compilers don't accept {NULL} for
+ # multi-dimensional arrays and structs
+ # feed the compiler a "filled" empty message
+ xml.message_info_array += '{"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, '
+ xml.message_info_array = xml.message_info_array[:-2]
+
+ # add some extra field attributes for convenience with arrays
+ for m in xml.message:
+ m.msg_name = m.name
+ if xml.crc_extra:
+ m.crc_extra_arg = ", %s" % m.crc_extra
+ else:
+ m.crc_extra_arg = ""
+ for f in m.fields:
+ if f.print_format is None:
+ f.c_print_format = 'NULL'
+ else:
+ f.c_print_format = '"%s"' % f.print_format
+ if f.array_length != 0:
+ f.array_suffix = '[%u]' % f.array_length
+ f.array_prefix = '*'
+ f.array_tag = '_array'
+ f.array_arg = ', %u' % f.array_length
+ f.array_return_arg = '%s, %u, ' % (f.name, f.array_length)
+ f.array_const = 'const '
+ f.decode_left = ''
+ f.decode_right = ', %s->%s' % (m.name_lower, f.name)
+ f.return_type = 'uint16_t'
+ f.get_arg = ', %s *%s' % (f.type, f.name)
+ if f.type == 'char':
+ f.c_test_value = '"%s"' % f.test_value
+ else:
+ test_strings = []
+ for v in f.test_value:
+ test_strings.append(str(v))
+ f.c_test_value = '{ %s }' % ', '.join(test_strings)
+ else:
+ f.array_suffix = ''
+ f.array_prefix = ''
+ f.array_tag = ''
+ f.array_arg = ''
+ f.array_return_arg = ''
+ f.array_const = ''
+ f.decode_left = "%s->%s = " % (m.name_lower, f.name)
+ f.decode_right = ''
+ f.get_arg = ''
+ f.return_type = f.type
+ if f.type == 'char':
+ f.c_test_value = "'%s'" % f.test_value
+ elif f.type == 'uint64_t':
+ f.c_test_value = "%sULL" % f.test_value
+ elif f.type == 'int64_t':
+ f.c_test_value = "%sLL" % f.test_value
+ else:
+ f.c_test_value = f.test_value
+
+ # cope with uint8_t_mavlink_version
+ for m in xml.message:
+ m.arg_fields = []
+ m.array_fields = []
+ m.scalar_fields = []
+ for f in m.ordered_fields:
+ if f.array_length != 0:
+ m.array_fields.append(f)
+ else:
+ m.scalar_fields.append(f)
+ for f in m.fields:
+ if not f.omit_arg:
+ m.arg_fields.append(f)
+ f.putname = f.name
+ else:
+ f.putname = f.const_value
+
+ generate_mavlink_h(directory, xml)
+ generate_version_h(directory, xml)
+ generate_main_h(directory, xml)
+ for m in xml.message:
+ generate_message_h(directory, m)
+ generate_testsuite_h(directory, xml)
+
+
+def generate(basename, xml_list):
+ '''generate complete MAVLink C implemenation'''
+
+ for xml in xml_list:
+ generate_one(basename, xml)
+ copy_fixed_headers(basename, xml_list[0])
+ copy_fixed_sources(basename, xml_list[0])
diff --git a/mavlink/share/pyshared/pymavlink/generator/mavgen_python.py b/mavlink/share/pyshared/pymavlink/generator/mavgen_python.py
new file mode 100644
index 000000000..fad366a68
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/mavgen_python.py
@@ -0,0 +1,455 @@
+#!/usr/bin/env python
+'''
+parse a MAVLink protocol XML file and generate a python implementation
+
+Copyright Andrew Tridgell 2011
+Released under GNU GPL version 3 or later
+'''
+
+import sys, textwrap, os
+import mavparse, mavtemplate
+
+t = mavtemplate.MAVTemplate()
+
+def generate_preamble(outf, msgs, args, xml):
+ print("Generating preamble")
+ t.write(outf, """
+'''
+MAVLink protocol implementation (auto-generated by mavgen.py)
+
+Generated from: ${FILELIST}
+
+Note: this file has been auto-generated. DO NOT EDIT
+'''
+
+import struct, array, mavutil, time
+
+WIRE_PROTOCOL_VERSION = "${WIRE_PROTOCOL_VERSION}"
+
+class MAVLink_header(object):
+ '''MAVLink message header'''
+ def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0):
+ self.mlen = mlen
+ self.seq = seq
+ self.srcSystem = srcSystem
+ self.srcComponent = srcComponent
+ self.msgId = msgId
+
+ def pack(self):
+ return struct.pack('BBBBBB', ${PROTOCOL_MARKER}, self.mlen, self.seq,
+ self.srcSystem, self.srcComponent, self.msgId)
+
+class MAVLink_message(object):
+ '''base MAVLink message class'''
+ def __init__(self, msgId, name):
+ self._header = MAVLink_header(msgId)
+ self._payload = None
+ self._msgbuf = None
+ self._crc = None
+ self._fieldnames = []
+ self._type = name
+
+ def get_msgbuf(self):
+ return self._msgbuf
+
+ def get_header(self):
+ return self._header
+
+ def get_payload(self):
+ return self._payload
+
+ def get_crc(self):
+ return self._crc
+
+ def get_fieldnames(self):
+ return self._fieldnames
+
+ def get_type(self):
+ return self._type
+
+ def get_msgId(self):
+ return self._header.msgId
+
+ def get_srcSystem(self):
+ return self._header.srcSystem
+
+ def get_srcComponent(self):
+ return self._header.srcComponent
+
+ def get_seq(self):
+ return self._header.seq
+
+ def __str__(self):
+ ret = '%s {' % self._type
+ for a in self._fieldnames:
+ v = getattr(self, a)
+ ret += '%s : %s, ' % (a, v)
+ ret = ret[0:-2] + '}'
+ return ret
+
+ def pack(self, mav, crc_extra, payload):
+ self._payload = payload
+ self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq,
+ mav.srcSystem, mav.srcComponent)
+ self._msgbuf = self._header.pack() + payload
+ crc = mavutil.x25crc(self._msgbuf[1:])
+ if ${crc_extra}: # using CRC extra
+ crc.accumulate(chr(crc_extra))
+ self._crc = crc.crc
+ self._msgbuf += struct.pack('<H', self._crc)
+ return self._msgbuf
+
+""", {'FILELIST' : ",".join(args),
+ 'PROTOCOL_MARKER' : xml.protocol_marker,
+ 'crc_extra' : xml.crc_extra,
+ 'WIRE_PROTOCOL_VERSION' : xml.wire_protocol_version })
+
+
+def generate_enums(outf, enums):
+ print("Generating enums")
+ outf.write("\n# enums\n")
+ wrapper = textwrap.TextWrapper(initial_indent="", subsequent_indent=" # ")
+ for e in enums:
+ outf.write("\n# %s\n" % e.name)
+ for entry in e.entry:
+ outf.write("%s = %u # %s\n" % (entry.name, entry.value, wrapper.fill(entry.description)))
+
+def generate_message_ids(outf, msgs):
+ print("Generating message IDs")
+ outf.write("\n# message IDs\n")
+ outf.write("MAVLINK_MSG_ID_BAD_DATA = -1\n")
+ for m in msgs:
+ outf.write("MAVLINK_MSG_ID_%s = %u\n" % (m.name.upper(), m.id))
+
+def generate_classes(outf, msgs):
+ print("Generating class definitions")
+ wrapper = textwrap.TextWrapper(initial_indent=" ", subsequent_indent=" ")
+ for m in msgs:
+ outf.write("""
+class MAVLink_%s_message(MAVLink_message):
+ '''
+%s
+ '''
+ def __init__(self""" % (m.name.lower(), wrapper.fill(m.description.strip())))
+ if len(m.fields) != 0:
+ outf.write(", " + ", ".join(m.fieldnames))
+ outf.write("):\n")
+ outf.write(" MAVLink_message.__init__(self, MAVLINK_MSG_ID_%s, '%s')\n" % (m.name.upper(), m.name.upper()))
+ if len(m.fieldnames) != 0:
+ outf.write(" self._fieldnames = ['%s']\n" % "', '".join(m.fieldnames))
+ for f in m.fields:
+ outf.write(" self.%s = %s\n" % (f.name, f.name))
+ outf.write("""
+ def pack(self, mav):
+ return MAVLink_message.pack(self, mav, %u, struct.pack('%s'""" % (m.crc_extra, m.fmtstr))
+ if len(m.fields) != 0:
+ outf.write(", self." + ", self.".join(m.ordered_fieldnames))
+ outf.write("))\n")
+
+
+def mavfmt(field):
+ '''work out the struct format for a type'''
+ map = {
+ 'float' : 'f',
+ 'double' : 'd',
+ 'char' : 'c',
+ 'int8_t' : 'b',
+ 'uint8_t' : 'B',
+ 'uint8_t_mavlink_version' : 'B',
+ 'int16_t' : 'h',
+ 'uint16_t' : 'H',
+ 'int32_t' : 'i',
+ 'uint32_t' : 'I',
+ 'int64_t' : 'q',
+ 'uint64_t' : 'Q',
+ }
+
+ if field.array_length:
+ if field.type in ['char', 'int8_t', 'uint8_t']:
+ return str(field.array_length)+'s'
+ return str(field.array_length)+map[field.type]
+ return map[field.type]
+
+def generate_mavlink_class(outf, msgs, xml):
+ print("Generating MAVLink class")
+
+ outf.write("\n\nmavlink_map = {\n");
+ for m in msgs:
+ outf.write(" MAVLINK_MSG_ID_%s : ( '%s', MAVLink_%s_message, %s, %u ),\n" % (
+ m.name.upper(), m.fmtstr, m.name.lower(), m.order_map, m.crc_extra))
+ outf.write("}\n\n")
+
+ t.write(outf, """
+class MAVError(Exception):
+ '''MAVLink error class'''
+ def __init__(self, msg):
+ Exception.__init__(self, msg)
+ self.message = msg
+
+class MAVString(str):
+ '''NUL terminated string'''
+ def __init__(self, s):
+ str.__init__(self)
+ def __str__(self):
+ i = self.find(chr(0))
+ if i == -1:
+ return self[:]
+ return self[0:i]
+
+class MAVLink_bad_data(MAVLink_message):
+ '''
+ a piece of bad data in a mavlink stream
+ '''
+ def __init__(self, data, reason):
+ MAVLink_message.__init__(self, MAVLINK_MSG_ID_BAD_DATA, 'BAD_DATA')
+ self._fieldnames = ['data', 'reason']
+ self.data = data
+ self.reason = reason
+ self._msgbuf = data
+
+class MAVLink(object):
+ '''MAVLink protocol handling class'''
+ def __init__(self, file, srcSystem=0, srcComponent=0):
+ self.seq = 0
+ self.file = file
+ self.srcSystem = srcSystem
+ self.srcComponent = srcComponent
+ self.callback = None
+ self.callback_args = None
+ self.callback_kwargs = None
+ self.buf = array.array('B')
+ self.expected_length = 6
+ self.have_prefix_error = False
+ self.robust_parsing = False
+ self.protocol_marker = ${protocol_marker}
+ self.little_endian = ${little_endian}
+ self.crc_extra = ${crc_extra}
+ self.sort_fields = ${sort_fields}
+ self.total_packets_sent = 0
+ self.total_bytes_sent = 0
+ self.total_packets_received = 0
+ self.total_bytes_received = 0
+ self.total_receive_errors = 0
+ self.startup_time = time.time()
+
+ def set_callback(self, callback, *args, **kwargs):
+ self.callback = callback
+ self.callback_args = args
+ self.callback_kwargs = kwargs
+
+ def send(self, mavmsg):
+ '''send a MAVLink message'''
+ buf = mavmsg.pack(self)
+ self.file.write(buf)
+ self.seq = (self.seq + 1) % 255
+ self.total_packets_sent += 1
+ self.total_bytes_sent += len(buf)
+
+ def bytes_needed(self):
+ '''return number of bytes needed for next parsing stage'''
+ ret = self.expected_length - len(self.buf)
+ if ret <= 0:
+ return 1
+ return ret
+
+ def parse_char(self, c):
+ '''input some data bytes, possibly returning a new message'''
+ if isinstance(c, str):
+ self.buf.fromstring(c)
+ else:
+ self.buf.extend(c)
+ self.total_bytes_received += len(c)
+ if len(self.buf) >= 1 and self.buf[0] != ${protocol_marker}:
+ magic = self.buf[0]
+ self.buf = self.buf[1:]
+ if self.robust_parsing:
+ m = MAVLink_bad_data(chr(magic), "Bad prefix")
+ if self.callback:
+ self.callback(m, *self.callback_args, **self.callback_kwargs)
+ self.expected_length = 6
+ self.total_receive_errors += 1
+ return m
+ if self.have_prefix_error:
+ return None
+ self.have_prefix_error = True
+ self.total_receive_errors += 1
+ raise MAVError("invalid MAVLink prefix '%s'" % magic)
+ self.have_prefix_error = False
+ if len(self.buf) >= 2:
+ (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2])
+ self.expected_length += 8
+ if self.expected_length >= 8 and len(self.buf) >= self.expected_length:
+ mbuf = self.buf[0:self.expected_length]
+ self.buf = self.buf[self.expected_length:]
+ self.expected_length = 6
+ if self.robust_parsing:
+ try:
+ m = self.decode(mbuf)
+ self.total_packets_received += 1
+ except MAVError as reason:
+ m = MAVLink_bad_data(mbuf, reason.message)
+ self.total_receive_errors += 1
+ else:
+ m = self.decode(mbuf)
+ self.total_packets_received += 1
+ if self.callback:
+ self.callback(m, *self.callback_args, **self.callback_kwargs)
+ return m
+ return None
+
+ def parse_buffer(self, s):
+ '''input some data bytes, possibly returning a list of new messages'''
+ m = self.parse_char(s)
+ if m is None:
+ return None
+ ret = [m]
+ while True:
+ m = self.parse_char("")
+ if m is None:
+ return ret
+ ret.append(m)
+ return ret
+
+ def decode(self, msgbuf):
+ '''decode a buffer as a MAVLink message'''
+ # decode the header
+ try:
+ magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6])
+ except struct.error as emsg:
+ raise MAVError('Unable to unpack MAVLink header: %s' % emsg)
+ if ord(magic) != ${protocol_marker}:
+ raise MAVError("invalid MAVLink prefix '%s'" % magic)
+ if mlen != len(msgbuf)-8:
+ raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId))
+
+ if not msgId in mavlink_map:
+ raise MAVError('unknown MAVLink message ID %u' % msgId)
+
+ # decode the payload
+ (fmt, type, order_map, crc_extra) = mavlink_map[msgId]
+
+ # decode the checksum
+ try:
+ crc, = struct.unpack('<H', msgbuf[-2:])
+ except struct.error as emsg:
+ raise MAVError('Unable to unpack MAVLink CRC: %s' % emsg)
+ crc2 = mavutil.x25crc(msgbuf[1:-2])
+ if ${crc_extra}: # using CRC extra
+ crc2.accumulate(chr(crc_extra))
+ if crc != crc2.crc:
+ raise MAVError('invalid MAVLink CRC in msgID %u 0x%04x should be 0x%04x' % (msgId, crc, crc2.crc))
+
+ try:
+ t = struct.unpack(fmt, msgbuf[6:-2])
+ except struct.error as emsg:
+ raise MAVError('Unable to unpack MAVLink payload type=%s fmt=%s payloadLength=%u: %s' % (
+ type, fmt, len(msgbuf[6:-2]), emsg))
+
+ tlist = list(t)
+ # handle sorted fields
+ if ${sort_fields}:
+ t = tlist[:]
+ for i in range(0, len(tlist)):
+ tlist[i] = t[order_map[i]]
+
+ # terminate any strings
+ for i in range(0, len(tlist)):
+ if isinstance(tlist[i], str):
+ tlist[i] = MAVString(tlist[i])
+ t = tuple(tlist)
+ # construct the message object
+ try:
+ m = type(*t)
+ except Exception as emsg:
+ raise MAVError('Unable to instantiate MAVLink message of type %s : %s' % (type, emsg))
+ m._msgbuf = msgbuf
+ m._payload = msgbuf[6:-2]
+ m._crc = crc
+ m._header = MAVLink_header(msgId, mlen, seq, srcSystem, srcComponent)
+ return m
+""", xml)
+
+def generate_methods(outf, msgs):
+ print("Generating methods")
+
+ def field_descriptions(fields):
+ ret = ""
+ for f in fields:
+ ret += " %-18s : %s (%s)\n" % (f.name, f.description.strip(), f.type)
+ return ret
+
+ wrapper = textwrap.TextWrapper(initial_indent="", subsequent_indent=" ")
+
+ for m in msgs:
+ comment = "%s\n\n%s" % (wrapper.fill(m.description.strip()), field_descriptions(m.fields))
+
+ selffieldnames = 'self, '
+ for f in m.fields:
+ if f.omit_arg:
+ selffieldnames += '%s=%s, ' % (f.name, f.const_value)
+ else:
+ selffieldnames += '%s, ' % f.name
+ selffieldnames = selffieldnames[:-2]
+
+ sub = {'NAMELOWER' : m.name.lower(),
+ 'SELFFIELDNAMES' : selffieldnames,
+ 'COMMENT' : comment,
+ 'FIELDNAMES' : ", ".join(m.fieldnames)}
+
+ t.write(outf, """
+ def ${NAMELOWER}_encode(${SELFFIELDNAMES}):
+ '''
+ ${COMMENT}
+ '''
+ msg = MAVLink_${NAMELOWER}_message(${FIELDNAMES})
+ msg.pack(self)
+ return msg
+
+""", sub)
+
+ t.write(outf, """
+ def ${NAMELOWER}_send(${SELFFIELDNAMES}):
+ '''
+ ${COMMENT}
+ '''
+ return self.send(self.${NAMELOWER}_encode(${FIELDNAMES}))
+
+""", sub)
+
+
+def generate(basename, xml):
+ '''generate complete python implemenation'''
+ if basename.endswith('.py'):
+ filename = basename
+ else:
+ filename = basename + '.py'
+
+ msgs = []
+ enums = []
+ filelist = []
+ for x in xml:
+ msgs.extend(x.message)
+ enums.extend(x.enum)
+ filelist.append(os.path.basename(x.filename))
+
+ for m in msgs:
+ if xml[0].little_endian:
+ m.fmtstr = '<'
+ else:
+ m.fmtstr = '>'
+ for f in m.ordered_fields:
+ m.fmtstr += mavfmt(f)
+ m.order_map = [ 0 ] * len(m.fieldnames)
+ for i in range(0, len(m.fieldnames)):
+ m.order_map[i] = m.ordered_fieldnames.index(m.fieldnames[i])
+
+ print("Generating %s" % filename)
+ outf = open(filename, "w")
+ generate_preamble(outf, msgs, filelist, xml[0])
+ generate_enums(outf, enums)
+ generate_message_ids(outf, msgs)
+ generate_classes(outf, msgs)
+ generate_mavlink_class(outf, msgs, xml[0])
+ generate_methods(outf, msgs)
+ outf.close()
+ print("Generated %s OK" % filename)
diff --git a/mavlink/share/pyshared/pymavlink/generator/mavparse.py b/mavlink/share/pyshared/pymavlink/generator/mavparse.py
new file mode 100644
index 000000000..cd2e6a55f
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/mavparse.py
@@ -0,0 +1,372 @@
+#!/usr/bin/env python
+'''
+mavlink python parse functions
+
+Copyright Andrew Tridgell 2011
+Released under GNU GPL version 3 or later
+'''
+
+import xml.parsers.expat, os, errno, time, sys, operator, mavutil
+
+PROTOCOL_0_9 = "0.9"
+PROTOCOL_1_0 = "1.0"
+
+class MAVParseError(Exception):
+ def __init__(self, message, inner_exception=None):
+ self.message = message
+ self.inner_exception = inner_exception
+ self.exception_info = sys.exc_info()
+ def __str__(self):
+ return self.message
+
+class MAVField(object):
+ def __init__(self, name, type, print_format, xml, description=''):
+ self.name = name
+ self.name_upper = name.upper()
+ self.description = description
+ self.array_length = 0
+ self.omit_arg = False
+ self.const_value = None
+ self.print_format = print_format
+ lengths = {
+ 'float' : 4,
+ 'double' : 8,
+ 'char' : 1,
+ 'int8_t' : 1,
+ 'uint8_t' : 1,
+ 'uint8_t_mavlink_version' : 1,
+ 'int16_t' : 2,
+ 'uint16_t' : 2,
+ 'int32_t' : 4,
+ 'uint32_t' : 4,
+ 'int64_t' : 8,
+ 'uint64_t' : 8,
+ }
+
+ if type=='uint8_t_mavlink_version':
+ type = 'uint8_t'
+ self.omit_arg = True
+ self.const_value = xml.version
+
+ aidx = type.find("[")
+ if aidx != -1:
+ assert type[-1:] == ']'
+ self.array_length = int(type[aidx+1:-1])
+ type = type[0:aidx]
+ if type == 'array':
+ type = 'int8_t'
+ if type in lengths:
+ self.type_length = lengths[type]
+ self.type = type
+ elif (type+"_t") in lengths:
+ self.type_length = lengths[type+"_t"]
+ self.type = type+'_t'
+ else:
+ raise MAVParseError("unknown type '%s'" % type)
+ if self.array_length != 0:
+ self.wire_length = self.array_length * self.type_length
+ else:
+ self.wire_length = self.type_length
+ self.type_upper = self.type.upper()
+
+ def gen_test_value(self, i):
+ '''generate a testsuite value for a MAVField'''
+ if self.const_value:
+ return self.const_value
+ elif self.type == 'float':
+ return 17.0 + self.wire_offset*7 + i
+ elif self.type == 'double':
+ return 123.0 + self.wire_offset*7 + i
+ elif self.type == 'char':
+ return chr(ord('A') + (self.wire_offset + i)%26)
+ elif self.type in [ 'int8_t', 'uint8_t' ]:
+ return (5 + self.wire_offset*67 + i) & 0xFF
+ elif self.type in ['int16_t', 'uint16_t']:
+ return (17235 + self.wire_offset*52 + i) & 0xFFFF
+ elif self.type in ['int32_t', 'uint32_t']:
+ return (963497464 + self.wire_offset*52 + i)&0xFFFFFFFF
+ elif self.type in ['int64_t', 'uint64_t']:
+ return 93372036854775807 + self.wire_offset*63 + i
+ else:
+ raise MAVError('unknown type %s' % self.type)
+
+ def set_test_value(self):
+ '''set a testsuite value for a MAVField'''
+ if self.array_length:
+ self.test_value = []
+ for i in range(self.array_length):
+ self.test_value.append(self.gen_test_value(i))
+ else:
+ self.test_value = self.gen_test_value(0)
+ if self.type == 'char' and self.array_length:
+ v = ""
+ for c in self.test_value:
+ v += c
+ self.test_value = v[:-1]
+
+
+class MAVType(object):
+ def __init__(self, name, id, linenumber, description=''):
+ self.name = name
+ self.name_lower = name.lower()
+ self.linenumber = linenumber
+ self.id = int(id)
+ self.description = description
+ self.fields = []
+ self.fieldnames = []
+
+class MAVEnumParam(object):
+ def __init__(self, index, description=''):
+ self.index = index
+ self.description = description
+
+class MAVEnumEntry(object):
+ def __init__(self, name, value, description='', end_marker=False):
+ self.name = name
+ self.value = value
+ self.description = description
+ self.param = []
+ self.end_marker = end_marker
+
+class MAVEnum(object):
+ def __init__(self, name, linenumber, description=''):
+ self.name = name
+ self.description = description
+ self.entry = []
+ self.highest_value = 0
+ self.linenumber = linenumber
+
+class MAVXML(object):
+ '''parse a mavlink XML file'''
+ def __init__(self, filename, wire_protocol_version=PROTOCOL_0_9):
+ self.filename = filename
+ self.basename = os.path.basename(filename)
+ if self.basename.lower().endswith(".xml"):
+ self.basename = self.basename[:-4]
+ self.basename_upper = self.basename.upper()
+ self.message = []
+ self.enum = []
+ self.parse_time = time.asctime()
+ self.version = 2
+ self.include = []
+ self.wire_protocol_version = wire_protocol_version
+
+ if wire_protocol_version == PROTOCOL_0_9:
+ self.protocol_marker = ord('U')
+ self.sort_fields = False
+ self.little_endian = False
+ self.crc_extra = False
+ elif wire_protocol_version == PROTOCOL_1_0:
+ self.protocol_marker = 0xFE
+ self.sort_fields = True
+ self.little_endian = True
+ self.crc_extra = True
+ else:
+ print("Unknown wire protocol version")
+ print("Available versions are: %s %s" % (PROTOCOL_0_9, PROTOCOL_1_0))
+ raise MAVParseError('Unknown MAVLink wire protocol version %s' % wire_protocol_version)
+
+ in_element_list = []
+
+ def check_attrs(attrs, check, where):
+ for c in check:
+ if not c in attrs:
+ raise MAVParseError('expected missing %s "%s" attribute at %s:%u' % (
+ where, c, filename, p.CurrentLineNumber))
+
+ def start_element(name, attrs):
+ in_element_list.append(name)
+ in_element = '.'.join(in_element_list)
+ #print in_element
+ if in_element == "mavlink.messages.message":
+ check_attrs(attrs, ['name', 'id'], 'message')
+ self.message.append(MAVType(attrs['name'], attrs['id'], p.CurrentLineNumber))
+ elif in_element == "mavlink.messages.message.field":
+ check_attrs(attrs, ['name', 'type'], 'field')
+ if 'print_format' in attrs:
+ print_format = attrs['print_format']
+ else:
+ print_format = None
+ self.message[-1].fields.append(MAVField(attrs['name'], attrs['type'],
+ print_format, self))
+ elif in_element == "mavlink.enums.enum":
+ check_attrs(attrs, ['name'], 'enum')
+ self.enum.append(MAVEnum(attrs['name'], p.CurrentLineNumber))
+ elif in_element == "mavlink.enums.enum.entry":
+ check_attrs(attrs, ['name'], 'enum entry')
+ if 'value' in attrs:
+ value = int(attrs['value'])
+ else:
+ value = self.enum[-1].highest_value + 1
+ if (value > self.enum[-1].highest_value):
+ self.enum[-1].highest_value = value
+ self.enum[-1].entry.append(MAVEnumEntry(attrs['name'], value))
+ elif in_element == "mavlink.enums.enum.entry.param":
+ check_attrs(attrs, ['index'], 'enum param')
+ self.enum[-1].entry[-1].param.append(MAVEnumParam(attrs['index']))
+
+ def end_element(name):
+ in_element = '.'.join(in_element_list)
+ if in_element == "mavlink.enums.enum":
+ # add a ENUM_END
+ self.enum[-1].entry.append(MAVEnumEntry("%s_ENUM_END" % self.enum[-1].name,
+ self.enum[-1].highest_value+1, end_marker=True))
+ in_element_list.pop()
+
+ def char_data(data):
+ in_element = '.'.join(in_element_list)
+ if in_element == "mavlink.messages.message.description":
+ self.message[-1].description += data
+ elif in_element == "mavlink.messages.message.field":
+ self.message[-1].fields[-1].description += data
+ elif in_element == "mavlink.enums.enum.description":
+ self.enum[-1].description += data
+ elif in_element == "mavlink.enums.enum.entry.description":
+ self.enum[-1].entry[-1].description += data
+ elif in_element == "mavlink.enums.enum.entry.param":
+ self.enum[-1].entry[-1].param[-1].description += data
+ elif in_element == "mavlink.version":
+ self.version = int(data)
+ elif in_element == "mavlink.include":
+ self.include.append(data)
+
+ f = open(filename, mode='rb')
+ p = xml.parsers.expat.ParserCreate()
+ p.StartElementHandler = start_element
+ p.EndElementHandler = end_element
+ p.CharacterDataHandler = char_data
+ p.ParseFile(f)
+ f.close()
+
+ self.message_lengths = [ 0 ] * 256
+ self.message_crcs = [ 0 ] * 256
+ self.message_names = [ None ] * 256
+ self.largest_payload = 0
+
+ for m in self.message:
+ m.wire_length = 0
+ m.fieldnames = []
+ m.ordered_fieldnames = []
+ if self.sort_fields:
+ m.ordered_fields = sorted(m.fields,
+ key=operator.attrgetter('type_length'),
+ reverse=True)
+ else:
+ m.ordered_fields = m.fields
+ for f in m.fields:
+ m.fieldnames.append(f.name)
+ for f in m.ordered_fields:
+ f.wire_offset = m.wire_length
+ m.wire_length += f.wire_length
+ m.ordered_fieldnames.append(f.name)
+ f.set_test_value()
+ m.num_fields = len(m.fieldnames)
+ if m.num_fields > 64:
+ raise MAVParseError("num_fields=%u : Maximum number of field names allowed is" % (
+ m.num_fields, 64))
+ m.crc_extra = message_checksum(m)
+ self.message_lengths[m.id] = m.wire_length
+ self.message_names[m.id] = m.name
+ self.message_crcs[m.id] = m.crc_extra
+ if m.wire_length > self.largest_payload:
+ self.largest_payload = m.wire_length
+
+ if m.wire_length+8 > 64:
+ print("Note: message %s is longer than 64 bytes long (%u bytes), which can cause fragmentation since many radio modems use 64 bytes as maximum air transfer unit." % (m.name, m.wire_length+8))
+
+ def __str__(self):
+ return "MAVXML for %s from %s (%u message, %u enums)" % (
+ self.basename, self.filename, len(self.message), len(self.enum))
+
+
+def message_checksum(msg):
+ '''calculate a 8-bit checksum of the key fields of a message, so we
+ can detect incompatible XML changes'''
+ crc = mavutil.x25crc(msg.name + ' ')
+ for f in msg.ordered_fields:
+ crc.accumulate(f.type + ' ')
+ crc.accumulate(f.name + ' ')
+ if f.array_length:
+ crc.accumulate(chr(f.array_length))
+ return (crc.crc&0xFF) ^ (crc.crc>>8)
+
+def merge_enums(xml):
+ '''merge enums between XML files'''
+ emap = {}
+ for x in xml:
+ newenums = []
+ for enum in x.enum:
+ if enum.name in emap:
+ emap[enum.name].entry.pop() # remove end marker
+ emap[enum.name].entry.extend(enum.entry)
+ print("Merged enum %s" % enum.name)
+ else:
+ newenums.append(enum)
+ emap[enum.name] = enum
+ x.enum = newenums
+ # sort by value
+ for e in emap:
+ emap[e].entry = sorted(emap[e].entry,
+ key=operator.attrgetter('value'),
+ reverse=False)
+
+
+def check_duplicates(xml):
+ '''check for duplicate message IDs'''
+
+ merge_enums(xml)
+
+ msgmap = {}
+ enummap = {}
+ for x in xml:
+ for m in x.message:
+ if m.id in msgmap:
+ print("ERROR: Duplicate message id %u for %s (%s:%u) also used by %s" % (
+ m.id, m.name,
+ x.filename, m.linenumber,
+ msgmap[m.id]))
+ return True
+ fieldset = set()
+ for f in m.fields:
+ if f.name in fieldset:
+ print("ERROR: Duplicate field %s in message %s (%s:%u)" % (
+ f.name, m.name,
+ x.filename, m.linenumber))
+ return True
+ fieldset.add(f.name)
+ msgmap[m.id] = '%s (%s:%u)' % (m.name, x.filename, m.linenumber)
+ for enum in x.enum:
+ for entry in enum.entry:
+ s1 = "%s.%s" % (enum.name, entry.name)
+ s2 = "%s.%s" % (enum.name, entry.value)
+ if s1 in enummap or s2 in enummap:
+ print("ERROR: Duplicate enums %s/%s at %s:%u and %s" % (
+ s1, entry.value, x.filename, enum.linenumber,
+ enummap.get(s1) or enummap.get(s2)))
+ return True
+ enummap[s1] = "%s:%u" % (x.filename, enum.linenumber)
+ enummap[s2] = "%s:%u" % (x.filename, enum.linenumber)
+
+ return False
+
+
+
+def total_msgs(xml):
+ '''count total number of msgs'''
+ count = 0
+ for x in xml:
+ count += len(x.message)
+ return count
+
+def mkdir_p(dir):
+ try:
+ os.makedirs(dir)
+ except OSError as exc:
+ if exc.errno == errno.EEXIST:
+ pass
+ else: raise
+
+# check version consistent
+# add test.xml
+# finish test suite
+# printf style error macro, if defined call errors
diff --git a/mavlink/share/pyshared/pymavlink/generator/mavtemplate.py b/mavlink/share/pyshared/pymavlink/generator/mavtemplate.py
new file mode 100644
index 000000000..6ef015315
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/mavtemplate.py
@@ -0,0 +1,121 @@
+#!/usr/bin/env python
+'''
+simple templating system for mavlink generator
+
+Copyright Andrew Tridgell 2011
+Released under GNU GPL version 3 or later
+'''
+
+from mavparse import MAVParseError
+
+class MAVTemplate(object):
+ '''simple templating system'''
+ def __init__(self,
+ start_var_token="${",
+ end_var_token="}",
+ start_rep_token="${{",
+ end_rep_token="}}",
+ trim_leading_lf=True,
+ checkmissing=True):
+ self.start_var_token = start_var_token
+ self.end_var_token = end_var_token
+ self.start_rep_token = start_rep_token
+ self.end_rep_token = end_rep_token
+ self.trim_leading_lf = trim_leading_lf
+ self.checkmissing = checkmissing
+
+ def find_end(self, text, start_token, end_token):
+ '''find the of a token.
+ Returns the offset in the string immediately after the matching end_token'''
+ if not text.startswith(start_token):
+ raise MAVParseError("invalid token start")
+ offset = len(start_token)
+ nesting = 1
+ while nesting > 0:
+ idx1 = text[offset:].find(start_token)
+ idx2 = text[offset:].find(end_token)
+ if idx1 == -1 and idx2 == -1:
+ raise MAVParseError("token nesting error")
+ if idx1 == -1 or idx1 > idx2:
+ offset += idx2 + len(end_token)
+ nesting -= 1
+ else:
+ offset += idx1 + len(start_token)
+ nesting += 1
+ return offset
+
+ def find_var_end(self, text):
+ '''find the of a variable'''
+ return self.find_end(text, self.start_var_token, self.end_var_token)
+
+ def find_rep_end(self, text):
+ '''find the of a repitition'''
+ return self.find_end(text, self.start_rep_token, self.end_rep_token)
+
+ def substitute(self, text, subvars={},
+ trim_leading_lf=None, checkmissing=None):
+ '''substitute variables in a string'''
+
+ if trim_leading_lf is None:
+ trim_leading_lf = self.trim_leading_lf
+ if checkmissing is None:
+ checkmissing = self.checkmissing
+
+ # handle repititions
+ while True:
+ subidx = text.find(self.start_rep_token)
+ if subidx == -1:
+ break
+ endidx = self.find_rep_end(text[subidx:])
+ if endidx == -1:
+ raise MAVParseError("missing end macro in %s" % text[subidx:])
+ part1 = text[0:subidx]
+ part2 = text[subidx+len(self.start_rep_token):subidx+(endidx-len(self.end_rep_token))]
+ part3 = text[subidx+endidx:]
+ a = part2.split(':')
+ field_name = a[0]
+ rest = ':'.join(a[1:])
+ v = getattr(subvars, field_name, None)
+ if v is None:
+ raise MAVParseError('unable to find field %s' % field_name)
+ t1 = part1
+ for f in v:
+ t1 += self.substitute(rest, f, trim_leading_lf=False, checkmissing=False)
+ if len(v) != 0 and t1[-1] in ["\n", ","]:
+ t1 = t1[:-1]
+ t1 += part3
+ text = t1
+
+ if trim_leading_lf:
+ if text[0] == '\n':
+ text = text[1:]
+ while True:
+ idx = text.find(self.start_var_token)
+ if idx == -1:
+ return text
+ endidx = text[idx:].find(self.end_var_token)
+ if endidx == -1:
+ raise MAVParseError('missing end of variable: %s' % text[idx:idx+10])
+ varname = text[idx+2:idx+endidx]
+ if isinstance(subvars, dict):
+ if not varname in subvars:
+ if checkmissing:
+ raise MAVParseError("unknown variable in '%s%s%s'" % (
+ self.start_var_token, varname, self.end_var_token))
+ return text[0:idx+endidx] + self.substitute(text[idx+endidx:], subvars,
+ trim_leading_lf=False, checkmissing=False)
+ value = subvars[varname]
+ else:
+ value = getattr(subvars, varname, None)
+ if value is None:
+ if checkmissing:
+ raise MAVParseError("unknown variable in '%s%s%s'" % (
+ self.start_var_token, varname, self.end_var_token))
+ return text[0:idx+endidx] + self.substitute(text[idx+endidx:], subvars,
+ trim_leading_lf=False, checkmissing=False)
+ text = text.replace("%s%s%s" % (self.start_var_token, varname, self.end_var_token), str(value))
+ return text
+
+ def write(self, file, text, subvars={}, trim_leading_lf=True):
+ '''write to a file with variable substitution'''
+ file.write(self.substitute(text, subvars=subvars, trim_leading_lf=trim_leading_lf))
diff --git a/mavlink/share/pyshared/pymavlink/generator/mavtestgen.py b/mavlink/share/pyshared/pymavlink/generator/mavtestgen.py
new file mode 100644
index 000000000..faffa1c19
--- /dev/null
+++ b/mavlink/share/pyshared/pymavlink/generator/mavtestgen.py
@@ -0,0 +1,142 @@
+#!/usr/bin/env python
+'''
+generate a MAVLink test suite
+
+Copyright Andrew Tridgell 2011
+Released under GNU GPL version 3 or later
+'''
+
+import sys, textwrap
+from optparse import OptionParser
+
+# mavparse is up a directory level
+sys.path.append('..')
+import mavparse
+
+def gen_value(f, i, language):
+ '''generate a test value for the ith field of a message'''
+ type = f.type
+
+ # could be an array
+ if type.find("[") != -1:
+ aidx = type.find("[")
+ basetype = type[0:aidx]
+ if basetype == "array":
+ basetype = "int8_t"
+ if language == 'C':
+ return '(const %s *)"%s%u"' % (basetype, f.name, i)
+ return '"%s%u"' % (f.name, i)
+
+ if type == 'float':
+ return 17.0 + i*7
+ if type == 'char':
+ return 'A' + i
+ if type == 'int8_t':
+ return 5 + i
+ if type in ['int8_t', 'uint8_t']:
+ return 5 + i
+ if type in ['uint8_t_mavlink_version']:
+ return 2
+ if type in ['int16_t', 'uint16_t']:
+ return 17235 + i*52
+ if type in ['int32_t', 'uint32_t']:
+ v = 963497464 + i*52
+ if language == 'C':
+ return "%sL" % v
+ return v
+ if type in ['int64_t', 'uint64_t']:
+ v = 9223372036854775807 + i*63
+ if language == 'C':
+ return "%sLL" % v
+ return v
+
+
+
+def generate_methods_python(outf, msgs):
+ outf.write("""
+'''
+MAVLink protocol test implementation (auto-generated by mavtestgen.py)
+
+Generated from: %s
+
+Note: this file has been auto-generated. DO NOT EDIT
+'''
+
+import mavlink
+
+def generate_outputs(mav):
+ '''generate all message types as outputs'''
+""")
+ for m in msgs:
+ if m.name == "HEARTBEAT": continue
+ outf.write("\tmav.%s_send(" % m.name.lower())
+ for i in range(0, len(m.fields)):
+ f = m.fields[i]
+ outf.write("%s=%s" % (f.name, gen_value(f, i, 'py')))
+ if i != len(m.fields)-1:
+ outf.write(",")
+ outf.write(")\n")
+
+
+def generate_methods_C(outf, msgs):
+ outf.write("""
+/*
+MAVLink protocol test implementation (auto-generated by mavtestgen.py)
+
+Generated from: %s
+
+Note: this file has been auto-generated. DO NOT EDIT
+*/
+
+static void mavtest_generate_outputs(mavlink_channel_t chan)
+{
+""")
+ for m in msgs:
+ if m.name == "HEARTBEAT": continue
+ outf.write("\tmavlink_msg_%s_send(chan," % m.name.lower())
+ for i in range(0, len(m.fields)):
+ f = m.fields[i]
+ outf.write("%s" % gen_value(f, i, 'C'))
+ if i != len(m.fields)-1:
+ outf.write(",")
+ outf.write(");\n")
+ outf.write("}\n")
+
+
+
+######################################################################
+'''main program'''
+
+parser = OptionParser("%prog [options] <XML files>")
+parser.add_option("-o", "--output", dest="output", default="mavtest", help="output folder [default: %default]")
+(opts, args) = parser.parse_args()
+
+if len(args) < 1:
+ parser.error("You must supply at least one MAVLink XML protocol definition")
+
+
+msgs = []
+enums = []
+
+for fname in args:
+ (m, e) = mavparse.parse_mavlink_xml(fname)
+ msgs.extend(m)
+ enums.extend(e)
+
+
+if mavparse.check_duplicates(msgs):
+ sys.exit(1)
+
+print("Found %u MAVLink message types" % len(msgs))
+
+print("Generating python %s" % (opts.output+'.py'))
+outf = open(opts.output + '.py', "w")
+generate_methods_python(outf, msgs)
+outf.close()
+
+print("Generating C %s" % (opts.output+'.h'))
+outf = open(opts.output + '.h', "w")
+generate_methods_C(outf, msgs)
+outf.close()
+
+print("Generated %s OK" % opts.output)