aboutsummaryrefslogtreecommitdiff
path: root/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0
diff options
context:
space:
mode:
Diffstat (limited to 'mavlink/share/pyshared/pymavlink/generator/C/include_v1.0')
-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
11 files changed, 0 insertions, 5938 deletions
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
deleted file mode 100644
index 4f4cce02f..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/checksum.h
+++ /dev/null
@@ -1,89 +0,0 @@
-#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
deleted file mode 100644
index 39d6930e5..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_helpers.h
+++ /dev/null
@@ -1,507 +0,0 @@
-#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
deleted file mode 100644
index fd3ddd026..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_protobuf_manager.hpp
+++ /dev/null
@@ -1,377 +0,0 @@
-#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
deleted file mode 100644
index 5fbde97f7..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_types.h
+++ /dev/null
@@ -1,158 +0,0 @@
-#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
deleted file mode 100644
index 7556606e9..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/pixhawk/pixhawk.pb.h
+++ /dev/null
@@ -1,3663 +0,0 @@
-// 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
deleted file mode 100644
index 7b3e3c0bd..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/protocol.h
+++ /dev/null
@@ -1,322 +0,0 @@
-#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
deleted file mode 100644
index e596b8fba..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/mavlink.h
+++ /dev/null
@@ -1,27 +0,0 @@
-/** @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
deleted file mode 100644
index 2a3a89ff9..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/mavlink_msg_test_types.h
+++ /dev/null
@@ -1,610 +0,0 @@
-// 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
deleted file mode 100644
index 4dc04f889..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/test.h
+++ /dev/null
@@ -1,53 +0,0 @@
-/** @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
deleted file mode 100644
index 658e1ae07..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/testsuite.h
+++ /dev/null
@@ -1,120 +0,0 @@
-/** @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
deleted file mode 100644
index 867641e21..000000000
--- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/version.h
+++ /dev/null
@@ -1,12 +0,0 @@
-/** @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