diff --git a/files/mavlink_generator/C/include_v0.9/checksum.h b/files/mavlink_generator/C/include_v0.9/checksum.h index b70991f5ab7c46163f7d13c6e11f70e5102b2457..4f4cce02fc91ae78f851d7dcb1ec65fa4dd1f526 100644 --- a/files/mavlink_generator/C/include_v0.9/checksum.h +++ b/files/mavlink_generator/C/include_v0.9/checksum.h @@ -52,7 +52,7 @@ static inline void crc_init(uint16_t* crcAccum) * @param length length of the byte array * @return the checksum over the buffer bytes **/ -static inline uint16_t crc_calculate(uint8_t* pBuffer, uint16_t length) +static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length) { uint16_t crcTmp; crc_init(&crcTmp); diff --git a/files/mavlink_generator/C/include_v0.9/mavlink_helpers.h b/files/mavlink_generator/C/include_v0.9/mavlink_helpers.h index 98250e1ac8377d4ffaf8966c9165a62fab64cf5f..804490add20dc0f42ac610f1e73c65e0916deb8a 100644 --- a/files/mavlink_generator/C/include_v0.9/mavlink_helpers.h +++ b/files/mavlink_generator/C/include_v0.9/mavlink_helpers.h @@ -18,6 +18,24 @@ MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan) 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 * @@ -120,7 +138,7 @@ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint */ MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg) { - memcpy(buffer, (uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len); + 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; } @@ -182,8 +200,6 @@ 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) { - static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS]; - /* default message crc function. You can override this per-system to put this data in a different memory segment @@ -195,7 +211,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa #endif #endif - mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message + 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; @@ -209,14 +225,15 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa { 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 */ +/* Support shorter buffers than the + default maximum packet size */ #if (MAVLINK_MAX_PAYLOAD_LEN < 255) || c > MAVLINK_MAX_PAYLOAD_LEN #endif @@ -269,7 +286,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa break; case MAVLINK_PARSE_STATE_GOT_MSGID: - _MAV_PAYLOAD(rxmsg)[status->packet_idx++] = (char)c; + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c; mavlink_update_checksum(rxmsg, c); if (status->packet_idx == rxmsg->len) { @@ -296,6 +313,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa else { status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c; } break; @@ -317,6 +335,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa // 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; diff --git a/files/mavlink_generator/C/include_v0.9/mavlink_types.h b/files/mavlink_generator/C/include_v0.9/mavlink_types.h index 9daeffc63f7347027bffed188c00431744898174..9d04155c77fdeaa3699371aa502aad23342af657 100644 --- a/files/mavlink_generator/C/include_v0.9/mavlink_types.h +++ b/files/mavlink_generator/C/include_v0.9/mavlink_types.h @@ -140,6 +140,7 @@ enum MAV_COMPONENT MAV_COMP_ID_AIRSLAM, MAV_COMP_ID_MAPPER, MAV_COMP_ID_CAMERA, + MAV_COMP_ID_RADIO = 68, MAV_COMP_ID_IMU = 200, MAV_COMP_ID_IMU_2 = 201, MAV_COMP_ID_IMU_3 = 202, @@ -179,11 +180,26 @@ enum MAVLINK_DATA_STREAM_TYPE #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; @@ -208,6 +224,14 @@ typedef struct __mavlink_message { 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, @@ -228,9 +252,9 @@ typedef struct __mavlink_field_info { const char *name; // name of this field const char *print_format; // printing format hint, or NULL mavlink_message_type_t type; // type of this field - unsigned array_length; // if non-zero, field is an array - unsigned wire_offset; // offset of each field in the payload - unsigned structure_offset; // offset in a C structure + 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 @@ -241,11 +265,12 @@ typedef struct __mavlink_message_info { mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information } mavlink_message_info_t; -#define _MAV_PAYLOAD(msg) ((char *)(&(msg)->payload64[0])) +#define _MAV_PAYLOAD(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(msg)) -#define mavlink_ck_b(msg) *((msg->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD(msg)) +#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, diff --git a/files/mavlink_generator/C/include_v0.9/protocol.h b/files/mavlink_generator/C/include_v0.9/protocol.h index 05195c36919d04a5bf50c9799ee724af011a20f0..7b3e3c0bd2112c9516e694b729cbc990d2e766bc 100644 --- a/files/mavlink_generator/C/include_v0.9/protocol.h +++ b/files/mavlink_generator/C/include_v0.9/protocol.h @@ -155,7 +155,7 @@ static inline void byte_copy_8(char *dst, const char *src) /* 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) { @@ -171,6 +171,7 @@ static void mav_array_memcpy(void *dest, const void *src, size_t n) 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); + } /* @@ -179,6 +180,7 @@ static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const cha 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); + } /* @@ -187,6 +189,7 @@ static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const 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 @@ -206,7 +209,7 @@ static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, co #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)); \ + mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \ } #endif @@ -219,9 +222,9 @@ _MAV_PUT_ARRAY(int64_t, i64) _MAV_PUT_ARRAY(float, f) _MAV_PUT_ARRAY(double, d) -#define _MAV_RETURN_char(msg, wire_offset) _MAV_PAYLOAD(msg)[wire_offset] -#define _MAV_RETURN_int8_t(msg, wire_offset) (int8_t)_MAV_PAYLOAD(msg)[wire_offset] -#define _MAV_RETURN_uint8_t(msg, wire_offset) (uint8_t)_MAV_PAYLOAD(msg)[wire_offset] +#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) \ diff --git a/mavlink/include/v0.9/test/mavlink.h b/files/mavlink_generator/C/include_v0.9/test/mavlink.h similarity index 100% rename from mavlink/include/v0.9/test/mavlink.h rename to files/mavlink_generator/C/include_v0.9/test/mavlink.h diff --git a/mavlink/include/v0.9/test/mavlink_msg_test_types.h b/files/mavlink_generator/C/include_v0.9/test/mavlink_msg_test_types.h similarity index 100% rename from mavlink/include/v0.9/test/mavlink_msg_test_types.h rename to files/mavlink_generator/C/include_v0.9/test/mavlink_msg_test_types.h diff --git a/mavlink/include/v0.9/test/test.h b/files/mavlink_generator/C/include_v0.9/test/test.h similarity index 100% rename from mavlink/include/v0.9/test/test.h rename to files/mavlink_generator/C/include_v0.9/test/test.h diff --git a/mavlink/include/v0.9/test/testsuite.h b/files/mavlink_generator/C/include_v0.9/test/testsuite.h similarity index 100% rename from mavlink/include/v0.9/test/testsuite.h rename to files/mavlink_generator/C/include_v0.9/test/testsuite.h diff --git a/mavlink/include/v0.9/test/version.h b/files/mavlink_generator/C/include_v0.9/test/version.h similarity index 84% rename from mavlink/include/v0.9/test/version.h rename to files/mavlink_generator/C/include_v0.9/test/version.h index a0366ddf9c00d24f96426bbdaf8f865b86c8d120..64ca0cb38b3b123389c8498448bacc8729fd89fb 100644 --- a/mavlink/include/v0.9/test/version.h +++ b/files/mavlink_generator/C/include_v0.9/test/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Mar 1 01:19:41 2012" +#define MAVLINK_BUILD_DATE "Thu Mar 1 15:11:54 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "0.9" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 179 diff --git a/files/mavlink_generator/C/include_v1.0/mavlink_protobuf_manager.hpp b/files/mavlink_generator/C/include_v1.0/mavlink_protobuf_manager.hpp index fad1956440ee9c1cf75892f00eb71dad9ecdf2ca..fd3ddd026f709c1acb8c31d7493523892924ab49 100644 --- a/files/mavlink_generator/C/include_v1.0/mavlink_protobuf_manager.hpp +++ b/files/mavlink_generator/C/include_v1.0/mavlink_protobuf_manager.hpp @@ -24,6 +24,30 @@ public: , kExtendedHeaderSize(MAVLINK_EXTENDED_HEADER_LEN) , kExtendedPayloadMaxSize(MAVLINK_MAX_EXTENDED_PAYLOAD_LEN) { + // register GLOverlay + { + std::tr1::shared_ptr msg(new px::GLOverlay); + registerType(msg); + } + + // register ObstacleList + { + std::tr1::shared_ptr msg(new px::ObstacleList); + registerType(msg); + } + + // register ObstacleMap + { + std::tr1::shared_ptr msg(new px::ObstacleMap); + registerType(msg); + } + + // register Path + { + std::tr1::shared_ptr msg(new px::Path); + registerType(msg); + } + // register PointCloudXYZI { std::tr1::shared_ptr msg(new px::PointCloudXYZI); @@ -144,7 +168,7 @@ public: if (typecode >= mTypeMap.size()) { std::cout << "# WARNING: Protobuf message with type code " - << typecode << " is not registered." << std::endl; + << static_cast(typecode) << " is not registered." << std::endl; return false; } @@ -186,6 +210,11 @@ public: if (offset == 0) { queue.push_back(msg); + + if ((flags & 0x1) != 0x1) + { + reassemble = true; + } } else { diff --git a/files/mavlink_generator/C/include_v1.0/mavlink_types.h b/files/mavlink_generator/C/include_v1.0/mavlink_types.h index 1060be832700ff81b5ea8091a5394969e55ef040..5fbde97f7363ad203981483c7bf88828e4bf5faf 100644 --- a/files/mavlink_generator/C/include_v1.0/mavlink_types.h +++ b/files/mavlink_generator/C/include_v1.0/mavlink_types.h @@ -17,7 +17,15 @@ #define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255 #define MAVLINK_EXTENDED_HEADER_LEN 14 -#define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507 + +#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 { diff --git a/files/mavlink_generator/C/include_v1.0/pixhawk/pixhawk.pb.h b/files/mavlink_generator/C/include_v1.0/pixhawk/pixhawk.pb.h new file mode 100644 index 0000000000000000000000000000000000000000..7556606e98e26066d539950e6a43037145937770 --- /dev/null +++ b/files/mavlink_generator/C/include_v1.0/pixhawk/pixhawk.pb.h @@ -0,0 +1,3663 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: pixhawk.proto + +#ifndef PROTOBUF_pixhawk_2eproto__INCLUDED +#define PROTOBUF_pixhawk_2eproto__INCLUDED + +#include + +#include + +#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 +#include +#include +#include +// @@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_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_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_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(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(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(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(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(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/include/v1.0/test/mavlink.h b/files/mavlink_generator/C/include_v1.0/test/mavlink.h similarity index 100% rename from mavlink/include/v1.0/test/mavlink.h rename to files/mavlink_generator/C/include_v1.0/test/mavlink.h diff --git a/files/mavlink_generator/C/include_v1.0/test/mavlink_msg_test_types.h b/files/mavlink_generator/C/include_v1.0/test/mavlink_msg_test_types.h new file mode 100644 index 0000000000000000000000000000000000000000..2a3a89ff905812784a232e690d797b7a4e27f61b --- /dev/null +++ b/files/mavlink_generator/C/include_v1.0/test/mavlink_msg_test_types.h @@ -0,0 +1,610 @@ +// MESSAGE TEST_TYPES PACKING + +#define MAVLINK_MSG_ID_TEST_TYPES 0 + +typedef struct __mavlink_test_types_t +{ + uint64_t u64; ///< uint64_t + int64_t s64; ///< int64_t + double d; ///< double + uint64_t u64_array[3]; ///< uint64_t_array + int64_t s64_array[3]; ///< int64_t_array + double d_array[3]; ///< double_array + uint32_t u32; ///< uint32_t + int32_t s32; ///< int32_t + float f; ///< float + uint32_t u32_array[3]; ///< uint32_t_array + int32_t s32_array[3]; ///< int32_t_array + float f_array[3]; ///< float_array + uint16_t u16; ///< uint16_t + int16_t s16; ///< int16_t + uint16_t u16_array[3]; ///< uint16_t_array + int16_t s16_array[3]; ///< int16_t_array + char c; ///< char + char s[10]; ///< string + uint8_t u8; ///< uint8_t + int8_t s8; ///< int8_t + uint8_t u8_array[3]; ///< uint8_t_array + int8_t s8_array[3]; ///< int8_t_array +} mavlink_test_types_t; + +#define MAVLINK_MSG_ID_TEST_TYPES_LEN 179 +#define MAVLINK_MSG_ID_0_LEN 179 + +#define MAVLINK_MSG_TEST_TYPES_FIELD_U64_ARRAY_LEN 3 +#define MAVLINK_MSG_TEST_TYPES_FIELD_S64_ARRAY_LEN 3 +#define MAVLINK_MSG_TEST_TYPES_FIELD_D_ARRAY_LEN 3 +#define MAVLINK_MSG_TEST_TYPES_FIELD_U32_ARRAY_LEN 3 +#define MAVLINK_MSG_TEST_TYPES_FIELD_S32_ARRAY_LEN 3 +#define MAVLINK_MSG_TEST_TYPES_FIELD_F_ARRAY_LEN 3 +#define MAVLINK_MSG_TEST_TYPES_FIELD_U16_ARRAY_LEN 3 +#define MAVLINK_MSG_TEST_TYPES_FIELD_S16_ARRAY_LEN 3 +#define MAVLINK_MSG_TEST_TYPES_FIELD_S_LEN 10 +#define MAVLINK_MSG_TEST_TYPES_FIELD_U8_ARRAY_LEN 3 +#define MAVLINK_MSG_TEST_TYPES_FIELD_S8_ARRAY_LEN 3 + +#define MAVLINK_MESSAGE_INFO_TEST_TYPES { \ + "TEST_TYPES", \ + 22, \ + { { "u64", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_test_types_t, u64) }, \ + { "s64", NULL, MAVLINK_TYPE_INT64_T, 0, 8, offsetof(mavlink_test_types_t, s64) }, \ + { "d", NULL, MAVLINK_TYPE_DOUBLE, 0, 16, offsetof(mavlink_test_types_t, d) }, \ + { "u64_array", NULL, MAVLINK_TYPE_UINT64_T, 3, 24, offsetof(mavlink_test_types_t, u64_array) }, \ + { "s64_array", NULL, MAVLINK_TYPE_INT64_T, 3, 48, offsetof(mavlink_test_types_t, s64_array) }, \ + { "d_array", NULL, MAVLINK_TYPE_DOUBLE, 3, 72, offsetof(mavlink_test_types_t, d_array) }, \ + { "u32", "0x%08x", MAVLINK_TYPE_UINT32_T, 0, 96, offsetof(mavlink_test_types_t, u32) }, \ + { "s32", NULL, MAVLINK_TYPE_INT32_T, 0, 100, offsetof(mavlink_test_types_t, s32) }, \ + { "f", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_test_types_t, f) }, \ + { "u32_array", NULL, MAVLINK_TYPE_UINT32_T, 3, 108, offsetof(mavlink_test_types_t, u32_array) }, \ + { "s32_array", NULL, MAVLINK_TYPE_INT32_T, 3, 120, offsetof(mavlink_test_types_t, s32_array) }, \ + { "f_array", NULL, MAVLINK_TYPE_FLOAT, 3, 132, offsetof(mavlink_test_types_t, f_array) }, \ + { "u16", NULL, MAVLINK_TYPE_UINT16_T, 0, 144, offsetof(mavlink_test_types_t, u16) }, \ + { "s16", NULL, MAVLINK_TYPE_INT16_T, 0, 146, offsetof(mavlink_test_types_t, s16) }, \ + { "u16_array", NULL, MAVLINK_TYPE_UINT16_T, 3, 148, offsetof(mavlink_test_types_t, u16_array) }, \ + { "s16_array", NULL, MAVLINK_TYPE_INT16_T, 3, 154, offsetof(mavlink_test_types_t, s16_array) }, \ + { "c", NULL, MAVLINK_TYPE_CHAR, 0, 160, offsetof(mavlink_test_types_t, c) }, \ + { "s", NULL, MAVLINK_TYPE_CHAR, 10, 161, offsetof(mavlink_test_types_t, s) }, \ + { "u8", NULL, MAVLINK_TYPE_UINT8_T, 0, 171, offsetof(mavlink_test_types_t, u8) }, \ + { "s8", NULL, MAVLINK_TYPE_INT8_T, 0, 172, offsetof(mavlink_test_types_t, s8) }, \ + { "u8_array", NULL, MAVLINK_TYPE_UINT8_T, 3, 173, offsetof(mavlink_test_types_t, u8_array) }, \ + { "s8_array", NULL, MAVLINK_TYPE_INT8_T, 3, 176, offsetof(mavlink_test_types_t, s8_array) }, \ + } \ +} + + +/** + * @brief Pack a test_types message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param c char + * @param s string + * @param u8 uint8_t + * @param u16 uint16_t + * @param u32 uint32_t + * @param u64 uint64_t + * @param s8 int8_t + * @param s16 int16_t + * @param s32 int32_t + * @param s64 int64_t + * @param f float + * @param d double + * @param u8_array uint8_t_array + * @param u16_array uint16_t_array + * @param u32_array uint32_t_array + * @param u64_array uint64_t_array + * @param s8_array int8_t_array + * @param s16_array int16_t_array + * @param s32_array int32_t_array + * @param s64_array int64_t_array + * @param f_array float_array + * @param d_array double_array + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_test_types_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[179]; + _mav_put_uint64_t(buf, 0, u64); + _mav_put_int64_t(buf, 8, s64); + _mav_put_double(buf, 16, d); + _mav_put_uint32_t(buf, 96, u32); + _mav_put_int32_t(buf, 100, s32); + _mav_put_float(buf, 104, f); + _mav_put_uint16_t(buf, 144, u16); + _mav_put_int16_t(buf, 146, s16); + _mav_put_char(buf, 160, c); + _mav_put_uint8_t(buf, 171, u8); + _mav_put_int8_t(buf, 172, s8); + _mav_put_uint64_t_array(buf, 24, u64_array, 3); + _mav_put_int64_t_array(buf, 48, s64_array, 3); + _mav_put_double_array(buf, 72, d_array, 3); + _mav_put_uint32_t_array(buf, 108, u32_array, 3); + _mav_put_int32_t_array(buf, 120, s32_array, 3); + _mav_put_float_array(buf, 132, f_array, 3); + _mav_put_uint16_t_array(buf, 148, u16_array, 3); + _mav_put_int16_t_array(buf, 154, s16_array, 3); + _mav_put_char_array(buf, 161, s, 10); + _mav_put_uint8_t_array(buf, 173, u8_array, 3); + _mav_put_int8_t_array(buf, 176, s8_array, 3); + memcpy(_MAV_PAYLOAD(msg), buf, 179); +#else + mavlink_test_types_t packet; + packet.u64 = u64; + packet.s64 = s64; + packet.d = d; + packet.u32 = u32; + packet.s32 = s32; + packet.f = f; + packet.u16 = u16; + packet.s16 = s16; + packet.c = c; + packet.u8 = u8; + packet.s8 = s8; + mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); + mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); + mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3); + mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); + mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); + mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3); + mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); + mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); + mav_array_memcpy(packet.s, s, sizeof(char)*10); + mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); + mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); + memcpy(_MAV_PAYLOAD(msg), &packet, 179); +#endif + + msg->msgid = MAVLINK_MSG_ID_TEST_TYPES; + return mavlink_finalize_message(msg, system_id, component_id, 179, 103); +} + +/** + * @brief Pack a test_types message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param c char + * @param s string + * @param u8 uint8_t + * @param u16 uint16_t + * @param u32 uint32_t + * @param u64 uint64_t + * @param s8 int8_t + * @param s16 int16_t + * @param s32 int32_t + * @param s64 int64_t + * @param f float + * @param d double + * @param u8_array uint8_t_array + * @param u16_array uint16_t_array + * @param u32_array uint32_t_array + * @param u64_array uint64_t_array + * @param s8_array int8_t_array + * @param s16_array int16_t_array + * @param s32_array int32_t_array + * @param s64_array int64_t_array + * @param f_array float_array + * @param d_array double_array + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_test_types_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + char c,const char *s,uint8_t u8,uint16_t u16,uint32_t u32,uint64_t u64,int8_t s8,int16_t s16,int32_t s32,int64_t s64,float f,double d,const uint8_t *u8_array,const uint16_t *u16_array,const uint32_t *u32_array,const uint64_t *u64_array,const int8_t *s8_array,const int16_t *s16_array,const int32_t *s32_array,const int64_t *s64_array,const float *f_array,const double *d_array) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[179]; + _mav_put_uint64_t(buf, 0, u64); + _mav_put_int64_t(buf, 8, s64); + _mav_put_double(buf, 16, d); + _mav_put_uint32_t(buf, 96, u32); + _mav_put_int32_t(buf, 100, s32); + _mav_put_float(buf, 104, f); + _mav_put_uint16_t(buf, 144, u16); + _mav_put_int16_t(buf, 146, s16); + _mav_put_char(buf, 160, c); + _mav_put_uint8_t(buf, 171, u8); + _mav_put_int8_t(buf, 172, s8); + _mav_put_uint64_t_array(buf, 24, u64_array, 3); + _mav_put_int64_t_array(buf, 48, s64_array, 3); + _mav_put_double_array(buf, 72, d_array, 3); + _mav_put_uint32_t_array(buf, 108, u32_array, 3); + _mav_put_int32_t_array(buf, 120, s32_array, 3); + _mav_put_float_array(buf, 132, f_array, 3); + _mav_put_uint16_t_array(buf, 148, u16_array, 3); + _mav_put_int16_t_array(buf, 154, s16_array, 3); + _mav_put_char_array(buf, 161, s, 10); + _mav_put_uint8_t_array(buf, 173, u8_array, 3); + _mav_put_int8_t_array(buf, 176, s8_array, 3); + memcpy(_MAV_PAYLOAD(msg), buf, 179); +#else + mavlink_test_types_t packet; + packet.u64 = u64; + packet.s64 = s64; + packet.d = d; + packet.u32 = u32; + packet.s32 = s32; + packet.f = f; + packet.u16 = u16; + packet.s16 = s16; + packet.c = c; + packet.u8 = u8; + packet.s8 = s8; + mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); + mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); + mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3); + mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); + mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); + mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3); + mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); + mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); + mav_array_memcpy(packet.s, s, sizeof(char)*10); + mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); + mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); + memcpy(_MAV_PAYLOAD(msg), &packet, 179); +#endif + + msg->msgid = MAVLINK_MSG_ID_TEST_TYPES; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 179, 103); +} + +/** + * @brief Encode a test_types struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param test_types C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_test_types_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_test_types_t* test_types) +{ + return mavlink_msg_test_types_pack(system_id, component_id, msg, test_types->c, test_types->s, test_types->u8, test_types->u16, test_types->u32, test_types->u64, test_types->s8, test_types->s16, test_types->s32, test_types->s64, test_types->f, test_types->d, test_types->u8_array, test_types->u16_array, test_types->u32_array, test_types->u64_array, test_types->s8_array, test_types->s16_array, test_types->s32_array, test_types->s64_array, test_types->f_array, test_types->d_array); +} + +/** + * @brief Send a test_types message + * @param chan MAVLink channel to send the message + * + * @param c char + * @param s string + * @param u8 uint8_t + * @param u16 uint16_t + * @param u32 uint32_t + * @param u64 uint64_t + * @param s8 int8_t + * @param s16 int16_t + * @param s32 int32_t + * @param s64 int64_t + * @param f float + * @param d double + * @param u8_array uint8_t_array + * @param u16_array uint16_t_array + * @param u32_array uint32_t_array + * @param u64_array uint64_t_array + * @param s8_array int8_t_array + * @param s16_array int16_t_array + * @param s32_array int32_t_array + * @param s64_array int64_t_array + * @param f_array float_array + * @param d_array double_array + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_test_types_send(mavlink_channel_t chan, char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[179]; + _mav_put_uint64_t(buf, 0, u64); + _mav_put_int64_t(buf, 8, s64); + _mav_put_double(buf, 16, d); + _mav_put_uint32_t(buf, 96, u32); + _mav_put_int32_t(buf, 100, s32); + _mav_put_float(buf, 104, f); + _mav_put_uint16_t(buf, 144, u16); + _mav_put_int16_t(buf, 146, s16); + _mav_put_char(buf, 160, c); + _mav_put_uint8_t(buf, 171, u8); + _mav_put_int8_t(buf, 172, s8); + _mav_put_uint64_t_array(buf, 24, u64_array, 3); + _mav_put_int64_t_array(buf, 48, s64_array, 3); + _mav_put_double_array(buf, 72, d_array, 3); + _mav_put_uint32_t_array(buf, 108, u32_array, 3); + _mav_put_int32_t_array(buf, 120, s32_array, 3); + _mav_put_float_array(buf, 132, f_array, 3); + _mav_put_uint16_t_array(buf, 148, u16_array, 3); + _mav_put_int16_t_array(buf, 154, s16_array, 3); + _mav_put_char_array(buf, 161, s, 10); + _mav_put_uint8_t_array(buf, 173, u8_array, 3); + _mav_put_int8_t_array(buf, 176, s8_array, 3); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, buf, 179, 103); +#else + mavlink_test_types_t packet; + packet.u64 = u64; + packet.s64 = s64; + packet.d = d; + packet.u32 = u32; + packet.s32 = s32; + packet.f = f; + packet.u16 = u16; + packet.s16 = s16; + packet.c = c; + packet.u8 = u8; + packet.s8 = s8; + mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); + mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); + mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3); + mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); + mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); + mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3); + mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); + mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); + mav_array_memcpy(packet.s, s, sizeof(char)*10); + mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); + mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, (const char *)&packet, 179, 103); +#endif +} + +#endif + +// MESSAGE TEST_TYPES UNPACKING + + +/** + * @brief Get field c from test_types message + * + * @return char + */ +static inline char mavlink_msg_test_types_get_c(const mavlink_message_t* msg) +{ + return _MAV_RETURN_char(msg, 160); +} + +/** + * @brief Get field s from test_types message + * + * @return string + */ +static inline uint16_t mavlink_msg_test_types_get_s(const mavlink_message_t* msg, char *s) +{ + return _MAV_RETURN_char_array(msg, s, 10, 161); +} + +/** + * @brief Get field u8 from test_types message + * + * @return uint8_t + */ +static inline uint8_t mavlink_msg_test_types_get_u8(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 171); +} + +/** + * @brief Get field u16 from test_types message + * + * @return uint16_t + */ +static inline uint16_t mavlink_msg_test_types_get_u16(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 144); +} + +/** + * @brief Get field u32 from test_types message + * + * @return uint32_t + */ +static inline uint32_t mavlink_msg_test_types_get_u32(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 96); +} + +/** + * @brief Get field u64 from test_types message + * + * @return uint64_t + */ +static inline uint64_t mavlink_msg_test_types_get_u64(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field s8 from test_types message + * + * @return int8_t + */ +static inline int8_t mavlink_msg_test_types_get_s8(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 172); +} + +/** + * @brief Get field s16 from test_types message + * + * @return int16_t + */ +static inline int16_t mavlink_msg_test_types_get_s16(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 146); +} + +/** + * @brief Get field s32 from test_types message + * + * @return int32_t + */ +static inline int32_t mavlink_msg_test_types_get_s32(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 100); +} + +/** + * @brief Get field s64 from test_types message + * + * @return int64_t + */ +static inline int64_t mavlink_msg_test_types_get_s64(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int64_t(msg, 8); +} + +/** + * @brief Get field f from test_types message + * + * @return float + */ +static inline float mavlink_msg_test_types_get_f(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 104); +} + +/** + * @brief Get field d from test_types message + * + * @return double + */ +static inline double mavlink_msg_test_types_get_d(const mavlink_message_t* msg) +{ + return _MAV_RETURN_double(msg, 16); +} + +/** + * @brief Get field u8_array from test_types message + * + * @return uint8_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u8_array(const mavlink_message_t* msg, uint8_t *u8_array) +{ + return _MAV_RETURN_uint8_t_array(msg, u8_array, 3, 173); +} + +/** + * @brief Get field u16_array from test_types message + * + * @return uint16_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u16_array(const mavlink_message_t* msg, uint16_t *u16_array) +{ + return _MAV_RETURN_uint16_t_array(msg, u16_array, 3, 148); +} + +/** + * @brief Get field u32_array from test_types message + * + * @return uint32_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u32_array(const mavlink_message_t* msg, uint32_t *u32_array) +{ + return _MAV_RETURN_uint32_t_array(msg, u32_array, 3, 108); +} + +/** + * @brief Get field u64_array from test_types message + * + * @return uint64_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u64_array(const mavlink_message_t* msg, uint64_t *u64_array) +{ + return _MAV_RETURN_uint64_t_array(msg, u64_array, 3, 24); +} + +/** + * @brief Get field s8_array from test_types message + * + * @return int8_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s8_array(const mavlink_message_t* msg, int8_t *s8_array) +{ + return _MAV_RETURN_int8_t_array(msg, s8_array, 3, 176); +} + +/** + * @brief Get field s16_array from test_types message + * + * @return int16_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s16_array(const mavlink_message_t* msg, int16_t *s16_array) +{ + return _MAV_RETURN_int16_t_array(msg, s16_array, 3, 154); +} + +/** + * @brief Get field s32_array from test_types message + * + * @return int32_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s32_array(const mavlink_message_t* msg, int32_t *s32_array) +{ + return _MAV_RETURN_int32_t_array(msg, s32_array, 3, 120); +} + +/** + * @brief Get field s64_array from test_types message + * + * @return int64_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s64_array(const mavlink_message_t* msg, int64_t *s64_array) +{ + return _MAV_RETURN_int64_t_array(msg, s64_array, 3, 48); +} + +/** + * @brief Get field f_array from test_types message + * + * @return float_array + */ +static inline uint16_t mavlink_msg_test_types_get_f_array(const mavlink_message_t* msg, float *f_array) +{ + return _MAV_RETURN_float_array(msg, f_array, 3, 132); +} + +/** + * @brief Get field d_array from test_types message + * + * @return double_array + */ +static inline uint16_t mavlink_msg_test_types_get_d_array(const mavlink_message_t* msg, double *d_array) +{ + return _MAV_RETURN_double_array(msg, d_array, 3, 72); +} + +/** + * @brief Decode a test_types message into a struct + * + * @param msg The message to decode + * @param test_types C-struct to decode the message contents into + */ +static inline void mavlink_msg_test_types_decode(const mavlink_message_t* msg, mavlink_test_types_t* test_types) +{ +#if MAVLINK_NEED_BYTE_SWAP + test_types->u64 = mavlink_msg_test_types_get_u64(msg); + test_types->s64 = mavlink_msg_test_types_get_s64(msg); + test_types->d = mavlink_msg_test_types_get_d(msg); + mavlink_msg_test_types_get_u64_array(msg, test_types->u64_array); + mavlink_msg_test_types_get_s64_array(msg, test_types->s64_array); + mavlink_msg_test_types_get_d_array(msg, test_types->d_array); + test_types->u32 = mavlink_msg_test_types_get_u32(msg); + test_types->s32 = mavlink_msg_test_types_get_s32(msg); + test_types->f = mavlink_msg_test_types_get_f(msg); + mavlink_msg_test_types_get_u32_array(msg, test_types->u32_array); + mavlink_msg_test_types_get_s32_array(msg, test_types->s32_array); + mavlink_msg_test_types_get_f_array(msg, test_types->f_array); + test_types->u16 = mavlink_msg_test_types_get_u16(msg); + test_types->s16 = mavlink_msg_test_types_get_s16(msg); + mavlink_msg_test_types_get_u16_array(msg, test_types->u16_array); + mavlink_msg_test_types_get_s16_array(msg, test_types->s16_array); + test_types->c = mavlink_msg_test_types_get_c(msg); + mavlink_msg_test_types_get_s(msg, test_types->s); + test_types->u8 = mavlink_msg_test_types_get_u8(msg); + test_types->s8 = mavlink_msg_test_types_get_s8(msg); + mavlink_msg_test_types_get_u8_array(msg, test_types->u8_array); + mavlink_msg_test_types_get_s8_array(msg, test_types->s8_array); +#else + memcpy(test_types, _MAV_PAYLOAD(msg), 179); +#endif +} diff --git a/files/mavlink_generator/C/include_v1.0/test/test.h b/files/mavlink_generator/C/include_v1.0/test/test.h new file mode 100644 index 0000000000000000000000000000000000000000..4dc04f889f5809f780b4eb3f55834ed832ed504c --- /dev/null +++ b/files/mavlink_generator/C/include_v1.0/test/test.h @@ -0,0 +1,53 @@ +/** @file + * @brief MAVLink comm protocol generated from test.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef TEST_H +#define TEST_H + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {179, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {103, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_TEST_TYPES, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_TEST + + + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 3 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 3 +#endif + +// ENUM DEFINITIONS + + + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_test_types.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // TEST_H diff --git a/mavlink/include/v1.0/test/testsuite.h b/files/mavlink_generator/C/include_v1.0/test/testsuite.h similarity index 100% rename from mavlink/include/v1.0/test/testsuite.h rename to files/mavlink_generator/C/include_v1.0/test/testsuite.h diff --git a/mavlink/include/v1.0/test/version.h b/files/mavlink_generator/C/include_v1.0/test/version.h similarity index 84% rename from mavlink/include/v1.0/test/version.h rename to files/mavlink_generator/C/include_v1.0/test/version.h index 605c945cd87c55c1fd93d5705704f58c47b28902..867641e2186d3f0afc4d59776279cb0f501c0d2f 100644 --- a/mavlink/include/v1.0/test/version.h +++ b/files/mavlink_generator/C/include_v1.0/test/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Feb 9 16:35:37 2012" +#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 diff --git a/mavlink/src/v1.0/pixhawk/pixhawk.pb.cc b/files/mavlink_generator/C/src_v1.0/pixhawk/pixhawk.pb.cc similarity index 100% rename from mavlink/src/v1.0/pixhawk/pixhawk.pb.cc rename to files/mavlink_generator/C/src_v1.0/pixhawk/pixhawk.pb.cc diff --git a/files/mavlink_generator/generator/C/test/posix/.gitignore b/files/mavlink_generator/generator/C/test/posix/.gitignore deleted file mode 100644 index 7c98650ccffa26661a01f32a8d20bf09605593cb..0000000000000000000000000000000000000000 --- a/files/mavlink_generator/generator/C/test/posix/.gitignore +++ /dev/null @@ -1,3 +0,0 @@ -/testmav0.9 -/testmav1.0 -/testmav1.0_nonstrict diff --git a/files/mavlink_generator/generator/C/test/posix/testmav.c b/files/mavlink_generator/generator/C/test/posix/testmav.c deleted file mode 100644 index 2fd7fa378b1c4bd0c3db9eac1e3cef857457154e..0000000000000000000000000000000000000000 --- a/files/mavlink_generator/generator/C/test/posix/testmav.c +++ /dev/null @@ -1,159 +0,0 @@ -/* - simple MAVLink testsuite for C - */ -#include -#include -#include -#include -#include - -#define MAVLINK_USE_CONVENIENCE_FUNCTIONS -#define MAVLINK_COMM_NUM_BUFFERS 2 - -// this trick allows us to make mavlink_message_t as small as possible -// for this dialect, which saves some memory -#include -#define MAVLINK_MAX_PAYLOAD_LEN MAVLINK_MAX_DIALECT_PAYLOAD_SIZE - -#include -static mavlink_system_t mavlink_system = {42,11,}; - -#define MAVLINK_ASSERT(x) assert(x) -static void comm_send_ch(mavlink_channel_t chan, uint8_t c); - -static mavlink_message_t last_msg; - -#include -#include - -static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS]; - -static const unsigned message_lengths[] = MAVLINK_MESSAGE_LENGTHS; -static unsigned error_count; - -static const mavlink_message_info_t message_info[256] = MAVLINK_MESSAGE_INFO; - -static void print_one_field(mavlink_message_t *msg, const mavlink_field_info_t *f, int idx) -{ -#define PRINT_FORMAT(f, def) (f->print_format?f->print_format:def) - switch (f->type) { - case MAVLINK_TYPE_CHAR: - printf(PRINT_FORMAT(f, "%c"), _MAV_RETURN_char(msg, f->wire_offset+idx*1)); - break; - case MAVLINK_TYPE_UINT8_T: - printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint8_t(msg, f->wire_offset+idx*1)); - break; - case MAVLINK_TYPE_INT8_T: - printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int8_t(msg, f->wire_offset+idx*1)); - break; - case MAVLINK_TYPE_UINT16_T: - printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint16_t(msg, f->wire_offset+idx*2)); - break; - case MAVLINK_TYPE_INT16_T: - printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int16_t(msg, f->wire_offset+idx*2)); - break; - case MAVLINK_TYPE_UINT32_T: - printf(PRINT_FORMAT(f, "%lu"), (unsigned long)_MAV_RETURN_uint32_t(msg, f->wire_offset+idx*4)); - break; - case MAVLINK_TYPE_INT32_T: - printf(PRINT_FORMAT(f, "%ld"), (long)_MAV_RETURN_int32_t(msg, f->wire_offset+idx*4)); - break; - case MAVLINK_TYPE_UINT64_T: - printf(PRINT_FORMAT(f, "%llu"), (unsigned long long)_MAV_RETURN_uint64_t(msg, f->wire_offset+idx*8)); - break; - case MAVLINK_TYPE_INT64_T: - printf(PRINT_FORMAT(f, "%lld"), (long long)_MAV_RETURN_int64_t(msg, f->wire_offset+idx*8)); - break; - case MAVLINK_TYPE_FLOAT: - printf(PRINT_FORMAT(f, "%f"), (double)_MAV_RETURN_float(msg, f->wire_offset+idx*4)); - break; - case MAVLINK_TYPE_DOUBLE: - printf(PRINT_FORMAT(f, "%f"), _MAV_RETURN_double(msg, f->wire_offset+idx*8)); - break; - } -} - -static void print_field(mavlink_message_t *msg, const mavlink_field_info_t *f) -{ - printf("%s: ", f->name); - if (f->array_length == 0) { - print_one_field(msg, f, 0); - printf(" "); - } else { - unsigned i; - /* print an array */ - if (f->type == MAVLINK_TYPE_CHAR) { - printf("'%.*s'", f->array_length, - f->wire_offset+(const char *)_MAV_PAYLOAD(msg)); - - } else { - printf("[ "); - for (i=0; iarray_length; i++) { - print_one_field(msg, f, i); - if (i < f->array_length) { - printf(", "); - } - } - printf("]"); - } - } - printf(" "); -} - -static void print_message(mavlink_message_t *msg) -{ - const mavlink_message_info_t *m = &message_info[msg->msgid]; - const mavlink_field_info_t *f = m->fields; - unsigned i; - printf("%s { ", m->name); - for (i=0; inum_fields; i++) { - print_field(msg, &f[i]); - } - printf("}\n"); -} - -static void comm_send_ch(mavlink_channel_t chan, uint8_t c) -{ - mavlink_status_t status; - if (mavlink_parse_char(chan, c, &last_msg, &status)) { - print_message(&last_msg); - chan_counts[chan]++; - /* channel 0 gets 3 messages per message, because of - the channel defaults for _pack() and _encode() */ - if (chan == MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)(chan_counts[chan]*3)) { - printf("Channel 0 sequence mismatch error at packet %u (rx_seq=%u)\n", - chan_counts[chan], status.current_rx_seq); - error_count++; - } else if (chan > MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)chan_counts[chan]) { - printf("Channel %u sequence mismatch error at packet %u (rx_seq=%u)\n", - (unsigned)chan, chan_counts[chan], status.current_rx_seq); - error_count++; - } - if (message_lengths[last_msg.msgid] != last_msg.len) { - printf("Incorrect message length %u for message %u - expected %u\n", - (unsigned)last_msg.len, (unsigned)last_msg.msgid, message_lengths[last_msg.msgid]); - error_count++; - } - } - if (status.packet_rx_drop_count != 0) { - printf("Parse error at packet %u\n", chan_counts[chan]); - error_count++; - } -} - -int main(void) -{ - mavlink_channel_t chan; - mavlink_test_all(11, 10, &last_msg); - for (chan=MAVLINK_COMM_0; chan<=MAVLINK_COMM_1; chan++) { - printf("Received %u messages on channel %u OK\n", - chan_counts[chan], (unsigned)chan); - } - if (error_count != 0) { - printf("Error count %u\n", error_count); - exit(1); - } - printf("No errors detected\n"); - return 0; -} - diff --git a/files/mavlink_generator/generator/C/test/windows/stdafx.cpp b/files/mavlink_generator/generator/C/test/windows/stdafx.cpp deleted file mode 100644 index 98b4abf0582a8638266d890d9963727f4bd7a020..0000000000000000000000000000000000000000 --- a/files/mavlink_generator/generator/C/test/windows/stdafx.cpp +++ /dev/null @@ -1,8 +0,0 @@ -// stdafx.cpp : source file that includes just the standard includes -// testmav.pch will be the pre-compiled header -// stdafx.obj will contain the pre-compiled type information - -#include "stdafx.h" - -// TODO: reference any additional headers you need in STDAFX.H -// and not in this file diff --git a/files/mavlink_generator/generator/C/test/windows/stdafx.h b/files/mavlink_generator/generator/C/test/windows/stdafx.h deleted file mode 100644 index 47a0d0252b148bbb77eca0042cbf79e4e65f4fc8..0000000000000000000000000000000000000000 --- a/files/mavlink_generator/generator/C/test/windows/stdafx.h +++ /dev/null @@ -1,15 +0,0 @@ -// stdafx.h : include file for standard system include files, -// or project specific include files that are used frequently, but -// are changed infrequently -// - -#pragma once - -#include "targetver.h" - -#include -#include - - - -// TODO: reference additional headers your program requires here diff --git a/files/mavlink_generator/generator/C/test/windows/targetver.h b/files/mavlink_generator/generator/C/test/windows/targetver.h deleted file mode 100644 index 90e767bfce745c059344fcd374185b064f09dcf7..0000000000000000000000000000000000000000 --- a/files/mavlink_generator/generator/C/test/windows/targetver.h +++ /dev/null @@ -1,8 +0,0 @@ -#pragma once - -// Including SDKDDKVer.h defines the highest available Windows platform. - -// If you wish to build your application for a previous Windows platform, include WinSDKVer.h and -// set the _WIN32_WINNT macro to the platform you wish to support before including SDKDDKVer.h. - -#include diff --git a/files/mavlink_generator/generator/C/test/windows/testmav.cpp b/files/mavlink_generator/generator/C/test/windows/testmav.cpp deleted file mode 100644 index aa83caceddc0160d92514f078c2362952aef22fb..0000000000000000000000000000000000000000 --- a/files/mavlink_generator/generator/C/test/windows/testmav.cpp +++ /dev/null @@ -1,154 +0,0 @@ -// testmav.cpp : Defines the entry point for the console application. -// - -#include "stdafx.h" -#include "stdio.h" -#include "stdint.h" -#include "stddef.h" -#include "assert.h" - - -#define MAVLINK_USE_CONVENIENCE_FUNCTIONS -#define MAVLINK_COMM_NUM_BUFFERS 2 - -#include -static mavlink_system_t mavlink_system = {42,11,}; - -#define MAVLINK_ASSERT(x) assert(x) -static void comm_send_ch(mavlink_channel_t chan, uint8_t c); - -static mavlink_message_t last_msg; - -#include -#include - -static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS]; - -static const unsigned message_lengths[] = MAVLINK_MESSAGE_LENGTHS; -static unsigned error_count; - -static const mavlink_message_info_t message_info[256] = MAVLINK_MESSAGE_INFO; - -static void print_one_field(mavlink_message_t *msg, const mavlink_field_info_t *f, int idx) -{ -#define PRINT_FORMAT(f, def) (f->print_format?f->print_format:def) - switch (f->type) { - case MAVLINK_TYPE_CHAR: - printf(PRINT_FORMAT(f, "%c"), _MAV_RETURN_char(msg, f->wire_offset+idx*1)); - break; - case MAVLINK_TYPE_UINT8_T: - printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint8_t(msg, f->wire_offset+idx*1)); - break; - case MAVLINK_TYPE_INT8_T: - printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int8_t(msg, f->wire_offset+idx*1)); - break; - case MAVLINK_TYPE_UINT16_T: - printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint16_t(msg, f->wire_offset+idx*2)); - break; - case MAVLINK_TYPE_INT16_T: - printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int16_t(msg, f->wire_offset+idx*2)); - break; - case MAVLINK_TYPE_UINT32_T: - printf(PRINT_FORMAT(f, "%lu"), (unsigned long)_MAV_RETURN_uint32_t(msg, f->wire_offset+idx*4)); - break; - case MAVLINK_TYPE_INT32_T: - printf(PRINT_FORMAT(f, "%ld"), (long)_MAV_RETURN_int32_t(msg, f->wire_offset+idx*4)); - break; - case MAVLINK_TYPE_UINT64_T: - printf(PRINT_FORMAT(f, "%llu"), (unsigned long long)_MAV_RETURN_uint64_t(msg, f->wire_offset+idx*8)); - break; - case MAVLINK_TYPE_INT64_T: - printf(PRINT_FORMAT(f, "%lld"), (long long)_MAV_RETURN_int64_t(msg, f->wire_offset+idx*8)); - break; - case MAVLINK_TYPE_FLOAT: - printf(PRINT_FORMAT(f, "%f"), (double)_MAV_RETURN_float(msg, f->wire_offset+idx*4)); - break; - case MAVLINK_TYPE_DOUBLE: - printf(PRINT_FORMAT(f, "%f"), _MAV_RETURN_double(msg, f->wire_offset+idx*8)); - break; - } -} - -static void print_field(mavlink_message_t *msg, const mavlink_field_info_t *f) -{ - printf("%s: ", f->name); - if (f->array_length == 0) { - print_one_field(msg, f, 0); - printf(" "); - } else { - unsigned i; - /* print an array */ - if (f->type == MAVLINK_TYPE_CHAR) { - printf("'%.*s'", f->array_length, - f->wire_offset+(const char *)_MAV_PAYLOAD(msg)); - - } else { - printf("[ "); - for (i=0; iarray_length; i++) { - print_one_field(msg, f, i); - if (i < f->array_length) { - printf(", "); - } - } - printf("]"); - } - } - printf(" "); -} - -static void print_message(mavlink_message_t *msg) -{ - const mavlink_message_info_t *m = &message_info[msg->msgid]; - const mavlink_field_info_t *f = m->fields; - unsigned i; - printf("%s { ", m->name); - for (i=0; inum_fields; i++) { - print_field(msg, &f[i]); - } - printf("}\n"); -} - -static void comm_send_ch(mavlink_channel_t chan, uint8_t c) -{ - mavlink_status_t status; - if (mavlink_parse_char(chan, c, &last_msg, &status)) { - print_message(&last_msg); - chan_counts[chan]++; - /* channel 0 gets 3 messages per message, because of - the channel defaults for _pack() and _encode() */ - if (chan == MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)(chan_counts[chan]*3)) { - printf("Channel 0 sequence mismatch error at packet %u (rx_seq=%u)\n", - chan_counts[chan], status.current_rx_seq); - error_count++; - } else if (chan > MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)chan_counts[chan]) { - printf("Channel %u sequence mismatch error at packet %u (rx_seq=%u)\n", - (unsigned)chan, chan_counts[chan], status.current_rx_seq); - error_count++; - } - if (message_lengths[last_msg.msgid] != last_msg.len) { - printf("Incorrect message length %u for message %u - expected %u\n", - (unsigned)last_msg.len, (unsigned)last_msg.msgid, message_lengths[last_msg.msgid]); - error_count++; - } - } - if (status.packet_rx_drop_count != 0) { - printf("Parse error at packet %u\n", chan_counts[chan]); - error_count++; - } -} - -int _tmain(int argc, _TCHAR* argv[]) -{ - int chan; - mavlink_test_all(11, 10, &last_msg); - for (chan=MAVLINK_COMM_0; chan<=MAVLINK_COMM_1; chan++) { - printf("Received %u messages on channel %u OK\n", - chan_counts[chan], (unsigned)chan); - } - if (error_count != 0) { - printf("Error count %u\n", error_count); - return(1); - } - printf("No errors detected\n"); - return 0; -} diff --git a/files/mavlink_generator/generator/_ctypes.pyd b/files/mavlink_generator/generator/_ctypes.pyd deleted file mode 100644 index ae456be8063dc5776e31bda4300a9c04304a2511..0000000000000000000000000000000000000000 Binary files a/files/mavlink_generator/generator/_ctypes.pyd and /dev/null differ diff --git a/files/mavlink_generator/generator/_hashlib.pyd b/files/mavlink_generator/generator/_hashlib.pyd deleted file mode 100644 index 5efea4ac7366e80f01d857462a066a1bbb74adfa..0000000000000000000000000000000000000000 Binary files a/files/mavlink_generator/generator/_hashlib.pyd and /dev/null differ diff --git a/files/mavlink_generator/generator/_socket.pyd b/files/mavlink_generator/generator/_socket.pyd deleted file mode 100644 index b4b3b1fe60899deb850110a1aacd46e956722ab0..0000000000000000000000000000000000000000 Binary files a/files/mavlink_generator/generator/_socket.pyd and /dev/null differ diff --git a/files/mavlink_generator/generator/_ssl.pyd b/files/mavlink_generator/generator/_ssl.pyd deleted file mode 100644 index c054f240d67ff88e4fb9f6745858b0365099829e..0000000000000000000000000000000000000000 Binary files a/files/mavlink_generator/generator/_ssl.pyd and /dev/null differ diff --git a/files/mavlink_generator/generator/bz2.pyd b/files/mavlink_generator/generator/bz2.pyd deleted file mode 100644 index df1a20e4c98d752349fefb7af3952102aa7cd2f4..0000000000000000000000000000000000000000 Binary files a/files/mavlink_generator/generator/bz2.pyd and /dev/null differ diff --git a/files/mavlink_generator/generator/library.zip b/files/mavlink_generator/generator/library.zip deleted file mode 100644 index fb48826192e9366422e77132c1dcfa05e616dd1f..0000000000000000000000000000000000000000 Binary files a/files/mavlink_generator/generator/library.zip and /dev/null differ diff --git a/files/mavlink_generator/generator/mavextra.py b/files/mavlink_generator/generator/mavextra.py deleted file mode 100644 index b4bb585f0d066c89877a6543022b5e8160f2ac64..0000000000000000000000000000000000000000 --- a/files/mavlink_generator/generator/mavextra.py +++ /dev/null @@ -1,38 +0,0 @@ -#!/usr/bin/env python -''' -useful extra functions for use by mavlink clients - -Copyright Andrew Tridgell 2011 -Released under GNU GPL version 3 or later -''' - -from math import * - - -def norm_heading(RAW_IMU, ATTITUDE, declination): - '''calculate heading from RAW_IMU and ATTITUDE''' - xmag = RAW_IMU.xmag - ymag = RAW_IMU.ymag - zmag = RAW_IMU.zmag - pitch = ATTITUDE.pitch - roll = ATTITUDE.roll - - headX = xmag*cos(pitch) + ymag*sin(roll)*sin(pitch) + zmag*cos(roll)*sin(pitch) - headY = ymag*cos(roll) - zmag*sin(roll) - heading = atan2(-headY, headX) - heading = fmod(degrees(heading) + declination + 360, 360) - return heading - -def TrueHeading(SERVO_OUTPUT_RAW): - rc3_min = 1060 - rc3_max = 1850 - p = float(SERVO_OUTPUT_RAW.servo3_raw - rc3_min) / (rc3_max - rc3_min) - return 172 + (1.0-p)*(326 - 172) - -def kmh(mps): - '''convert m/s to Km/h''' - return mps*3.6 - -def altitude(press_abs, ground_press=955.0, ground_temp=30): - '''calculate barometric altitude''' - return log(ground_press/press_abs)*(ground_temp+273.15)*29271.267*0.001 diff --git a/files/mavlink_generator/generator/mavgen.exe b/files/mavlink_generator/generator/mavgen.exe deleted file mode 100644 index b59dd82c45c0f4288c3ece8bd02f4ea3f1f72379..0000000000000000000000000000000000000000 Binary files a/files/mavlink_generator/generator/mavgen.exe and /dev/null differ diff --git a/files/mavlink_generator/generator/mavgen.py b/files/mavlink_generator/generator/mavgen.py index c2e925dc53cbc6e10975d1dcf0c06a915eb5cf28..05f71f778d42e226413247395aa7bda018e060e2 100755 --- a/files/mavlink_generator/generator/mavgen.py +++ b/files/mavlink_generator/generator/mavgen.py @@ -71,10 +71,10 @@ if __name__=="__main__": import mavgen_python import mavgen_c - parser = OptionParser("mavgen.py [options] ") - parser.add_option("-o", "--output", dest="output", default="mavlink", help="output base name") - parser.add_option("--lang", dest="language", default="python", help="language to generate") - parser.add_option("--wire-protocol", dest="wire_protocol", default=mavparse.PROTOCOL_0_9, help="wire protocol version") + parser = OptionParser("%prog [options] ") + parser.add_option("-o", "--output", dest="output", default="mavlink", help="output directory.") + parser.add_option("--lang", dest="language", default="python", help="language of generated code: 'Python' or 'C' [default: %default]") + parser.add_option("--wire-protocol", dest="wire_protocol", default=mavparse.PROTOCOL_0_9, help="MAVLink protocol version: '0.9' or '1.0'. [default: %default]") (opts, args) = parser.parse_args() if len(args) < 1: diff --git a/files/mavlink_generator/generator/mavgen_c.py b/files/mavlink_generator/generator/mavgen_c.py index f05b5aaa300d4efe15b0681852bd322a0fc3803f..255919f0d4e297a1fcec6bb27ab09aeeb906a290 100644 --- a/files/mavlink_generator/generator/mavgen_c.py +++ b/files/mavlink_generator/generator/mavgen_c.py @@ -404,16 +404,41 @@ ${{message: mavlink_test_${name_lower}(system_id, component_id, last_msg); def copy_fixed_headers(directory, xml): '''copy the fixed protocol headers to the target directory''' import shutil - hlist = [ 'protocol.h', 'mavlink_helpers.h', 'mavlink_types.h', 'checksum.h' ] + hlist = [ 'protocol.h', 'mavlink_helpers.h', 'mavlink_types.h', 'checksum.h', 'mavlink_protobuf_manager.hpp' ] basepath = os.path.dirname(os.path.realpath(__file__)) srcpath = os.path.join(basepath, 'C/include_v%s' % xml.wire_protocol_version) print("Copying fixed headers") for h in hlist: + if (not (h == 'mavlink_protobuf_manager.hpp' and xml.wire_protocol_version == '0.9')): + src = os.path.realpath(os.path.join(srcpath, h)) + dest = os.path.realpath(os.path.join(directory, h)) + if src == dest: + continue + shutil.copy(src, dest) + # XXX This is a hack - to be removed + if (xml.basename == 'pixhawk' and xml.wire_protocol_version == '1.0'): + h = 'pixhawk/pixhawk.pb.h' src = os.path.realpath(os.path.join(srcpath, h)) dest = os.path.realpath(os.path.join(directory, h)) - if src == dest: - continue shutil.copy(src, dest) + +def copy_fixed_sources(directory, xml): + # XXX This is a hack - to be removed + import shutil + basepath = os.path.dirname(os.path.realpath(__file__)) + srcpath = os.path.join(basepath, 'C/src_v%s' % xml.wire_protocol_version) + if (xml.basename == 'pixhawk' and xml.wire_protocol_version == '1.0'): + print("Copying fixed sources") + src = os.path.realpath(os.path.join(srcpath, 'pixhawk/pixhawk.pb.cc')) + dest = os.path.realpath(os.path.join(directory, '../../../share/mavlink/src/v%s/pixhawk/pixhawk.pb.cc' % xml.wire_protocol_version)) + destdir = os.path.realpath(os.path.join(directory, '../../../share/mavlink/src/v%s/pixhawk' % xml.wire_protocol_version)) + try: + os.makedirs(destdir) + except: + print("Not re-creating directory") + shutil.copy(src, dest) + print("Copied to"), + print(dest) class mav_include(object): def __init__(self, base): @@ -553,3 +578,4 @@ def generate(basename, xml_list): for xml in xml_list: generate_one(basename, xml) copy_fixed_headers(basename, xml_list[0]) + copy_fixed_sources(basename, xml_list[0]) diff --git a/files/mavlink_generator/generator/mavlink.py b/files/mavlink_generator/generator/mavlink.py deleted file mode 100644 index ee8720bf6a3a37b3e387971c17c78436f9692b4d..0000000000000000000000000000000000000000 --- a/files/mavlink_generator/generator/mavlink.py +++ /dev/null @@ -1,4731 +0,0 @@ -''' -MAVLink protocol implementation (auto-generated by mavgen.py) - -Generated from: ardupilotmega.xml,common.xml - -Note: this file has been auto-generated. DO NOT EDIT -''' - -import struct, array, mavutil, time - -WIRE_PROTOCOL_VERSION = "0.9" - -class MAVLink_header(object): - '''MAVLink message header''' - def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): - self.mlen = mlen - self.seq = seq - self.srcSystem = srcSystem - self.srcComponent = srcComponent - self.msgId = msgId - - def pack(self): - return struct.pack('BBBBBB', 85, self.mlen, self.seq, - self.srcSystem, self.srcComponent, self.msgId) - -class MAVLink_message(object): - '''base MAVLink message class''' - def __init__(self, msgId, name): - self._header = MAVLink_header(msgId) - self._payload = None - self._msgbuf = None - self._crc = None - self._fieldnames = [] - self._type = name - - def get_msgbuf(self): - return self._msgbuf - - def get_header(self): - return self._header - - def get_payload(self): - return self._payload - - def get_crc(self): - return self._crc - - def get_fieldnames(self): - return self._fieldnames - - def get_type(self): - return self._type - - def get_msgId(self): - return self._header.msgId - - def get_srcSystem(self): - return self._header.srcSystem - - def get_srcComponent(self): - return self._header.srcComponent - - def get_seq(self): - return self._header.seq - - def __str__(self): - ret = '%s {' % self._type - for a in self._fieldnames: - v = getattr(self, a) - ret += '%s : %s, ' % (a, v) - ret = ret[0:-2] + '}' - return ret - - def pack(self, mav, crc_extra, payload): - self._payload = payload - self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, - mav.srcSystem, mav.srcComponent) - self._msgbuf = self._header.pack() + payload - crc = mavutil.x25crc(self._msgbuf[1:]) - if False: # using CRC extra - crc.accumulate(chr(crc_extra)) - self._crc = crc.crc - self._msgbuf += struct.pack('hhhfiiffffff', self.mag_ofs_x, self.mag_ofs_y, self.mag_ofs_z, self.mag_declination, self.raw_press, self.raw_temp, self.gyro_cal_x, self.gyro_cal_y, self.gyro_cal_z, self.accel_cal_x, self.accel_cal_y, self.accel_cal_z)) - -class MAVLink_set_mag_offsets_message(MAVLink_message): - ''' - set the magnetometer offsets - ''' - def __init__(self, target_system, target_component, mag_ofs_x, mag_ofs_y, mag_ofs_z): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_MAG_OFFSETS, 'SET_MAG_OFFSETS') - self._fieldnames = ['target_system', 'target_component', 'mag_ofs_x', 'mag_ofs_y', 'mag_ofs_z'] - self.target_system = target_system - self.target_component = target_component - self.mag_ofs_x = mag_ofs_x - self.mag_ofs_y = mag_ofs_y - self.mag_ofs_z = mag_ofs_z - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 29, struct.pack('>BBhhh', self.target_system, self.target_component, self.mag_ofs_x, self.mag_ofs_y, self.mag_ofs_z)) - -class MAVLink_meminfo_message(MAVLink_message): - ''' - state of APM memory - ''' - def __init__(self, brkval, freemem): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_MEMINFO, 'MEMINFO') - self._fieldnames = ['brkval', 'freemem'] - self.brkval = brkval - self.freemem = freemem - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 208, struct.pack('>HH', self.brkval, self.freemem)) - -class MAVLink_ap_adc_message(MAVLink_message): - ''' - raw ADC output - ''' - def __init__(self, adc1, adc2, adc3, adc4, adc5, adc6): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_AP_ADC, 'AP_ADC') - self._fieldnames = ['adc1', 'adc2', 'adc3', 'adc4', 'adc5', 'adc6'] - self.adc1 = adc1 - self.adc2 = adc2 - self.adc3 = adc3 - self.adc4 = adc4 - self.adc5 = adc5 - self.adc6 = adc6 - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 188, struct.pack('>HHHHHH', self.adc1, self.adc2, self.adc3, self.adc4, self.adc5, self.adc6)) - -class MAVLink_digicam_configure_message(MAVLink_message): - ''' - Configure on-board Camera Control System. - ''' - def __init__(self, target_system, target_component, mode, shutter_speed, aperture, iso, exposure_type, command_id, engine_cut_off, extra_param, extra_value): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, 'DIGICAM_CONFIGURE') - self._fieldnames = ['target_system', 'target_component', 'mode', 'shutter_speed', 'aperture', 'iso', 'exposure_type', 'command_id', 'engine_cut_off', 'extra_param', 'extra_value'] - self.target_system = target_system - self.target_component = target_component - self.mode = mode - self.shutter_speed = shutter_speed - self.aperture = aperture - self.iso = iso - self.exposure_type = exposure_type - self.command_id = command_id - self.engine_cut_off = engine_cut_off - self.extra_param = extra_param - self.extra_value = extra_value - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 118, struct.pack('>BBBHBBBBBBf', self.target_system, self.target_component, self.mode, self.shutter_speed, self.aperture, self.iso, self.exposure_type, self.command_id, self.engine_cut_off, self.extra_param, self.extra_value)) - -class MAVLink_digicam_control_message(MAVLink_message): - ''' - Control on-board Camera Control System to take shots. - ''' - def __init__(self, target_system, target_component, session, zoom_pos, zoom_step, focus_lock, shot, command_id, extra_param, extra_value): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_DIGICAM_CONTROL, 'DIGICAM_CONTROL') - self._fieldnames = ['target_system', 'target_component', 'session', 'zoom_pos', 'zoom_step', 'focus_lock', 'shot', 'command_id', 'extra_param', 'extra_value'] - self.target_system = target_system - self.target_component = target_component - self.session = session - self.zoom_pos = zoom_pos - self.zoom_step = zoom_step - self.focus_lock = focus_lock - self.shot = shot - self.command_id = command_id - self.extra_param = extra_param - self.extra_value = extra_value - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 242, struct.pack('>BBBBbBBBBf', self.target_system, self.target_component, self.session, self.zoom_pos, self.zoom_step, self.focus_lock, self.shot, self.command_id, self.extra_param, self.extra_value)) - -class MAVLink_mount_configure_message(MAVLink_message): - ''' - Message to configure a camera mount, directional antenna, etc. - ''' - def __init__(self, target_system, target_component, mount_mode, stab_roll, stab_pitch, stab_yaw): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_MOUNT_CONFIGURE, 'MOUNT_CONFIGURE') - self._fieldnames = ['target_system', 'target_component', 'mount_mode', 'stab_roll', 'stab_pitch', 'stab_yaw'] - self.target_system = target_system - self.target_component = target_component - self.mount_mode = mount_mode - self.stab_roll = stab_roll - self.stab_pitch = stab_pitch - self.stab_yaw = stab_yaw - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 19, struct.pack('>BBBBBB', self.target_system, self.target_component, self.mount_mode, self.stab_roll, self.stab_pitch, self.stab_yaw)) - -class MAVLink_mount_control_message(MAVLink_message): - ''' - Message to control a camera mount, directional antenna, etc. - ''' - def __init__(self, target_system, target_component, input_a, input_b, input_c, save_position): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_MOUNT_CONTROL, 'MOUNT_CONTROL') - self._fieldnames = ['target_system', 'target_component', 'input_a', 'input_b', 'input_c', 'save_position'] - self.target_system = target_system - self.target_component = target_component - self.input_a = input_a - self.input_b = input_b - self.input_c = input_c - self.save_position = save_position - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 97, struct.pack('>BBiiiB', self.target_system, self.target_component, self.input_a, self.input_b, self.input_c, self.save_position)) - -class MAVLink_mount_status_message(MAVLink_message): - ''' - Message with some status from APM to GCS about camera or - antenna mount - ''' - def __init__(self, target_system, target_component, pointing_a, pointing_b, pointing_c): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_MOUNT_STATUS, 'MOUNT_STATUS') - self._fieldnames = ['target_system', 'target_component', 'pointing_a', 'pointing_b', 'pointing_c'] - self.target_system = target_system - self.target_component = target_component - self.pointing_a = pointing_a - self.pointing_b = pointing_b - self.pointing_c = pointing_c - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 233, struct.pack('>BBiii', self.target_system, self.target_component, self.pointing_a, self.pointing_b, self.pointing_c)) - -class MAVLink_fence_point_message(MAVLink_message): - ''' - A fence point. Used to set a point when from GCS - -> MAV. Also used to return a point from MAV -> GCS - ''' - def __init__(self, target_system, target_component, idx, count, lat, lng): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_FENCE_POINT, 'FENCE_POINT') - self._fieldnames = ['target_system', 'target_component', 'idx', 'count', 'lat', 'lng'] - self.target_system = target_system - self.target_component = target_component - self.idx = idx - self.count = count - self.lat = lat - self.lng = lng - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 18, struct.pack('>BBBBff', self.target_system, self.target_component, self.idx, self.count, self.lat, self.lng)) - -class MAVLink_fence_fetch_point_message(MAVLink_message): - ''' - Request a current fence point from MAV - ''' - def __init__(self, target_system, target_component, idx): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_FENCE_FETCH_POINT, 'FENCE_FETCH_POINT') - self._fieldnames = ['target_system', 'target_component', 'idx'] - self.target_system = target_system - self.target_component = target_component - self.idx = idx - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 68, struct.pack('>BBB', self.target_system, self.target_component, self.idx)) - -class MAVLink_fence_status_message(MAVLink_message): - ''' - Status of geo-fencing. Sent in extended status - stream when fencing enabled - ''' - def __init__(self, breach_status, breach_count, breach_type, breach_time): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_FENCE_STATUS, 'FENCE_STATUS') - self._fieldnames = ['breach_status', 'breach_count', 'breach_type', 'breach_time'] - self.breach_status = breach_status - self.breach_count = breach_count - self.breach_type = breach_type - self.breach_time = breach_time - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 136, struct.pack('>BHBI', self.breach_status, self.breach_count, self.breach_type, self.breach_time)) - -class MAVLink_heartbeat_message(MAVLink_message): - ''' - The heartbeat message shows that a system is present and - responding. The type of the MAV and Autopilot hardware allow - the receiving system to treat further messages from this - system appropriate (e.g. by laying out the user interface - based on the autopilot). - ''' - def __init__(self, type, autopilot, mavlink_version): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_HEARTBEAT, 'HEARTBEAT') - self._fieldnames = ['type', 'autopilot', 'mavlink_version'] - self.type = type - self.autopilot = autopilot - self.mavlink_version = mavlink_version - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 72, struct.pack('>BBB', self.type, self.autopilot, self.mavlink_version)) - -class MAVLink_boot_message(MAVLink_message): - ''' - The boot message indicates that a system is starting. The - onboard software version allows to keep track of onboard - soft/firmware revisions. - ''' - def __init__(self, version): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_BOOT, 'BOOT') - self._fieldnames = ['version'] - self.version = version - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 39, struct.pack('>I', self.version)) - -class MAVLink_system_time_message(MAVLink_message): - ''' - The system time is the time of the master clock, typically the - computer clock of the main onboard computer. - ''' - def __init__(self, time_usec): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SYSTEM_TIME, 'SYSTEM_TIME') - self._fieldnames = ['time_usec'] - self.time_usec = time_usec - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 190, struct.pack('>Q', self.time_usec)) - -class MAVLink_ping_message(MAVLink_message): - ''' - A ping message either requesting or responding to a ping. This - allows to measure the system latencies, including serial port, - radio modem and UDP connections. - ''' - def __init__(self, seq, target_system, target_component, time): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_PING, 'PING') - self._fieldnames = ['seq', 'target_system', 'target_component', 'time'] - self.seq = seq - self.target_system = target_system - self.target_component = target_component - self.time = time - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 92, struct.pack('>IBBQ', self.seq, self.target_system, self.target_component, self.time)) - -class MAVLink_system_time_utc_message(MAVLink_message): - ''' - UTC date and time from GPS module - ''' - def __init__(self, utc_date, utc_time): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SYSTEM_TIME_UTC, 'SYSTEM_TIME_UTC') - self._fieldnames = ['utc_date', 'utc_time'] - self.utc_date = utc_date - self.utc_time = utc_time - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 191, struct.pack('>II', self.utc_date, self.utc_time)) - -class MAVLink_change_operator_control_message(MAVLink_message): - ''' - Request to control this MAV - ''' - def __init__(self, target_system, control_request, version, passkey): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, 'CHANGE_OPERATOR_CONTROL') - self._fieldnames = ['target_system', 'control_request', 'version', 'passkey'] - self.target_system = target_system - self.control_request = control_request - self.version = version - self.passkey = passkey - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 217, struct.pack('>BBB25s', self.target_system, self.control_request, self.version, self.passkey)) - -class MAVLink_change_operator_control_ack_message(MAVLink_message): - ''' - Accept / deny control of this MAV - ''' - def __init__(self, gcs_system_id, control_request, ack): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, 'CHANGE_OPERATOR_CONTROL_ACK') - self._fieldnames = ['gcs_system_id', 'control_request', 'ack'] - self.gcs_system_id = gcs_system_id - self.control_request = control_request - self.ack = ack - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 104, struct.pack('>BBB', self.gcs_system_id, self.control_request, self.ack)) - -class MAVLink_auth_key_message(MAVLink_message): - ''' - Emit an encrypted signature / key identifying this system. - PLEASE NOTE: This protocol has been kept simple, so - transmitting the key requires an encrypted channel for true - safety. - ''' - def __init__(self, key): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_AUTH_KEY, 'AUTH_KEY') - self._fieldnames = ['key'] - self.key = key - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 119, struct.pack('>32s', self.key)) - -class MAVLink_action_ack_message(MAVLink_message): - ''' - This message acknowledges an action. IMPORTANT: The - acknowledgement can be also negative, e.g. the MAV rejects a - reset message because it is in-flight. The action ids are - defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h - ''' - def __init__(self, action, result): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_ACTION_ACK, 'ACTION_ACK') - self._fieldnames = ['action', 'result'] - self.action = action - self.result = result - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 219, struct.pack('>BB', self.action, self.result)) - -class MAVLink_action_message(MAVLink_message): - ''' - An action message allows to execute a certain onboard action. - These include liftoff, land, storing parameters too EEPROM, - shutddown, etc. The action ids are defined in ENUM MAV_ACTION - in mavlink/include/mavlink_types.h - ''' - def __init__(self, target, target_component, action): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_ACTION, 'ACTION') - self._fieldnames = ['target', 'target_component', 'action'] - self.target = target - self.target_component = target_component - self.action = action - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 60, struct.pack('>BBB', self.target, self.target_component, self.action)) - -class MAVLink_set_mode_message(MAVLink_message): - ''' - Set the system mode, as defined by enum MAV_MODE in - mavlink/include/mavlink_types.h. There is no target component - id as the mode is by definition for the overall aircraft, not - only for one component. - ''' - def __init__(self, target, mode): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_MODE, 'SET_MODE') - self._fieldnames = ['target', 'mode'] - self.target = target - self.mode = mode - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 186, struct.pack('>BB', self.target, self.mode)) - -class MAVLink_set_nav_mode_message(MAVLink_message): - ''' - Set the system navigation mode, as defined by enum - MAV_NAV_MODE in mavlink/include/mavlink_types.h. The - navigation mode applies to the whole aircraft and thus all - components. - ''' - def __init__(self, target, nav_mode): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_NAV_MODE, 'SET_NAV_MODE') - self._fieldnames = ['target', 'nav_mode'] - self.target = target - self.nav_mode = nav_mode - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 10, struct.pack('>BB', self.target, self.nav_mode)) - -class MAVLink_param_request_read_message(MAVLink_message): - ''' - Request to read the onboard parameter with the param_id string - id. Onboard parameters are stored as key[const char*] -> - value[float]. This allows to send a parameter to any other - component (such as the GCS) without the need of previous - knowledge of possible parameter names. Thus the same GCS can - store different parameters for different autopilots. See also - http://qgroundcontrol.org/parameter_interface for a full - documentation of QGroundControl and IMU code. - ''' - def __init__(self, target_system, target_component, param_id, param_index): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_REQUEST_READ, 'PARAM_REQUEST_READ') - self._fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] - self.target_system = target_system - self.target_component = target_component - self.param_id = param_id - self.param_index = param_index - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 89, struct.pack('>BB15sh', self.target_system, self.target_component, self.param_id, self.param_index)) - -class MAVLink_param_request_list_message(MAVLink_message): - ''' - Request all parameters of this component. After his request, - all parameters are emitted. - ''' - def __init__(self, target_system, target_component): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, 'PARAM_REQUEST_LIST') - self._fieldnames = ['target_system', 'target_component'] - self.target_system = target_system - self.target_component = target_component - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 159, struct.pack('>BB', self.target_system, self.target_component)) - -class MAVLink_param_value_message(MAVLink_message): - ''' - Emit the value of a onboard parameter. The inclusion of - param_count and param_index in the message allows the - recipient to keep track of received parameters and allows him - to re-request missing parameters after a loss or timeout. - ''' - def __init__(self, param_id, param_value, param_count, param_index): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_VALUE, 'PARAM_VALUE') - self._fieldnames = ['param_id', 'param_value', 'param_count', 'param_index'] - self.param_id = param_id - self.param_value = param_value - self.param_count = param_count - self.param_index = param_index - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 162, struct.pack('>15sfHH', self.param_id, self.param_value, self.param_count, self.param_index)) - -class MAVLink_param_set_message(MAVLink_message): - ''' - Set a parameter value TEMPORARILY to RAM. It will be reset to - default on system reboot. Send the ACTION - MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents - to EEPROM. IMPORTANT: The receiving component should - acknowledge the new parameter value by sending a param_value - message to all communication partners. This will also ensure - that multiple GCS all have an up-to-date list of all - parameters. If the sending GCS did not receive a PARAM_VALUE - message within its timeout time, it should re-send the - PARAM_SET message. - ''' - def __init__(self, target_system, target_component, param_id, param_value): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_SET, 'PARAM_SET') - self._fieldnames = ['target_system', 'target_component', 'param_id', 'param_value'] - self.target_system = target_system - self.target_component = target_component - self.param_id = param_id - self.param_value = param_value - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 121, struct.pack('>BB15sf', self.target_system, self.target_component, self.param_id, self.param_value)) - -class MAVLink_gps_raw_int_message(MAVLink_message): - ''' - The global position, as returned by the Global Positioning - System (GPS). This is NOT the global position estimate of the - sytem, but rather a RAW sensor value. See message - GLOBAL_POSITION for the global position estimate. Coordinate - frame is right-handed, Z-axis up (GPS frame) - ''' - def __init__(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_RAW_INT, 'GPS_RAW_INT') - self._fieldnames = ['usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg'] - self.usec = usec - self.fix_type = fix_type - self.lat = lat - self.lon = lon - self.alt = alt - self.eph = eph - self.epv = epv - self.v = v - self.hdg = hdg - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 149, struct.pack('>QBiiiffff', self.usec, self.fix_type, self.lat, self.lon, self.alt, self.eph, self.epv, self.v, self.hdg)) - -class MAVLink_scaled_imu_message(MAVLink_message): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This - message should contain the scaled values to the described - units - ''' - def __init__(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SCALED_IMU, 'SCALED_IMU') - self._fieldnames = ['usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag'] - self.usec = usec - self.xacc = xacc - self.yacc = yacc - self.zacc = zacc - self.xgyro = xgyro - self.ygyro = ygyro - self.zgyro = zgyro - self.xmag = xmag - self.ymag = ymag - self.zmag = zmag - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 222, struct.pack('>Qhhhhhhhhh', self.usec, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag)) - -class MAVLink_gps_status_message(MAVLink_message): - ''' - The positioning status, as reported by GPS. This message is - intended to display status information about each satellite - visible to the receiver. See message GLOBAL_POSITION for the - global position estimate. This message can contain information - for up to 20 satellites. - ''' - def __init__(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_STATUS, 'GPS_STATUS') - self._fieldnames = ['satellites_visible', 'satellite_prn', 'satellite_used', 'satellite_elevation', 'satellite_azimuth', 'satellite_snr'] - self.satellites_visible = satellites_visible - self.satellite_prn = satellite_prn - self.satellite_used = satellite_used - self.satellite_elevation = satellite_elevation - self.satellite_azimuth = satellite_azimuth - self.satellite_snr = satellite_snr - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 110, struct.pack('>B20s20s20s20s20s', self.satellites_visible, self.satellite_prn, self.satellite_used, self.satellite_elevation, self.satellite_azimuth, self.satellite_snr)) - -class MAVLink_raw_imu_message(MAVLink_message): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This - message should always contain the true raw values without any - scaling to allow data capture and system debugging. - ''' - def __init__(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_RAW_IMU, 'RAW_IMU') - self._fieldnames = ['usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag'] - self.usec = usec - self.xacc = xacc - self.yacc = yacc - self.zacc = zacc - self.xgyro = xgyro - self.ygyro = ygyro - self.zgyro = zgyro - self.xmag = xmag - self.ymag = ymag - self.zmag = zmag - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 179, struct.pack('>Qhhhhhhhhh', self.usec, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag)) - -class MAVLink_raw_pressure_message(MAVLink_message): - ''' - The RAW pressure readings for the typical setup of one - absolute pressure and one differential pressure sensor. The - sensor values should be the raw, UNSCALED ADC values. - ''' - def __init__(self, usec, press_abs, press_diff1, press_diff2, temperature): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_RAW_PRESSURE, 'RAW_PRESSURE') - self._fieldnames = ['usec', 'press_abs', 'press_diff1', 'press_diff2', 'temperature'] - self.usec = usec - self.press_abs = press_abs - self.press_diff1 = press_diff1 - self.press_diff2 = press_diff2 - self.temperature = temperature - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 136, struct.pack('>Qhhhh', self.usec, self.press_abs, self.press_diff1, self.press_diff2, self.temperature)) - -class MAVLink_scaled_pressure_message(MAVLink_message): - ''' - The pressure readings for the typical setup of one absolute - and differential pressure sensor. The units are as specified - in each field. - ''' - def __init__(self, usec, press_abs, press_diff, temperature): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SCALED_PRESSURE, 'SCALED_PRESSURE') - self._fieldnames = ['usec', 'press_abs', 'press_diff', 'temperature'] - self.usec = usec - self.press_abs = press_abs - self.press_diff = press_diff - self.temperature = temperature - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 229, struct.pack('>Qffh', self.usec, self.press_abs, self.press_diff, self.temperature)) - -class MAVLink_attitude_message(MAVLink_message): - ''' - The attitude in the aeronautical frame (right-handed, Z-down, - X-front, Y-right). - ''' - def __init__(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_ATTITUDE, 'ATTITUDE') - self._fieldnames = ['usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed'] - self.usec = usec - self.roll = roll - self.pitch = pitch - self.yaw = yaw - self.rollspeed = rollspeed - self.pitchspeed = pitchspeed - self.yawspeed = yawspeed - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 66, struct.pack('>Qffffff', self.usec, self.roll, self.pitch, self.yaw, self.rollspeed, self.pitchspeed, self.yawspeed)) - -class MAVLink_local_position_message(MAVLink_message): - ''' - The filtered local position (e.g. fused computer vision and - accelerometers). Coordinate frame is right-handed, Z-axis down - (aeronautical frame) - ''' - def __init__(self, usec, x, y, z, vx, vy, vz): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_LOCAL_POSITION, 'LOCAL_POSITION') - self._fieldnames = ['usec', 'x', 'y', 'z', 'vx', 'vy', 'vz'] - self.usec = usec - self.x = x - self.y = y - self.z = z - self.vx = vx - self.vy = vy - self.vz = vz - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 126, struct.pack('>Qffffff', self.usec, self.x, self.y, self.z, self.vx, self.vy, self.vz)) - -class MAVLink_global_position_message(MAVLink_message): - ''' - The filtered global position (e.g. fused GPS and - accelerometers). Coordinate frame is right-handed, Z-axis up - (GPS frame) - ''' - def __init__(self, usec, lat, lon, alt, vx, vy, vz): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_GLOBAL_POSITION, 'GLOBAL_POSITION') - self._fieldnames = ['usec', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz'] - self.usec = usec - self.lat = lat - self.lon = lon - self.alt = alt - self.vx = vx - self.vy = vy - self.vz = vz - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 147, struct.pack('>Qffffff', self.usec, self.lat, self.lon, self.alt, self.vx, self.vy, self.vz)) - -class MAVLink_gps_raw_message(MAVLink_message): - ''' - The global position, as returned by the Global Positioning - System (GPS). This is NOT the global position estimate of the - sytem, but rather a RAW sensor value. See message - GLOBAL_POSITION for the global position estimate. Coordinate - frame is right-handed, Z-axis up (GPS frame) - ''' - def __init__(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_RAW, 'GPS_RAW') - self._fieldnames = ['usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg'] - self.usec = usec - self.fix_type = fix_type - self.lat = lat - self.lon = lon - self.alt = alt - self.eph = eph - self.epv = epv - self.v = v - self.hdg = hdg - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 185, struct.pack('>QBfffffff', self.usec, self.fix_type, self.lat, self.lon, self.alt, self.eph, self.epv, self.v, self.hdg)) - -class MAVLink_sys_status_message(MAVLink_message): - ''' - The general system state. If the system is following the - MAVLink standard, the system state is mainly defined by three - orthogonal states/modes: The system mode, which is either - LOCKED (motors shut down and locked), MANUAL (system under RC - control), GUIDED (system with autonomous position control, - position setpoint controlled manually) or AUTO (system guided - by path/waypoint planner). The NAV_MODE defined the current - flight state: LIFTOFF (often an open-loop maneuver), LANDING, - WAYPOINTS or VECTOR. This represents the internal navigation - state machine. The system status shows wether the system is - currently active or not and if an emergency occured. During - the CRITICAL and EMERGENCY states the MAV is still considered - to be active, but should start emergency procedures - autonomously. After a failure occured it should first move - from active to critical to allow manual intervention and then - move to emergency after a certain timeout. - ''' - def __init__(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SYS_STATUS, 'SYS_STATUS') - self._fieldnames = ['mode', 'nav_mode', 'status', 'load', 'vbat', 'battery_remaining', 'packet_drop'] - self.mode = mode - self.nav_mode = nav_mode - self.status = status - self.load = load - self.vbat = vbat - self.battery_remaining = battery_remaining - self.packet_drop = packet_drop - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 112, struct.pack('>BBBHHHH', self.mode, self.nav_mode, self.status, self.load, self.vbat, self.battery_remaining, self.packet_drop)) - -class MAVLink_rc_channels_raw_message(MAVLink_message): - ''' - The RAW values of the RC channels received. The standard PPM - modulation is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. Individual receivers/transmitters might - violate this specification. - ''' - def __init__(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_RC_CHANNELS_RAW, 'RC_CHANNELS_RAW') - self._fieldnames = ['chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw', 'rssi'] - self.chan1_raw = chan1_raw - self.chan2_raw = chan2_raw - self.chan3_raw = chan3_raw - self.chan4_raw = chan4_raw - self.chan5_raw = chan5_raw - self.chan6_raw = chan6_raw - self.chan7_raw = chan7_raw - self.chan8_raw = chan8_raw - self.rssi = rssi - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 252, struct.pack('>HHHHHHHHB', self.chan1_raw, self.chan2_raw, self.chan3_raw, self.chan4_raw, self.chan5_raw, self.chan6_raw, self.chan7_raw, self.chan8_raw, self.rssi)) - -class MAVLink_rc_channels_scaled_message(MAVLink_message): - ''' - The scaled values of the RC channels received. (-100%) -10000, - (0%) 0, (100%) 10000 - ''' - def __init__(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, 'RC_CHANNELS_SCALED') - self._fieldnames = ['chan1_scaled', 'chan2_scaled', 'chan3_scaled', 'chan4_scaled', 'chan5_scaled', 'chan6_scaled', 'chan7_scaled', 'chan8_scaled', 'rssi'] - self.chan1_scaled = chan1_scaled - self.chan2_scaled = chan2_scaled - self.chan3_scaled = chan3_scaled - self.chan4_scaled = chan4_scaled - self.chan5_scaled = chan5_scaled - self.chan6_scaled = chan6_scaled - self.chan7_scaled = chan7_scaled - self.chan8_scaled = chan8_scaled - self.rssi = rssi - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 162, struct.pack('>hhhhhhhhB', self.chan1_scaled, self.chan2_scaled, self.chan3_scaled, self.chan4_scaled, self.chan5_scaled, self.chan6_scaled, self.chan7_scaled, self.chan8_scaled, self.rssi)) - -class MAVLink_servo_output_raw_message(MAVLink_message): - ''' - The RAW values of the servo outputs (for RC input from the - remote, use the RC_CHANNELS messages). The standard PPM - modulation is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. - ''' - def __init__(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 'SERVO_OUTPUT_RAW') - self._fieldnames = ['servo1_raw', 'servo2_raw', 'servo3_raw', 'servo4_raw', 'servo5_raw', 'servo6_raw', 'servo7_raw', 'servo8_raw'] - self.servo1_raw = servo1_raw - self.servo2_raw = servo2_raw - self.servo3_raw = servo3_raw - self.servo4_raw = servo4_raw - self.servo5_raw = servo5_raw - self.servo6_raw = servo6_raw - self.servo7_raw = servo7_raw - self.servo8_raw = servo8_raw - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 215, struct.pack('>HHHHHHHH', self.servo1_raw, self.servo2_raw, self.servo3_raw, self.servo4_raw, self.servo5_raw, self.servo6_raw, self.servo7_raw, self.servo8_raw)) - -class MAVLink_waypoint_message(MAVLink_message): - ''' - Message encoding a waypoint. This message is emitted to - announce the presence of a waypoint and to set a waypoint - on the system. The waypoint can be either in x, y, z meters - (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is - Z-down, right handed, global frame is Z-up, right handed - ''' - def __init__(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT, 'WAYPOINT') - self._fieldnames = ['target_system', 'target_component', 'seq', 'frame', 'command', 'current', 'autocontinue', 'param1', 'param2', 'param3', 'param4', 'x', 'y', 'z'] - self.target_system = target_system - self.target_component = target_component - self.seq = seq - self.frame = frame - self.command = command - self.current = current - self.autocontinue = autocontinue - self.param1 = param1 - self.param2 = param2 - self.param3 = param3 - self.param4 = param4 - self.x = x - self.y = y - self.z = z - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 128, struct.pack('>BBHBBBBfffffff', self.target_system, self.target_component, self.seq, self.frame, self.command, self.current, self.autocontinue, self.param1, self.param2, self.param3, self.param4, self.x, self.y, self.z)) - -class MAVLink_waypoint_request_message(MAVLink_message): - ''' - Request the information of the waypoint with the sequence - number seq. The response of the system to this message should - be a WAYPOINT message. - ''' - def __init__(self, target_system, target_component, seq): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_REQUEST, 'WAYPOINT_REQUEST') - self._fieldnames = ['target_system', 'target_component', 'seq'] - self.target_system = target_system - self.target_component = target_component - self.seq = seq - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 9, struct.pack('>BBH', self.target_system, self.target_component, self.seq)) - -class MAVLink_waypoint_set_current_message(MAVLink_message): - ''' - Set the waypoint with sequence number seq as current waypoint. - This means that the MAV will continue to this waypoint on the - shortest path (not following the waypoints in-between). - ''' - def __init__(self, target_system, target_component, seq): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT, 'WAYPOINT_SET_CURRENT') - self._fieldnames = ['target_system', 'target_component', 'seq'] - self.target_system = target_system - self.target_component = target_component - self.seq = seq - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 106, struct.pack('>BBH', self.target_system, self.target_component, self.seq)) - -class MAVLink_waypoint_current_message(MAVLink_message): - ''' - Message that announces the sequence number of the current - active waypoint. The MAV will fly towards this waypoint. - ''' - def __init__(self, seq): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_CURRENT, 'WAYPOINT_CURRENT') - self._fieldnames = ['seq'] - self.seq = seq - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 101, struct.pack('>H', self.seq)) - -class MAVLink_waypoint_request_list_message(MAVLink_message): - ''' - Request the overall list of waypoints from the - system/component. - ''' - def __init__(self, target_system, target_component): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST, 'WAYPOINT_REQUEST_LIST') - self._fieldnames = ['target_system', 'target_component'] - self.target_system = target_system - self.target_component = target_component - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 213, struct.pack('>BB', self.target_system, self.target_component)) - -class MAVLink_waypoint_count_message(MAVLink_message): - ''' - This message is emitted as response to WAYPOINT_REQUEST_LIST - by the MAV. The GCS can then request the individual waypoints - based on the knowledge of the total number of waypoints. - ''' - def __init__(self, target_system, target_component, count): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_COUNT, 'WAYPOINT_COUNT') - self._fieldnames = ['target_system', 'target_component', 'count'] - self.target_system = target_system - self.target_component = target_component - self.count = count - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 4, struct.pack('>BBH', self.target_system, self.target_component, self.count)) - -class MAVLink_waypoint_clear_all_message(MAVLink_message): - ''' - Delete all waypoints at once. - ''' - def __init__(self, target_system, target_component): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL, 'WAYPOINT_CLEAR_ALL') - self._fieldnames = ['target_system', 'target_component'] - self.target_system = target_system - self.target_component = target_component - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 229, struct.pack('>BB', self.target_system, self.target_component)) - -class MAVLink_waypoint_reached_message(MAVLink_message): - ''' - A certain waypoint has been reached. The system will either - hold this position (or circle on the orbit) or (if the - autocontinue on the WP was set) continue to the next waypoint. - ''' - def __init__(self, seq): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_REACHED, 'WAYPOINT_REACHED') - self._fieldnames = ['seq'] - self.seq = seq - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 21, struct.pack('>H', self.seq)) - -class MAVLink_waypoint_ack_message(MAVLink_message): - ''' - Ack message during waypoint handling. The type field states if - this message is a positive ack (type=0) or if an error - happened (type=non-zero). - ''' - def __init__(self, target_system, target_component, type): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_ACK, 'WAYPOINT_ACK') - self._fieldnames = ['target_system', 'target_component', 'type'] - self.target_system = target_system - self.target_component = target_component - self.type = type - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 214, struct.pack('>BBB', self.target_system, self.target_component, self.type)) - -class MAVLink_gps_set_global_origin_message(MAVLink_message): - ''' - As local waypoints exist, the global waypoint reference allows - to transform between the local coordinate frame and the global - (GPS) coordinate frame. This can be necessary when e.g. in- - and outdoor settings are connected and the MAV should move - from in- to outdoor. - ''' - def __init__(self, target_system, target_component, latitude, longitude, altitude): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN, 'GPS_SET_GLOBAL_ORIGIN') - self._fieldnames = ['target_system', 'target_component', 'latitude', 'longitude', 'altitude'] - self.target_system = target_system - self.target_component = target_component - self.latitude = latitude - self.longitude = longitude - self.altitude = altitude - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 215, struct.pack('>BBiii', self.target_system, self.target_component, self.latitude, self.longitude, self.altitude)) - -class MAVLink_gps_local_origin_set_message(MAVLink_message): - ''' - Once the MAV sets a new GPS-Local correspondence, this message - announces the origin (0,0,0) position - ''' - def __init__(self, latitude, longitude, altitude): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET, 'GPS_LOCAL_ORIGIN_SET') - self._fieldnames = ['latitude', 'longitude', 'altitude'] - self.latitude = latitude - self.longitude = longitude - self.altitude = altitude - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 14, struct.pack('>iii', self.latitude, self.longitude, self.altitude)) - -class MAVLink_local_position_setpoint_set_message(MAVLink_message): - ''' - Set the setpoint for a local position controller. This is the - position in local coordinates the MAV should fly to. This - message is sent by the path/waypoint planner to the onboard - position controller. As some MAVs have a degree of freedom in - yaw (e.g. all helicopters/quadrotors), the desired yaw angle - is part of the message. - ''' - def __init__(self, target_system, target_component, x, y, z, yaw): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET, 'LOCAL_POSITION_SETPOINT_SET') - self._fieldnames = ['target_system', 'target_component', 'x', 'y', 'z', 'yaw'] - self.target_system = target_system - self.target_component = target_component - self.x = x - self.y = y - self.z = z - self.yaw = yaw - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 206, struct.pack('>BBffff', self.target_system, self.target_component, self.x, self.y, self.z, self.yaw)) - -class MAVLink_local_position_setpoint_message(MAVLink_message): - ''' - Transmit the current local setpoint of the controller to other - MAVs (collision avoidance) and to the GCS. - ''' - def __init__(self, x, y, z, yaw): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, 'LOCAL_POSITION_SETPOINT') - self._fieldnames = ['x', 'y', 'z', 'yaw'] - self.x = x - self.y = y - self.z = z - self.yaw = yaw - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 50, struct.pack('>ffff', self.x, self.y, self.z, self.yaw)) - -class MAVLink_control_status_message(MAVLink_message): - ''' - - ''' - def __init__(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_CONTROL_STATUS, 'CONTROL_STATUS') - self._fieldnames = ['position_fix', 'vision_fix', 'gps_fix', 'ahrs_health', 'control_att', 'control_pos_xy', 'control_pos_z', 'control_pos_yaw'] - self.position_fix = position_fix - self.vision_fix = vision_fix - self.gps_fix = gps_fix - self.ahrs_health = ahrs_health - self.control_att = control_att - self.control_pos_xy = control_pos_xy - self.control_pos_z = control_pos_z - self.control_pos_yaw = control_pos_yaw - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 157, struct.pack('>BBBBBBBB', self.position_fix, self.vision_fix, self.gps_fix, self.ahrs_health, self.control_att, self.control_pos_xy, self.control_pos_z, self.control_pos_yaw)) - -class MAVLink_safety_set_allowed_area_message(MAVLink_message): - ''' - Set a safety zone (volume), which is defined by two corners of - a cube. This message can be used to tell the MAV which - setpoints/waypoints to accept and which to reject. Safety - areas are often enforced by national or competition - regulations. - ''' - def __init__(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, 'SAFETY_SET_ALLOWED_AREA') - self._fieldnames = ['target_system', 'target_component', 'frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z'] - self.target_system = target_system - self.target_component = target_component - self.frame = frame - self.p1x = p1x - self.p1y = p1y - self.p1z = p1z - self.p2x = p2x - self.p2y = p2y - self.p2z = p2z - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 126, struct.pack('>BBBffffff', self.target_system, self.target_component, self.frame, self.p1x, self.p1y, self.p1z, self.p2x, self.p2y, self.p2z)) - -class MAVLink_safety_allowed_area_message(MAVLink_message): - ''' - Read out the safety zone the MAV currently assumes. - ''' - def __init__(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, 'SAFETY_ALLOWED_AREA') - self._fieldnames = ['frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z'] - self.frame = frame - self.p1x = p1x - self.p1y = p1y - self.p1z = p1z - self.p2x = p2x - self.p2y = p2y - self.p2z = p2z - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 108, struct.pack('>Bffffff', self.frame, self.p1x, self.p1y, self.p1z, self.p2x, self.p2y, self.p2z)) - -class MAVLink_set_roll_pitch_yaw_thrust_message(MAVLink_message): - ''' - Set roll, pitch and yaw. - ''' - def __init__(self, target_system, target_component, roll, pitch, yaw, thrust): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, 'SET_ROLL_PITCH_YAW_THRUST') - self._fieldnames = ['target_system', 'target_component', 'roll', 'pitch', 'yaw', 'thrust'] - self.target_system = target_system - self.target_component = target_component - self.roll = roll - self.pitch = pitch - self.yaw = yaw - self.thrust = thrust - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 213, struct.pack('>BBffff', self.target_system, self.target_component, self.roll, self.pitch, self.yaw, self.thrust)) - -class MAVLink_set_roll_pitch_yaw_speed_thrust_message(MAVLink_message): - ''' - Set roll, pitch and yaw. - ''' - def __init__(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, 'SET_ROLL_PITCH_YAW_SPEED_THRUST') - self._fieldnames = ['target_system', 'target_component', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust'] - self.target_system = target_system - self.target_component = target_component - self.roll_speed = roll_speed - self.pitch_speed = pitch_speed - self.yaw_speed = yaw_speed - self.thrust = thrust - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 95, struct.pack('>BBffff', self.target_system, self.target_component, self.roll_speed, self.pitch_speed, self.yaw_speed, self.thrust)) - -class MAVLink_roll_pitch_yaw_thrust_setpoint_message(MAVLink_message): - ''' - Setpoint in roll, pitch, yaw currently active on the system. - ''' - def __init__(self, time_us, roll, pitch, yaw, thrust): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, 'ROLL_PITCH_YAW_THRUST_SETPOINT') - self._fieldnames = ['time_us', 'roll', 'pitch', 'yaw', 'thrust'] - self.time_us = time_us - self.roll = roll - self.pitch = pitch - self.yaw = yaw - self.thrust = thrust - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 5, struct.pack('>Qffff', self.time_us, self.roll, self.pitch, self.yaw, self.thrust)) - -class MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(MAVLink_message): - ''' - Setpoint in rollspeed, pitchspeed, yawspeed currently active - on the system. - ''' - def __init__(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, 'ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT') - self._fieldnames = ['time_us', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust'] - self.time_us = time_us - self.roll_speed = roll_speed - self.pitch_speed = pitch_speed - self.yaw_speed = yaw_speed - self.thrust = thrust - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 127, struct.pack('>Qffff', self.time_us, self.roll_speed, self.pitch_speed, self.yaw_speed, self.thrust)) - -class MAVLink_nav_controller_output_message(MAVLink_message): - ''' - Outputs of the APM navigation controller. The primary use of - this message is to check the response and signs of the - controller before actual flight and to assist with tuning - controller parameters - ''' - def __init__(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, 'NAV_CONTROLLER_OUTPUT') - self._fieldnames = ['nav_roll', 'nav_pitch', 'nav_bearing', 'target_bearing', 'wp_dist', 'alt_error', 'aspd_error', 'xtrack_error'] - self.nav_roll = nav_roll - self.nav_pitch = nav_pitch - self.nav_bearing = nav_bearing - self.target_bearing = target_bearing - self.wp_dist = wp_dist - self.alt_error = alt_error - self.aspd_error = aspd_error - self.xtrack_error = xtrack_error - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 57, struct.pack('>ffhhHfff', self.nav_roll, self.nav_pitch, self.nav_bearing, self.target_bearing, self.wp_dist, self.alt_error, self.aspd_error, self.xtrack_error)) - -class MAVLink_position_target_message(MAVLink_message): - ''' - The goal position of the system. This position is the input to - any navigation or path planning algorithm and does NOT - represent the current controller setpoint. - ''' - def __init__(self, x, y, z, yaw): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_POSITION_TARGET, 'POSITION_TARGET') - self._fieldnames = ['x', 'y', 'z', 'yaw'] - self.x = x - self.y = y - self.z = z - self.yaw = yaw - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 126, struct.pack('>ffff', self.x, self.y, self.z, self.yaw)) - -class MAVLink_state_correction_message(MAVLink_message): - ''' - Corrects the systems state by adding an error correction term - to the position and velocity, and by rotating the attitude by - a correction angle. - ''' - def __init__(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_STATE_CORRECTION, 'STATE_CORRECTION') - self._fieldnames = ['xErr', 'yErr', 'zErr', 'rollErr', 'pitchErr', 'yawErr', 'vxErr', 'vyErr', 'vzErr'] - self.xErr = xErr - self.yErr = yErr - self.zErr = zErr - self.rollErr = rollErr - self.pitchErr = pitchErr - self.yawErr = yawErr - self.vxErr = vxErr - self.vyErr = vyErr - self.vzErr = vzErr - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 130, struct.pack('>fffffffff', self.xErr, self.yErr, self.zErr, self.rollErr, self.pitchErr, self.yawErr, self.vxErr, self.vyErr, self.vzErr)) - -class MAVLink_set_altitude_message(MAVLink_message): - ''' - - ''' - def __init__(self, target, mode): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_ALTITUDE, 'SET_ALTITUDE') - self._fieldnames = ['target', 'mode'] - self.target = target - self.mode = mode - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 119, struct.pack('>BI', self.target, self.mode)) - -class MAVLink_request_data_stream_message(MAVLink_message): - ''' - - ''' - def __init__(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, 'REQUEST_DATA_STREAM') - self._fieldnames = ['target_system', 'target_component', 'req_stream_id', 'req_message_rate', 'start_stop'] - self.target_system = target_system - self.target_component = target_component - self.req_stream_id = req_stream_id - self.req_message_rate = req_message_rate - self.start_stop = start_stop - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 193, struct.pack('>BBBHB', self.target_system, self.target_component, self.req_stream_id, self.req_message_rate, self.start_stop)) - -class MAVLink_hil_state_message(MAVLink_message): - ''' - This packet is useful for high throughput - applications such as hardware in the loop simulations. - ''' - def __init__(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_HIL_STATE, 'HIL_STATE') - self._fieldnames = ['usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz', 'xacc', 'yacc', 'zacc'] - self.usec = usec - self.roll = roll - self.pitch = pitch - self.yaw = yaw - self.rollspeed = rollspeed - self.pitchspeed = pitchspeed - self.yawspeed = yawspeed - self.lat = lat - self.lon = lon - self.alt = alt - self.vx = vx - self.vy = vy - self.vz = vz - self.xacc = xacc - self.yacc = yacc - self.zacc = zacc - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 191, struct.pack('>Qffffffiiihhhhhh', self.usec, self.roll, self.pitch, self.yaw, self.rollspeed, self.pitchspeed, self.yawspeed, self.lat, self.lon, self.alt, self.vx, self.vy, self.vz, self.xacc, self.yacc, self.zacc)) - -class MAVLink_hil_controls_message(MAVLink_message): - ''' - Hardware in the loop control outputs - ''' - def __init__(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_HIL_CONTROLS, 'HIL_CONTROLS') - self._fieldnames = ['time_us', 'roll_ailerons', 'pitch_elevator', 'yaw_rudder', 'throttle', 'mode', 'nav_mode'] - self.time_us = time_us - self.roll_ailerons = roll_ailerons - self.pitch_elevator = pitch_elevator - self.yaw_rudder = yaw_rudder - self.throttle = throttle - self.mode = mode - self.nav_mode = nav_mode - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 236, struct.pack('>QffffBB', self.time_us, self.roll_ailerons, self.pitch_elevator, self.yaw_rudder, self.throttle, self.mode, self.nav_mode)) - -class MAVLink_manual_control_message(MAVLink_message): - ''' - - ''' - def __init__(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_MANUAL_CONTROL, 'MANUAL_CONTROL') - self._fieldnames = ['target', 'roll', 'pitch', 'yaw', 'thrust', 'roll_manual', 'pitch_manual', 'yaw_manual', 'thrust_manual'] - self.target = target - self.roll = roll - self.pitch = pitch - self.yaw = yaw - self.thrust = thrust - self.roll_manual = roll_manual - self.pitch_manual = pitch_manual - self.yaw_manual = yaw_manual - self.thrust_manual = thrust_manual - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 158, struct.pack('>BffffBBBB', self.target, self.roll, self.pitch, self.yaw, self.thrust, self.roll_manual, self.pitch_manual, self.yaw_manual, self.thrust_manual)) - -class MAVLink_rc_channels_override_message(MAVLink_message): - ''' - The RAW values of the RC channels sent to the MAV to override - info received from the RC radio. A value of -1 means no change - to that channel. A value of 0 means control of that channel - should be released back to the RC radio. The standard PPM - modulation is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. Individual receivers/transmitters might - violate this specification. - ''' - def __init__(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, 'RC_CHANNELS_OVERRIDE') - self._fieldnames = ['target_system', 'target_component', 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw'] - self.target_system = target_system - self.target_component = target_component - self.chan1_raw = chan1_raw - self.chan2_raw = chan2_raw - self.chan3_raw = chan3_raw - self.chan4_raw = chan4_raw - self.chan5_raw = chan5_raw - self.chan6_raw = chan6_raw - self.chan7_raw = chan7_raw - self.chan8_raw = chan8_raw - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 143, struct.pack('>BBHHHHHHHH', self.target_system, self.target_component, self.chan1_raw, self.chan2_raw, self.chan3_raw, self.chan4_raw, self.chan5_raw, self.chan6_raw, self.chan7_raw, self.chan8_raw)) - -class MAVLink_global_position_int_message(MAVLink_message): - ''' - The filtered global position (e.g. fused GPS and - accelerometers). The position is in GPS-frame (right-handed, - Z-up) - ''' - def __init__(self, lat, lon, alt, vx, vy, vz): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, 'GLOBAL_POSITION_INT') - self._fieldnames = ['lat', 'lon', 'alt', 'vx', 'vy', 'vz'] - self.lat = lat - self.lon = lon - self.alt = alt - self.vx = vx - self.vy = vy - self.vz = vz - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 104, struct.pack('>iiihhh', self.lat, self.lon, self.alt, self.vx, self.vy, self.vz)) - -class MAVLink_vfr_hud_message(MAVLink_message): - ''' - Metrics typically displayed on a HUD for fixed wing aircraft - ''' - def __init__(self, airspeed, groundspeed, heading, throttle, alt, climb): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_VFR_HUD, 'VFR_HUD') - self._fieldnames = ['airspeed', 'groundspeed', 'heading', 'throttle', 'alt', 'climb'] - self.airspeed = airspeed - self.groundspeed = groundspeed - self.heading = heading - self.throttle = throttle - self.alt = alt - self.climb = climb - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 123, struct.pack('>ffhHff', self.airspeed, self.groundspeed, self.heading, self.throttle, self.alt, self.climb)) - -class MAVLink_command_message(MAVLink_message): - ''' - Send a command with up to four parameters to the MAV - ''' - def __init__(self, target_system, target_component, command, confirmation, param1, param2, param3, param4): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_COMMAND, 'COMMAND') - self._fieldnames = ['target_system', 'target_component', 'command', 'confirmation', 'param1', 'param2', 'param3', 'param4'] - self.target_system = target_system - self.target_component = target_component - self.command = command - self.confirmation = confirmation - self.param1 = param1 - self.param2 = param2 - self.param3 = param3 - self.param4 = param4 - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 131, struct.pack('>BBBBffff', self.target_system, self.target_component, self.command, self.confirmation, self.param1, self.param2, self.param3, self.param4)) - -class MAVLink_command_ack_message(MAVLink_message): - ''' - Report status of a command. Includes feedback wether the - command was executed - ''' - def __init__(self, command, result): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_COMMAND_ACK, 'COMMAND_ACK') - self._fieldnames = ['command', 'result'] - self.command = command - self.result = result - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 8, struct.pack('>ff', self.command, self.result)) - -class MAVLink_optical_flow_message(MAVLink_message): - ''' - Optical flow from a flow sensor (e.g. optical mouse sensor) - ''' - def __init__(self, time, sensor_id, flow_x, flow_y, quality, ground_distance): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_OPTICAL_FLOW, 'OPTICAL_FLOW') - self._fieldnames = ['time', 'sensor_id', 'flow_x', 'flow_y', 'quality', 'ground_distance'] - self.time = time - self.sensor_id = sensor_id - self.flow_x = flow_x - self.flow_y = flow_y - self.quality = quality - self.ground_distance = ground_distance - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 174, struct.pack('>QBhhBf', self.time, self.sensor_id, self.flow_x, self.flow_y, self.quality, self.ground_distance)) - -class MAVLink_object_detection_event_message(MAVLink_message): - ''' - Object has been detected - ''' - def __init__(self, time, object_id, type, name, quality, bearing, distance): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT, 'OBJECT_DETECTION_EVENT') - self._fieldnames = ['time', 'object_id', 'type', 'name', 'quality', 'bearing', 'distance'] - self.time = time - self.object_id = object_id - self.type = type - self.name = name - self.quality = quality - self.bearing = bearing - self.distance = distance - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 155, struct.pack('>IHB20sBff', self.time, self.object_id, self.type, self.name, self.quality, self.bearing, self.distance)) - -class MAVLink_debug_vect_message(MAVLink_message): - ''' - - ''' - def __init__(self, name, usec, x, y, z): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_DEBUG_VECT, 'DEBUG_VECT') - self._fieldnames = ['name', 'usec', 'x', 'y', 'z'] - self.name = name - self.usec = usec - self.x = x - self.y = y - self.z = z - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 178, struct.pack('>10sQfff', self.name, self.usec, self.x, self.y, self.z)) - -class MAVLink_named_value_float_message(MAVLink_message): - ''' - Send a key-value pair as float. The use of this message is - discouraged for normal packets, but a quite efficient way for - testing new messages and getting experimental debug output. - ''' - def __init__(self, name, value): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, 'NAMED_VALUE_FLOAT') - self._fieldnames = ['name', 'value'] - self.name = name - self.value = value - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 224, struct.pack('>10sf', self.name, self.value)) - -class MAVLink_named_value_int_message(MAVLink_message): - ''' - Send a key-value pair as integer. The use of this message is - discouraged for normal packets, but a quite efficient way for - testing new messages and getting experimental debug output. - ''' - def __init__(self, name, value): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_NAMED_VALUE_INT, 'NAMED_VALUE_INT') - self._fieldnames = ['name', 'value'] - self.name = name - self.value = value - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 60, struct.pack('>10si', self.name, self.value)) - -class MAVLink_statustext_message(MAVLink_message): - ''' - Status text message. These messages are printed in yellow in - the COMM console of QGroundControl. WARNING: They consume - quite some bandwidth, so use only for important status and - error messages. If implemented wisely, these messages are - buffered on the MCU and sent only at a limited rate (e.g. 10 - Hz). - ''' - def __init__(self, severity, text): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_STATUSTEXT, 'STATUSTEXT') - self._fieldnames = ['severity', 'text'] - self.severity = severity - self.text = text - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 106, struct.pack('>B50s', self.severity, self.text)) - -class MAVLink_debug_message(MAVLink_message): - ''' - Send a debug value. The index is used to discriminate between - values. These values show up in the plot of QGroundControl as - DEBUG N. - ''' - def __init__(self, ind, value): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_DEBUG, 'DEBUG') - self._fieldnames = ['ind', 'value'] - self.ind = ind - self.value = value - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 7, struct.pack('>Bf', self.ind, self.value)) - - -mavlink_map = { - MAVLINK_MSG_ID_SENSOR_OFFSETS : ( '>hhhfiiffffff', MAVLink_sensor_offsets_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11], 143 ), - MAVLINK_MSG_ID_SET_MAG_OFFSETS : ( '>BBhhh', MAVLink_set_mag_offsets_message, [0, 1, 2, 3, 4], 29 ), - MAVLINK_MSG_ID_MEMINFO : ( '>HH', MAVLink_meminfo_message, [0, 1], 208 ), - MAVLINK_MSG_ID_AP_ADC : ( '>HHHHHH', MAVLink_ap_adc_message, [0, 1, 2, 3, 4, 5], 188 ), - MAVLINK_MSG_ID_DIGICAM_CONFIGURE : ( '>BBBHBBBBBBf', MAVLink_digicam_configure_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10], 118 ), - MAVLINK_MSG_ID_DIGICAM_CONTROL : ( '>BBBBbBBBBf', MAVLink_digicam_control_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9], 242 ), - MAVLINK_MSG_ID_MOUNT_CONFIGURE : ( '>BBBBBB', MAVLink_mount_configure_message, [0, 1, 2, 3, 4, 5], 19 ), - MAVLINK_MSG_ID_MOUNT_CONTROL : ( '>BBiiiB', MAVLink_mount_control_message, [0, 1, 2, 3, 4, 5], 97 ), - MAVLINK_MSG_ID_MOUNT_STATUS : ( '>BBiii', MAVLink_mount_status_message, [0, 1, 2, 3, 4], 233 ), - MAVLINK_MSG_ID_FENCE_POINT : ( '>BBBBff', MAVLink_fence_point_message, [0, 1, 2, 3, 4, 5], 18 ), - MAVLINK_MSG_ID_FENCE_FETCH_POINT : ( '>BBB', MAVLink_fence_fetch_point_message, [0, 1, 2], 68 ), - MAVLINK_MSG_ID_FENCE_STATUS : ( '>BHBI', MAVLink_fence_status_message, [0, 1, 2, 3], 136 ), - MAVLINK_MSG_ID_HEARTBEAT : ( '>BBB', MAVLink_heartbeat_message, [0, 1, 2], 72 ), - MAVLINK_MSG_ID_BOOT : ( '>I', MAVLink_boot_message, [0], 39 ), - MAVLINK_MSG_ID_SYSTEM_TIME : ( '>Q', MAVLink_system_time_message, [0], 190 ), - MAVLINK_MSG_ID_PING : ( '>IBBQ', MAVLink_ping_message, [0, 1, 2, 3], 92 ), - MAVLINK_MSG_ID_SYSTEM_TIME_UTC : ( '>II', MAVLink_system_time_utc_message, [0, 1], 191 ), - MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL : ( '>BBB25s', MAVLink_change_operator_control_message, [0, 1, 2, 3], 217 ), - MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK : ( '>BBB', MAVLink_change_operator_control_ack_message, [0, 1, 2], 104 ), - MAVLINK_MSG_ID_AUTH_KEY : ( '>32s', MAVLink_auth_key_message, [0], 119 ), - MAVLINK_MSG_ID_ACTION_ACK : ( '>BB', MAVLink_action_ack_message, [0, 1], 219 ), - MAVLINK_MSG_ID_ACTION : ( '>BBB', MAVLink_action_message, [0, 1, 2], 60 ), - MAVLINK_MSG_ID_SET_MODE : ( '>BB', MAVLink_set_mode_message, [0, 1], 186 ), - MAVLINK_MSG_ID_SET_NAV_MODE : ( '>BB', MAVLink_set_nav_mode_message, [0, 1], 10 ), - MAVLINK_MSG_ID_PARAM_REQUEST_READ : ( '>BB15sh', MAVLink_param_request_read_message, [0, 1, 2, 3], 89 ), - MAVLINK_MSG_ID_PARAM_REQUEST_LIST : ( '>BB', MAVLink_param_request_list_message, [0, 1], 159 ), - MAVLINK_MSG_ID_PARAM_VALUE : ( '>15sfHH', MAVLink_param_value_message, [0, 1, 2, 3], 162 ), - MAVLINK_MSG_ID_PARAM_SET : ( '>BB15sf', MAVLink_param_set_message, [0, 1, 2, 3], 121 ), - MAVLINK_MSG_ID_GPS_RAW_INT : ( '>QBiiiffff', MAVLink_gps_raw_int_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 149 ), - MAVLINK_MSG_ID_SCALED_IMU : ( '>Qhhhhhhhhh', MAVLink_scaled_imu_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9], 222 ), - MAVLINK_MSG_ID_GPS_STATUS : ( '>B20s20s20s20s20s', MAVLink_gps_status_message, [0, 1, 2, 3, 4, 5], 110 ), - MAVLINK_MSG_ID_RAW_IMU : ( '>Qhhhhhhhhh', MAVLink_raw_imu_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9], 179 ), - MAVLINK_MSG_ID_RAW_PRESSURE : ( '>Qhhhh', MAVLink_raw_pressure_message, [0, 1, 2, 3, 4], 136 ), - MAVLINK_MSG_ID_SCALED_PRESSURE : ( '>Qffh', MAVLink_scaled_pressure_message, [0, 1, 2, 3], 229 ), - MAVLINK_MSG_ID_ATTITUDE : ( '>Qffffff', MAVLink_attitude_message, [0, 1, 2, 3, 4, 5, 6], 66 ), - MAVLINK_MSG_ID_LOCAL_POSITION : ( '>Qffffff', MAVLink_local_position_message, [0, 1, 2, 3, 4, 5, 6], 126 ), - MAVLINK_MSG_ID_GLOBAL_POSITION : ( '>Qffffff', MAVLink_global_position_message, [0, 1, 2, 3, 4, 5, 6], 147 ), - MAVLINK_MSG_ID_GPS_RAW : ( '>QBfffffff', MAVLink_gps_raw_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 185 ), - MAVLINK_MSG_ID_SYS_STATUS : ( '>BBBHHHH', MAVLink_sys_status_message, [0, 1, 2, 3, 4, 5, 6], 112 ), - MAVLINK_MSG_ID_RC_CHANNELS_RAW : ( '>HHHHHHHHB', MAVLink_rc_channels_raw_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 252 ), - MAVLINK_MSG_ID_RC_CHANNELS_SCALED : ( '>hhhhhhhhB', MAVLink_rc_channels_scaled_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 162 ), - MAVLINK_MSG_ID_SERVO_OUTPUT_RAW : ( '>HHHHHHHH', MAVLink_servo_output_raw_message, [0, 1, 2, 3, 4, 5, 6, 7], 215 ), - MAVLINK_MSG_ID_WAYPOINT : ( '>BBHBBBBfffffff', MAVLink_waypoint_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13], 128 ), - MAVLINK_MSG_ID_WAYPOINT_REQUEST : ( '>BBH', MAVLink_waypoint_request_message, [0, 1, 2], 9 ), - MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT : ( '>BBH', MAVLink_waypoint_set_current_message, [0, 1, 2], 106 ), - MAVLINK_MSG_ID_WAYPOINT_CURRENT : ( '>H', MAVLink_waypoint_current_message, [0], 101 ), - MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST : ( '>BB', MAVLink_waypoint_request_list_message, [0, 1], 213 ), - MAVLINK_MSG_ID_WAYPOINT_COUNT : ( '>BBH', MAVLink_waypoint_count_message, [0, 1, 2], 4 ), - MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL : ( '>BB', MAVLink_waypoint_clear_all_message, [0, 1], 229 ), - MAVLINK_MSG_ID_WAYPOINT_REACHED : ( '>H', MAVLink_waypoint_reached_message, [0], 21 ), - MAVLINK_MSG_ID_WAYPOINT_ACK : ( '>BBB', MAVLink_waypoint_ack_message, [0, 1, 2], 214 ), - MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN : ( '>BBiii', MAVLink_gps_set_global_origin_message, [0, 1, 2, 3, 4], 215 ), - MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET : ( '>iii', MAVLink_gps_local_origin_set_message, [0, 1, 2], 14 ), - MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET : ( '>BBffff', MAVLink_local_position_setpoint_set_message, [0, 1, 2, 3, 4, 5], 206 ), - MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT : ( '>ffff', MAVLink_local_position_setpoint_message, [0, 1, 2, 3], 50 ), - MAVLINK_MSG_ID_CONTROL_STATUS : ( '>BBBBBBBB', MAVLink_control_status_message, [0, 1, 2, 3, 4, 5, 6, 7], 157 ), - MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA : ( '>BBBffffff', MAVLink_safety_set_allowed_area_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 126 ), - MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA : ( '>Bffffff', MAVLink_safety_allowed_area_message, [0, 1, 2, 3, 4, 5, 6], 108 ), - MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST : ( '>BBffff', MAVLink_set_roll_pitch_yaw_thrust_message, [0, 1, 2, 3, 4, 5], 213 ), - MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST : ( '>BBffff', MAVLink_set_roll_pitch_yaw_speed_thrust_message, [0, 1, 2, 3, 4, 5], 95 ), - MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT : ( '>Qffff', MAVLink_roll_pitch_yaw_thrust_setpoint_message, [0, 1, 2, 3, 4], 5 ), - MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT : ( '>Qffff', MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message, [0, 1, 2, 3, 4], 127 ), - MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT : ( '>ffhhHfff', MAVLink_nav_controller_output_message, [0, 1, 2, 3, 4, 5, 6, 7], 57 ), - MAVLINK_MSG_ID_POSITION_TARGET : ( '>ffff', MAVLink_position_target_message, [0, 1, 2, 3], 126 ), - MAVLINK_MSG_ID_STATE_CORRECTION : ( '>fffffffff', MAVLink_state_correction_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 130 ), - MAVLINK_MSG_ID_SET_ALTITUDE : ( '>BI', MAVLink_set_altitude_message, [0, 1], 119 ), - MAVLINK_MSG_ID_REQUEST_DATA_STREAM : ( '>BBBHB', MAVLink_request_data_stream_message, [0, 1, 2, 3, 4], 193 ), - MAVLINK_MSG_ID_HIL_STATE : ( '>Qffffffiiihhhhhh', MAVLink_hil_state_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15], 191 ), - MAVLINK_MSG_ID_HIL_CONTROLS : ( '>QffffBB', MAVLink_hil_controls_message, [0, 1, 2, 3, 4, 5, 6], 236 ), - MAVLINK_MSG_ID_MANUAL_CONTROL : ( '>BffffBBBB', MAVLink_manual_control_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 158 ), - MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE : ( '>BBHHHHHHHH', MAVLink_rc_channels_override_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9], 143 ), - MAVLINK_MSG_ID_GLOBAL_POSITION_INT : ( '>iiihhh', MAVLink_global_position_int_message, [0, 1, 2, 3, 4, 5], 104 ), - MAVLINK_MSG_ID_VFR_HUD : ( '>ffhHff', MAVLink_vfr_hud_message, [0, 1, 2, 3, 4, 5], 123 ), - MAVLINK_MSG_ID_COMMAND : ( '>BBBBffff', MAVLink_command_message, [0, 1, 2, 3, 4, 5, 6, 7], 131 ), - MAVLINK_MSG_ID_COMMAND_ACK : ( '>ff', MAVLink_command_ack_message, [0, 1], 8 ), - MAVLINK_MSG_ID_OPTICAL_FLOW : ( '>QBhhBf', MAVLink_optical_flow_message, [0, 1, 2, 3, 4, 5], 174 ), - MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT : ( '>IHB20sBff', MAVLink_object_detection_event_message, [0, 1, 2, 3, 4, 5, 6], 155 ), - MAVLINK_MSG_ID_DEBUG_VECT : ( '>10sQfff', MAVLink_debug_vect_message, [0, 1, 2, 3, 4], 178 ), - MAVLINK_MSG_ID_NAMED_VALUE_FLOAT : ( '>10sf', MAVLink_named_value_float_message, [0, 1], 224 ), - MAVLINK_MSG_ID_NAMED_VALUE_INT : ( '>10si', MAVLink_named_value_int_message, [0, 1], 60 ), - MAVLINK_MSG_ID_STATUSTEXT : ( '>B50s', MAVLink_statustext_message, [0, 1], 106 ), - MAVLINK_MSG_ID_DEBUG : ( '>Bf', MAVLink_debug_message, [0, 1], 7 ), -} - -class MAVError(Exception): - '''MAVLink error class''' - def __init__(self, msg): - Exception.__init__(self, msg) - self.message = msg - -class MAVString(str): - '''NUL terminated string''' - def __init__(self, s): - str.__init__(self) - def __str__(self): - i = self.find(chr(0)) - if i == -1: - return self[:] - return self[0:i] - -class MAVLink_bad_data(MAVLink_message): - ''' - a piece of bad data in a mavlink stream - ''' - def __init__(self, data, reason): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_BAD_DATA, 'BAD_DATA') - self._fieldnames = ['data', 'reason'] - self.data = data - self.reason = reason - self._msgbuf = data - -class MAVLink(object): - '''MAVLink protocol handling class''' - def __init__(self, file, srcSystem=0, srcComponent=0): - self.seq = 0 - self.file = file - self.srcSystem = srcSystem - self.srcComponent = srcComponent - self.callback = None - self.callback_args = None - self.callback_kwargs = None - self.buf = array.array('B') - self.expected_length = 6 - self.have_prefix_error = False - self.robust_parsing = False - self.protocol_marker = 85 - self.little_endian = False - self.crc_extra = False - self.sort_fields = False - self.total_packets_sent = 0 - self.total_bytes_sent = 0 - self.total_packets_received = 0 - self.total_bytes_received = 0 - self.total_receive_errors = 0 - self.startup_time = time.time() - - def set_callback(self, callback, *args, **kwargs): - self.callback = callback - self.callback_args = args - self.callback_kwargs = kwargs - - def send(self, mavmsg): - '''send a MAVLink message''' - buf = mavmsg.pack(self) - self.file.write(buf) - self.seq = (self.seq + 1) % 255 - self.total_packets_sent += 1 - self.total_bytes_sent += len(buf) - - def bytes_needed(self): - '''return number of bytes needed for next parsing stage''' - ret = self.expected_length - len(self.buf) - if ret <= 0: - return 1 - return ret - - def parse_char(self, c): - '''input some data bytes, possibly returning a new message''' - if isinstance(c, str): - self.buf.fromstring(c) - else: - self.buf.extend(c) - self.total_bytes_received += len(c) - if len(self.buf) >= 1 and self.buf[0] != 85: - magic = self.buf[0] - self.buf = self.buf[1:] - if self.robust_parsing: - m = MAVLink_bad_data(chr(magic), "Bad prefix") - if self.callback: - self.callback(m, *self.callback_args, **self.callback_kwargs) - self.expected_length = 6 - self.total_receive_errors += 1 - return m - if self.have_prefix_error: - return None - self.have_prefix_error = True - self.total_receive_errors += 1 - raise MAVError("invalid MAVLink prefix '%s'" % magic) - self.have_prefix_error = False - if len(self.buf) >= 2: - (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) - self.expected_length += 8 - if self.expected_length >= 8 and len(self.buf) >= self.expected_length: - mbuf = self.buf[0:self.expected_length] - self.buf = self.buf[self.expected_length:] - self.expected_length = 6 - if self.robust_parsing: - try: - m = self.decode(mbuf) - self.total_packets_received += 1 - except MAVError as reason: - m = MAVLink_bad_data(mbuf, reason.message) - self.total_receive_errors += 1 - else: - m = self.decode(mbuf) - self.total_packets_received += 1 - if self.callback: - self.callback(m, *self.callback_args, **self.callback_kwargs) - return m - return None - - def parse_buffer(self, s): - '''input some data bytes, possibly returning a list of new messages''' - m = self.parse_char(s) - if m is None: - return None - ret = [m] - while True: - m = self.parse_char("") - if m is None: - return ret - ret.append(m) - return ret - - def decode(self, msgbuf): - '''decode a buffer as a MAVLink message''' - # decode the header - try: - magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) - except struct.error as emsg: - raise MAVError('Unable to unpack MAVLink header: %s' % emsg) - if ord(magic) != 85: - raise MAVError("invalid MAVLink prefix '%s'" % magic) - if mlen != len(msgbuf)-8: - raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) - - if not msgId in mavlink_map: - raise MAVError('unknown MAVLink message ID %u' % msgId) - - # decode the payload - (fmt, type, order_map, crc_extra) = mavlink_map[msgId] - - # decode the checksum - try: - crc, = struct.unpack(' MAV. - Also used to return a point from MAV -> GCS - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - idx : point index (first point is 1, 0 is for return point) (uint8_t) - count : total number of points (for sanity checking) (uint8_t) - lat : Latitude of point (float) - lng : Longitude of point (float) - - ''' - msg = MAVLink_fence_point_message(target_system, target_component, idx, count, lat, lng) - msg.pack(self) - return msg - - def fence_point_send(self, target_system, target_component, idx, count, lat, lng): - ''' - A fence point. Used to set a point when from GCS -> MAV. - Also used to return a point from MAV -> GCS - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - idx : point index (first point is 1, 0 is for return point) (uint8_t) - count : total number of points (for sanity checking) (uint8_t) - lat : Latitude of point (float) - lng : Longitude of point (float) - - ''' - return self.send(self.fence_point_encode(target_system, target_component, idx, count, lat, lng)) - - def fence_fetch_point_encode(self, target_system, target_component, idx): - ''' - Request a current fence point from MAV - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - idx : point index (first point is 1, 0 is for return point) (uint8_t) - - ''' - msg = MAVLink_fence_fetch_point_message(target_system, target_component, idx) - msg.pack(self) - return msg - - def fence_fetch_point_send(self, target_system, target_component, idx): - ''' - Request a current fence point from MAV - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - idx : point index (first point is 1, 0 is for return point) (uint8_t) - - ''' - return self.send(self.fence_fetch_point_encode(target_system, target_component, idx)) - - def fence_status_encode(self, breach_status, breach_count, breach_type, breach_time): - ''' - Status of geo-fencing. Sent in extended status stream when - fencing enabled - - breach_status : 0 if currently inside fence, 1 if outside (uint8_t) - breach_count : number of fence breaches (uint16_t) - breach_type : last breach type (see FENCE_BREACH_* enum) (uint8_t) - breach_time : time of last breach in milliseconds since boot (uint32_t) - - ''' - msg = MAVLink_fence_status_message(breach_status, breach_count, breach_type, breach_time) - msg.pack(self) - return msg - - def fence_status_send(self, breach_status, breach_count, breach_type, breach_time): - ''' - Status of geo-fencing. Sent in extended status stream when - fencing enabled - - breach_status : 0 if currently inside fence, 1 if outside (uint8_t) - breach_count : number of fence breaches (uint16_t) - breach_type : last breach type (see FENCE_BREACH_* enum) (uint8_t) - breach_time : time of last breach in milliseconds since boot (uint32_t) - - ''' - return self.send(self.fence_status_encode(breach_status, breach_count, breach_type, breach_time)) - - def heartbeat_encode(self, type, autopilot, mavlink_version=2): - ''' - The heartbeat message shows that a system is present and responding. - The type of the MAV and Autopilot hardware allow the - receiving system to treat further messages from this - system appropriate (e.g. by laying out the user - interface based on the autopilot). - - type : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t) - autopilot : Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM (uint8_t) - mavlink_version : MAVLink version (uint8_t) - - ''' - msg = MAVLink_heartbeat_message(type, autopilot, mavlink_version) - msg.pack(self) - return msg - - def heartbeat_send(self, type, autopilot, mavlink_version=2): - ''' - The heartbeat message shows that a system is present and responding. - The type of the MAV and Autopilot hardware allow the - receiving system to treat further messages from this - system appropriate (e.g. by laying out the user - interface based on the autopilot). - - type : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t) - autopilot : Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM (uint8_t) - mavlink_version : MAVLink version (uint8_t) - - ''' - return self.send(self.heartbeat_encode(type, autopilot, mavlink_version)) - - def boot_encode(self, version): - ''' - The boot message indicates that a system is starting. The onboard - software version allows to keep track of onboard - soft/firmware revisions. - - version : The onboard software version (uint32_t) - - ''' - msg = MAVLink_boot_message(version) - msg.pack(self) - return msg - - def boot_send(self, version): - ''' - The boot message indicates that a system is starting. The onboard - software version allows to keep track of onboard - soft/firmware revisions. - - version : The onboard software version (uint32_t) - - ''' - return self.send(self.boot_encode(version)) - - def system_time_encode(self, time_usec): - ''' - The system time is the time of the master clock, typically the - computer clock of the main onboard computer. - - time_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t) - - ''' - msg = MAVLink_system_time_message(time_usec) - msg.pack(self) - return msg - - def system_time_send(self, time_usec): - ''' - The system time is the time of the master clock, typically the - computer clock of the main onboard computer. - - time_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t) - - ''' - return self.send(self.system_time_encode(time_usec)) - - def ping_encode(self, seq, target_system, target_component, time): - ''' - A ping message either requesting or responding to a ping. This allows - to measure the system latencies, including serial - port, radio modem and UDP connections. - - seq : PING sequence (uint32_t) - target_system : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) - target_component : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) - time : Unix timestamp in microseconds (uint64_t) - - ''' - msg = MAVLink_ping_message(seq, target_system, target_component, time) - msg.pack(self) - return msg - - def ping_send(self, seq, target_system, target_component, time): - ''' - A ping message either requesting or responding to a ping. This allows - to measure the system latencies, including serial - port, radio modem and UDP connections. - - seq : PING sequence (uint32_t) - target_system : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) - target_component : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) - time : Unix timestamp in microseconds (uint64_t) - - ''' - return self.send(self.ping_encode(seq, target_system, target_component, time)) - - def system_time_utc_encode(self, utc_date, utc_time): - ''' - UTC date and time from GPS module - - utc_date : GPS UTC date ddmmyy (uint32_t) - utc_time : GPS UTC time hhmmss (uint32_t) - - ''' - msg = MAVLink_system_time_utc_message(utc_date, utc_time) - msg.pack(self) - return msg - - def system_time_utc_send(self, utc_date, utc_time): - ''' - UTC date and time from GPS module - - utc_date : GPS UTC date ddmmyy (uint32_t) - utc_time : GPS UTC time hhmmss (uint32_t) - - ''' - return self.send(self.system_time_utc_encode(utc_date, utc_time)) - - def change_operator_control_encode(self, target_system, control_request, version, passkey): - ''' - Request to control this MAV - - target_system : System the GCS requests control for (uint8_t) - control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) - version : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t) - passkey : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char) - - ''' - msg = MAVLink_change_operator_control_message(target_system, control_request, version, passkey) - msg.pack(self) - return msg - - def change_operator_control_send(self, target_system, control_request, version, passkey): - ''' - Request to control this MAV - - target_system : System the GCS requests control for (uint8_t) - control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) - version : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t) - passkey : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char) - - ''' - return self.send(self.change_operator_control_encode(target_system, control_request, version, passkey)) - - def change_operator_control_ack_encode(self, gcs_system_id, control_request, ack): - ''' - Accept / deny control of this MAV - - gcs_system_id : ID of the GCS this message (uint8_t) - control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) - ack : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t) - - ''' - msg = MAVLink_change_operator_control_ack_message(gcs_system_id, control_request, ack) - msg.pack(self) - return msg - - def change_operator_control_ack_send(self, gcs_system_id, control_request, ack): - ''' - Accept / deny control of this MAV - - gcs_system_id : ID of the GCS this message (uint8_t) - control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) - ack : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t) - - ''' - return self.send(self.change_operator_control_ack_encode(gcs_system_id, control_request, ack)) - - def auth_key_encode(self, key): - ''' - Emit an encrypted signature / key identifying this system. PLEASE - NOTE: This protocol has been kept simple, so - transmitting the key requires an encrypted channel for - true safety. - - key : key (char) - - ''' - msg = MAVLink_auth_key_message(key) - msg.pack(self) - return msg - - def auth_key_send(self, key): - ''' - Emit an encrypted signature / key identifying this system. PLEASE - NOTE: This protocol has been kept simple, so - transmitting the key requires an encrypted channel for - true safety. - - key : key (char) - - ''' - return self.send(self.auth_key_encode(key)) - - def action_ack_encode(self, action, result): - ''' - This message acknowledges an action. IMPORTANT: The acknowledgement - can be also negative, e.g. the MAV rejects a reset - message because it is in-flight. The action ids are - defined in ENUM MAV_ACTION in - mavlink/include/mavlink_types.h - - action : The action id (uint8_t) - result : 0: Action DENIED, 1: Action executed (uint8_t) - - ''' - msg = MAVLink_action_ack_message(action, result) - msg.pack(self) - return msg - - def action_ack_send(self, action, result): - ''' - This message acknowledges an action. IMPORTANT: The acknowledgement - can be also negative, e.g. the MAV rejects a reset - message because it is in-flight. The action ids are - defined in ENUM MAV_ACTION in - mavlink/include/mavlink_types.h - - action : The action id (uint8_t) - result : 0: Action DENIED, 1: Action executed (uint8_t) - - ''' - return self.send(self.action_ack_encode(action, result)) - - def action_encode(self, target, target_component, action): - ''' - An action message allows to execute a certain onboard action. These - include liftoff, land, storing parameters too EEPROM, - shutddown, etc. The action ids are defined in ENUM - MAV_ACTION in mavlink/include/mavlink_types.h - - target : The system executing the action (uint8_t) - target_component : The component executing the action (uint8_t) - action : The action id (uint8_t) - - ''' - msg = MAVLink_action_message(target, target_component, action) - msg.pack(self) - return msg - - def action_send(self, target, target_component, action): - ''' - An action message allows to execute a certain onboard action. These - include liftoff, land, storing parameters too EEPROM, - shutddown, etc. The action ids are defined in ENUM - MAV_ACTION in mavlink/include/mavlink_types.h - - target : The system executing the action (uint8_t) - target_component : The component executing the action (uint8_t) - action : The action id (uint8_t) - - ''' - return self.send(self.action_encode(target, target_component, action)) - - def set_mode_encode(self, target, mode): - ''' - Set the system mode, as defined by enum MAV_MODE in - mavlink/include/mavlink_types.h. There is no target - component id as the mode is by definition for the - overall aircraft, not only for one component. - - target : The system setting the mode (uint8_t) - mode : The new mode (uint8_t) - - ''' - msg = MAVLink_set_mode_message(target, mode) - msg.pack(self) - return msg - - def set_mode_send(self, target, mode): - ''' - Set the system mode, as defined by enum MAV_MODE in - mavlink/include/mavlink_types.h. There is no target - component id as the mode is by definition for the - overall aircraft, not only for one component. - - target : The system setting the mode (uint8_t) - mode : The new mode (uint8_t) - - ''' - return self.send(self.set_mode_encode(target, mode)) - - def set_nav_mode_encode(self, target, nav_mode): - ''' - Set the system navigation mode, as defined by enum MAV_NAV_MODE in - mavlink/include/mavlink_types.h. The navigation mode - applies to the whole aircraft and thus all components. - - target : The system setting the mode (uint8_t) - nav_mode : The new navigation mode (uint8_t) - - ''' - msg = MAVLink_set_nav_mode_message(target, nav_mode) - msg.pack(self) - return msg - - def set_nav_mode_send(self, target, nav_mode): - ''' - Set the system navigation mode, as defined by enum MAV_NAV_MODE in - mavlink/include/mavlink_types.h. The navigation mode - applies to the whole aircraft and thus all components. - - target : The system setting the mode (uint8_t) - nav_mode : The new navigation mode (uint8_t) - - ''' - return self.send(self.set_nav_mode_encode(target, nav_mode)) - - def param_request_read_encode(self, target_system, target_component, param_id, param_index): - ''' - Request to read the onboard parameter with the param_id string id. - Onboard parameters are stored as key[const char*] -> - value[float]. This allows to send a parameter to any - other component (such as the GCS) without the need of - previous knowledge of possible parameter names. Thus - the same GCS can store different parameters for - different autopilots. See also - http://qgroundcontrol.org/parameter_interface for a - full documentation of QGroundControl and IMU code. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - param_id : Onboard parameter id (int8_t) - param_index : Parameter index. Send -1 to use the param ID field as identifier (int16_t) - - ''' - msg = MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) - msg.pack(self) - return msg - - def param_request_read_send(self, target_system, target_component, param_id, param_index): - ''' - Request to read the onboard parameter with the param_id string id. - Onboard parameters are stored as key[const char*] -> - value[float]. This allows to send a parameter to any - other component (such as the GCS) without the need of - previous knowledge of possible parameter names. Thus - the same GCS can store different parameters for - different autopilots. See also - http://qgroundcontrol.org/parameter_interface for a - full documentation of QGroundControl and IMU code. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - param_id : Onboard parameter id (int8_t) - param_index : Parameter index. Send -1 to use the param ID field as identifier (int16_t) - - ''' - return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) - - def param_request_list_encode(self, target_system, target_component): - ''' - Request all parameters of this component. After his request, all - parameters are emitted. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - msg = MAVLink_param_request_list_message(target_system, target_component) - msg.pack(self) - return msg - - def param_request_list_send(self, target_system, target_component): - ''' - Request all parameters of this component. After his request, all - parameters are emitted. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - return self.send(self.param_request_list_encode(target_system, target_component)) - - def param_value_encode(self, param_id, param_value, param_count, param_index): - ''' - Emit the value of a onboard parameter. The inclusion of param_count - and param_index in the message allows the recipient to - keep track of received parameters and allows him to - re-request missing parameters after a loss or timeout. - - param_id : Onboard parameter id (int8_t) - param_value : Onboard parameter value (float) - param_count : Total number of onboard parameters (uint16_t) - param_index : Index of this onboard parameter (uint16_t) - - ''' - msg = MAVLink_param_value_message(param_id, param_value, param_count, param_index) - msg.pack(self) - return msg - - def param_value_send(self, param_id, param_value, param_count, param_index): - ''' - Emit the value of a onboard parameter. The inclusion of param_count - and param_index in the message allows the recipient to - keep track of received parameters and allows him to - re-request missing parameters after a loss or timeout. - - param_id : Onboard parameter id (int8_t) - param_value : Onboard parameter value (float) - param_count : Total number of onboard parameters (uint16_t) - param_index : Index of this onboard parameter (uint16_t) - - ''' - return self.send(self.param_value_encode(param_id, param_value, param_count, param_index)) - - def param_set_encode(self, target_system, target_component, param_id, param_value): - ''' - Set a parameter value TEMPORARILY to RAM. It will be reset to default - on system reboot. Send the ACTION - MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM - contents to EEPROM. IMPORTANT: The receiving component - should acknowledge the new parameter value by sending - a param_value message to all communication partners. - This will also ensure that multiple GCS all have an - up-to-date list of all parameters. If the sending GCS - did not receive a PARAM_VALUE message within its - timeout time, it should re-send the PARAM_SET message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - param_id : Onboard parameter id (int8_t) - param_value : Onboard parameter value (float) - - ''' - msg = MAVLink_param_set_message(target_system, target_component, param_id, param_value) - msg.pack(self) - return msg - - def param_set_send(self, target_system, target_component, param_id, param_value): - ''' - Set a parameter value TEMPORARILY to RAM. It will be reset to default - on system reboot. Send the ACTION - MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM - contents to EEPROM. IMPORTANT: The receiving component - should acknowledge the new parameter value by sending - a param_value message to all communication partners. - This will also ensure that multiple GCS all have an - up-to-date list of all parameters. If the sending GCS - did not receive a PARAM_VALUE message within its - timeout time, it should re-send the PARAM_SET message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - param_id : Onboard parameter id (int8_t) - param_value : Onboard parameter value (float) - - ''' - return self.send(self.param_set_encode(target_system, target_component, param_id, param_value)) - - def gps_raw_int_encode(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): - ''' - The global position, as returned by the Global Positioning System - (GPS). This is NOT the global position estimate of the - sytem, but rather a RAW sensor value. See message - GLOBAL_POSITION for the global position estimate. - Coordinate frame is right-handed, Z-axis up (GPS - frame) - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) - lat : Latitude in 1E7 degrees (int32_t) - lon : Longitude in 1E7 degrees (int32_t) - alt : Altitude in 1E3 meters (millimeters) (int32_t) - eph : GPS HDOP (float) - epv : GPS VDOP (float) - v : GPS ground speed (m/s) (float) - hdg : Compass heading in degrees, 0..360 degrees (float) - - ''' - msg = MAVLink_gps_raw_int_message(usec, fix_type, lat, lon, alt, eph, epv, v, hdg) - msg.pack(self) - return msg - - def gps_raw_int_send(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): - ''' - The global position, as returned by the Global Positioning System - (GPS). This is NOT the global position estimate of the - sytem, but rather a RAW sensor value. See message - GLOBAL_POSITION for the global position estimate. - Coordinate frame is right-handed, Z-axis up (GPS - frame) - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) - lat : Latitude in 1E7 degrees (int32_t) - lon : Longitude in 1E7 degrees (int32_t) - alt : Altitude in 1E3 meters (millimeters) (int32_t) - eph : GPS HDOP (float) - epv : GPS VDOP (float) - v : GPS ground speed (m/s) (float) - hdg : Compass heading in degrees, 0..360 degrees (float) - - ''' - return self.send(self.gps_raw_int_encode(usec, fix_type, lat, lon, alt, eph, epv, v, hdg)) - - def scaled_imu_encode(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This message - should contain the scaled values to the described - units - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - xacc : X acceleration (mg) (int16_t) - yacc : Y acceleration (mg) (int16_t) - zacc : Z acceleration (mg) (int16_t) - xgyro : Angular speed around X axis (millirad /sec) (int16_t) - ygyro : Angular speed around Y axis (millirad /sec) (int16_t) - zgyro : Angular speed around Z axis (millirad /sec) (int16_t) - xmag : X Magnetic field (milli tesla) (int16_t) - ymag : Y Magnetic field (milli tesla) (int16_t) - zmag : Z Magnetic field (milli tesla) (int16_t) - - ''' - msg = MAVLink_scaled_imu_message(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) - msg.pack(self) - return msg - - def scaled_imu_send(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This message - should contain the scaled values to the described - units - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - xacc : X acceleration (mg) (int16_t) - yacc : Y acceleration (mg) (int16_t) - zacc : Z acceleration (mg) (int16_t) - xgyro : Angular speed around X axis (millirad /sec) (int16_t) - ygyro : Angular speed around Y axis (millirad /sec) (int16_t) - zgyro : Angular speed around Z axis (millirad /sec) (int16_t) - xmag : X Magnetic field (milli tesla) (int16_t) - ymag : Y Magnetic field (milli tesla) (int16_t) - zmag : Z Magnetic field (milli tesla) (int16_t) - - ''' - return self.send(self.scaled_imu_encode(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) - - def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): - ''' - The positioning status, as reported by GPS. This message is intended - to display status information about each satellite - visible to the receiver. See message GLOBAL_POSITION - for the global position estimate. This message can - contain information for up to 20 satellites. - - satellites_visible : Number of satellites visible (uint8_t) - satellite_prn : Global satellite ID (int8_t) - satellite_used : 0: Satellite not used, 1: used for localization (int8_t) - satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (int8_t) - satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (int8_t) - satellite_snr : Signal to noise ratio of satellite (int8_t) - - ''' - msg = MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) - msg.pack(self) - return msg - - def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): - ''' - The positioning status, as reported by GPS. This message is intended - to display status information about each satellite - visible to the receiver. See message GLOBAL_POSITION - for the global position estimate. This message can - contain information for up to 20 satellites. - - satellites_visible : Number of satellites visible (uint8_t) - satellite_prn : Global satellite ID (int8_t) - satellite_used : 0: Satellite not used, 1: used for localization (int8_t) - satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (int8_t) - satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (int8_t) - satellite_snr : Signal to noise ratio of satellite (int8_t) - - ''' - return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) - - def raw_imu_encode(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This message - should always contain the true raw values without any - scaling to allow data capture and system debugging. - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - xacc : X acceleration (raw) (int16_t) - yacc : Y acceleration (raw) (int16_t) - zacc : Z acceleration (raw) (int16_t) - xgyro : Angular speed around X axis (raw) (int16_t) - ygyro : Angular speed around Y axis (raw) (int16_t) - zgyro : Angular speed around Z axis (raw) (int16_t) - xmag : X Magnetic field (raw) (int16_t) - ymag : Y Magnetic field (raw) (int16_t) - zmag : Z Magnetic field (raw) (int16_t) - - ''' - msg = MAVLink_raw_imu_message(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) - msg.pack(self) - return msg - - def raw_imu_send(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This message - should always contain the true raw values without any - scaling to allow data capture and system debugging. - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - xacc : X acceleration (raw) (int16_t) - yacc : Y acceleration (raw) (int16_t) - zacc : Z acceleration (raw) (int16_t) - xgyro : Angular speed around X axis (raw) (int16_t) - ygyro : Angular speed around Y axis (raw) (int16_t) - zgyro : Angular speed around Z axis (raw) (int16_t) - xmag : X Magnetic field (raw) (int16_t) - ymag : Y Magnetic field (raw) (int16_t) - zmag : Z Magnetic field (raw) (int16_t) - - ''' - return self.send(self.raw_imu_encode(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) - - def raw_pressure_encode(self, usec, press_abs, press_diff1, press_diff2, temperature): - ''' - The RAW pressure readings for the typical setup of one absolute - pressure and one differential pressure sensor. The - sensor values should be the raw, UNSCALED ADC values. - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - press_abs : Absolute pressure (raw) (int16_t) - press_diff1 : Differential pressure 1 (raw) (int16_t) - press_diff2 : Differential pressure 2 (raw) (int16_t) - temperature : Raw Temperature measurement (raw) (int16_t) - - ''' - msg = MAVLink_raw_pressure_message(usec, press_abs, press_diff1, press_diff2, temperature) - msg.pack(self) - return msg - - def raw_pressure_send(self, usec, press_abs, press_diff1, press_diff2, temperature): - ''' - The RAW pressure readings for the typical setup of one absolute - pressure and one differential pressure sensor. The - sensor values should be the raw, UNSCALED ADC values. - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - press_abs : Absolute pressure (raw) (int16_t) - press_diff1 : Differential pressure 1 (raw) (int16_t) - press_diff2 : Differential pressure 2 (raw) (int16_t) - temperature : Raw Temperature measurement (raw) (int16_t) - - ''' - return self.send(self.raw_pressure_encode(usec, press_abs, press_diff1, press_diff2, temperature)) - - def scaled_pressure_encode(self, usec, press_abs, press_diff, temperature): - ''' - The pressure readings for the typical setup of one absolute and - differential pressure sensor. The units are as - specified in each field. - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - press_abs : Absolute pressure (hectopascal) (float) - press_diff : Differential pressure 1 (hectopascal) (float) - temperature : Temperature measurement (0.01 degrees celsius) (int16_t) - - ''' - msg = MAVLink_scaled_pressure_message(usec, press_abs, press_diff, temperature) - msg.pack(self) - return msg - - def scaled_pressure_send(self, usec, press_abs, press_diff, temperature): - ''' - The pressure readings for the typical setup of one absolute and - differential pressure sensor. The units are as - specified in each field. - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - press_abs : Absolute pressure (hectopascal) (float) - press_diff : Differential pressure 1 (hectopascal) (float) - temperature : Temperature measurement (0.01 degrees celsius) (int16_t) - - ''' - return self.send(self.scaled_pressure_encode(usec, press_abs, press_diff, temperature)) - - def attitude_encode(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): - ''' - The attitude in the aeronautical frame (right-handed, Z-down, X-front, - Y-right). - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - - ''' - msg = MAVLink_attitude_message(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) - msg.pack(self) - return msg - - def attitude_send(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): - ''' - The attitude in the aeronautical frame (right-handed, Z-down, X-front, - Y-right). - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - - ''' - return self.send(self.attitude_encode(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) - - def local_position_encode(self, usec, x, y, z, vx, vy, vz): - ''' - The filtered local position (e.g. fused computer vision and - accelerometers). Coordinate frame is right-handed, - Z-axis down (aeronautical frame) - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - x : X Position (float) - y : Y Position (float) - z : Z Position (float) - vx : X Speed (float) - vy : Y Speed (float) - vz : Z Speed (float) - - ''' - msg = MAVLink_local_position_message(usec, x, y, z, vx, vy, vz) - msg.pack(self) - return msg - - def local_position_send(self, usec, x, y, z, vx, vy, vz): - ''' - The filtered local position (e.g. fused computer vision and - accelerometers). Coordinate frame is right-handed, - Z-axis down (aeronautical frame) - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - x : X Position (float) - y : Y Position (float) - z : Z Position (float) - vx : X Speed (float) - vy : Y Speed (float) - vz : Z Speed (float) - - ''' - return self.send(self.local_position_encode(usec, x, y, z, vx, vy, vz)) - - def global_position_encode(self, usec, lat, lon, alt, vx, vy, vz): - ''' - The filtered global position (e.g. fused GPS and accelerometers). - Coordinate frame is right-handed, Z-axis up (GPS - frame) - - usec : Timestamp (microseconds since unix epoch) (uint64_t) - lat : Latitude, in degrees (float) - lon : Longitude, in degrees (float) - alt : Absolute altitude, in meters (float) - vx : X Speed (in Latitude direction, positive: going north) (float) - vy : Y Speed (in Longitude direction, positive: going east) (float) - vz : Z Speed (in Altitude direction, positive: going up) (float) - - ''' - msg = MAVLink_global_position_message(usec, lat, lon, alt, vx, vy, vz) - msg.pack(self) - return msg - - def global_position_send(self, usec, lat, lon, alt, vx, vy, vz): - ''' - The filtered global position (e.g. fused GPS and accelerometers). - Coordinate frame is right-handed, Z-axis up (GPS - frame) - - usec : Timestamp (microseconds since unix epoch) (uint64_t) - lat : Latitude, in degrees (float) - lon : Longitude, in degrees (float) - alt : Absolute altitude, in meters (float) - vx : X Speed (in Latitude direction, positive: going north) (float) - vy : Y Speed (in Longitude direction, positive: going east) (float) - vz : Z Speed (in Altitude direction, positive: going up) (float) - - ''' - return self.send(self.global_position_encode(usec, lat, lon, alt, vx, vy, vz)) - - def gps_raw_encode(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): - ''' - The global position, as returned by the Global Positioning System - (GPS). This is NOT the global position estimate of the - sytem, but rather a RAW sensor value. See message - GLOBAL_POSITION for the global position estimate. - Coordinate frame is right-handed, Z-axis up (GPS - frame) - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) - lat : Latitude in degrees (float) - lon : Longitude in degrees (float) - alt : Altitude in meters (float) - eph : GPS HDOP (float) - epv : GPS VDOP (float) - v : GPS ground speed (float) - hdg : Compass heading in degrees, 0..360 degrees (float) - - ''' - msg = MAVLink_gps_raw_message(usec, fix_type, lat, lon, alt, eph, epv, v, hdg) - msg.pack(self) - return msg - - def gps_raw_send(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): - ''' - The global position, as returned by the Global Positioning System - (GPS). This is NOT the global position estimate of the - sytem, but rather a RAW sensor value. See message - GLOBAL_POSITION for the global position estimate. - Coordinate frame is right-handed, Z-axis up (GPS - frame) - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) - lat : Latitude in degrees (float) - lon : Longitude in degrees (float) - alt : Altitude in meters (float) - eph : GPS HDOP (float) - epv : GPS VDOP (float) - v : GPS ground speed (float) - hdg : Compass heading in degrees, 0..360 degrees (float) - - ''' - return self.send(self.gps_raw_encode(usec, fix_type, lat, lon, alt, eph, epv, v, hdg)) - - def sys_status_encode(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop): - ''' - The general system state. If the system is following the MAVLink - standard, the system state is mainly defined by three - orthogonal states/modes: The system mode, which is - either LOCKED (motors shut down and locked), MANUAL - (system under RC control), GUIDED (system with - autonomous position control, position setpoint - controlled manually) or AUTO (system guided by - path/waypoint planner). The NAV_MODE defined the - current flight state: LIFTOFF (often an open-loop - maneuver), LANDING, WAYPOINTS or VECTOR. This - represents the internal navigation state machine. The - system status shows wether the system is currently - active or not and if an emergency occured. During the - CRITICAL and EMERGENCY states the MAV is still - considered to be active, but should start emergency - procedures autonomously. After a failure occured it - should first move from active to critical to allow - manual intervention and then move to emergency after a - certain timeout. - - mode : System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h (uint8_t) - nav_mode : Navigation mode, see MAV_NAV_MODE ENUM (uint8_t) - status : System status flag, see MAV_STATUS ENUM (uint8_t) - load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) - vbat : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) - battery_remaining : Remaining battery energy: (0%: 0, 100%: 1000) (uint16_t) - packet_drop : Dropped packets (packets that were corrupted on reception on the MAV) (uint16_t) - - ''' - msg = MAVLink_sys_status_message(mode, nav_mode, status, load, vbat, battery_remaining, packet_drop) - msg.pack(self) - return msg - - def sys_status_send(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop): - ''' - The general system state. If the system is following the MAVLink - standard, the system state is mainly defined by three - orthogonal states/modes: The system mode, which is - either LOCKED (motors shut down and locked), MANUAL - (system under RC control), GUIDED (system with - autonomous position control, position setpoint - controlled manually) or AUTO (system guided by - path/waypoint planner). The NAV_MODE defined the - current flight state: LIFTOFF (often an open-loop - maneuver), LANDING, WAYPOINTS or VECTOR. This - represents the internal navigation state machine. The - system status shows wether the system is currently - active or not and if an emergency occured. During the - CRITICAL and EMERGENCY states the MAV is still - considered to be active, but should start emergency - procedures autonomously. After a failure occured it - should first move from active to critical to allow - manual intervention and then move to emergency after a - certain timeout. - - mode : System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h (uint8_t) - nav_mode : Navigation mode, see MAV_NAV_MODE ENUM (uint8_t) - status : System status flag, see MAV_STATUS ENUM (uint8_t) - load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) - vbat : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) - battery_remaining : Remaining battery energy: (0%: 0, 100%: 1000) (uint16_t) - packet_drop : Dropped packets (packets that were corrupted on reception on the MAV) (uint16_t) - - ''' - return self.send(self.sys_status_encode(mode, nav_mode, status, load, vbat, battery_remaining, packet_drop)) - - def rc_channels_raw_encode(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): - ''' - The RAW values of the RC channels received. The standard PPM - modulation is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. Individual receivers/transmitters - might violate this specification. - - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - msg = MAVLink_rc_channels_raw_message(chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) - msg.pack(self) - return msg - - def rc_channels_raw_send(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): - ''' - The RAW values of the RC channels received. The standard PPM - modulation is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. Individual receivers/transmitters - might violate this specification. - - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - return self.send(self.rc_channels_raw_encode(chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) - - def rc_channels_scaled_encode(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): - ''' - The scaled values of the RC channels received. (-100%) -10000, (0%) 0, - (100%) 10000 - - chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - msg = MAVLink_rc_channels_scaled_message(chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) - msg.pack(self) - return msg - - def rc_channels_scaled_send(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): - ''' - The scaled values of the RC channels received. (-100%) -10000, (0%) 0, - (100%) 10000 - - chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - return self.send(self.rc_channels_scaled_encode(chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) - - def servo_output_raw_encode(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): - ''' - The RAW values of the servo outputs (for RC input from the remote, use - the RC_CHANNELS messages). The standard PPM modulation - is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. - - servo1_raw : Servo output 1 value, in microseconds (uint16_t) - servo2_raw : Servo output 2 value, in microseconds (uint16_t) - servo3_raw : Servo output 3 value, in microseconds (uint16_t) - servo4_raw : Servo output 4 value, in microseconds (uint16_t) - servo5_raw : Servo output 5 value, in microseconds (uint16_t) - servo6_raw : Servo output 6 value, in microseconds (uint16_t) - servo7_raw : Servo output 7 value, in microseconds (uint16_t) - servo8_raw : Servo output 8 value, in microseconds (uint16_t) - - ''' - msg = MAVLink_servo_output_raw_message(servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) - msg.pack(self) - return msg - - def servo_output_raw_send(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): - ''' - The RAW values of the servo outputs (for RC input from the remote, use - the RC_CHANNELS messages). The standard PPM modulation - is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. - - servo1_raw : Servo output 1 value, in microseconds (uint16_t) - servo2_raw : Servo output 2 value, in microseconds (uint16_t) - servo3_raw : Servo output 3 value, in microseconds (uint16_t) - servo4_raw : Servo output 4 value, in microseconds (uint16_t) - servo5_raw : Servo output 5 value, in microseconds (uint16_t) - servo6_raw : Servo output 6 value, in microseconds (uint16_t) - servo7_raw : Servo output 7 value, in microseconds (uint16_t) - servo8_raw : Servo output 8 value, in microseconds (uint16_t) - - ''' - return self.send(self.servo_output_raw_encode(servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) - - def waypoint_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): - ''' - Message encoding a waypoint. This message is emitted to announce - the presence of a waypoint and to set a waypoint on - the system. The waypoint can be either in x, y, z - meters (type: LOCAL) or x:lat, y:lon, z:altitude. - Local frame is Z-down, right handed, global frame is - Z-up, right handed - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - frame : The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h (uint8_t) - command : The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs (uint8_t) - current : false:0, true:1 (uint8_t) - autocontinue : autocontinue to next wp (uint8_t) - param1 : PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters (float) - param2 : PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float) - param3 : PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float) - param4 : PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH (float) - x : PARAM5 / local: x position, global: latitude (float) - y : PARAM6 / y position: global: longitude (float) - z : PARAM7 / z position: global: altitude (float) - - ''' - msg = MAVLink_waypoint_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) - msg.pack(self) - return msg - - def waypoint_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): - ''' - Message encoding a waypoint. This message is emitted to announce - the presence of a waypoint and to set a waypoint on - the system. The waypoint can be either in x, y, z - meters (type: LOCAL) or x:lat, y:lon, z:altitude. - Local frame is Z-down, right handed, global frame is - Z-up, right handed - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - frame : The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h (uint8_t) - command : The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs (uint8_t) - current : false:0, true:1 (uint8_t) - autocontinue : autocontinue to next wp (uint8_t) - param1 : PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters (float) - param2 : PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float) - param3 : PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float) - param4 : PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH (float) - x : PARAM5 / local: x position, global: latitude (float) - y : PARAM6 / y position: global: longitude (float) - z : PARAM7 / z position: global: altitude (float) - - ''' - return self.send(self.waypoint_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) - - def waypoint_request_encode(self, target_system, target_component, seq): - ''' - Request the information of the waypoint with the sequence number seq. - The response of the system to this message should be a - WAYPOINT message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - - ''' - msg = MAVLink_waypoint_request_message(target_system, target_component, seq) - msg.pack(self) - return msg - - def waypoint_request_send(self, target_system, target_component, seq): - ''' - Request the information of the waypoint with the sequence number seq. - The response of the system to this message should be a - WAYPOINT message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - - ''' - return self.send(self.waypoint_request_encode(target_system, target_component, seq)) - - def waypoint_set_current_encode(self, target_system, target_component, seq): - ''' - Set the waypoint with sequence number seq as current waypoint. This - means that the MAV will continue to this waypoint on - the shortest path (not following the waypoints in- - between). - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - - ''' - msg = MAVLink_waypoint_set_current_message(target_system, target_component, seq) - msg.pack(self) - return msg - - def waypoint_set_current_send(self, target_system, target_component, seq): - ''' - Set the waypoint with sequence number seq as current waypoint. This - means that the MAV will continue to this waypoint on - the shortest path (not following the waypoints in- - between). - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - - ''' - return self.send(self.waypoint_set_current_encode(target_system, target_component, seq)) - - def waypoint_current_encode(self, seq): - ''' - Message that announces the sequence number of the current active - waypoint. The MAV will fly towards this waypoint. - - seq : Sequence (uint16_t) - - ''' - msg = MAVLink_waypoint_current_message(seq) - msg.pack(self) - return msg - - def waypoint_current_send(self, seq): - ''' - Message that announces the sequence number of the current active - waypoint. The MAV will fly towards this waypoint. - - seq : Sequence (uint16_t) - - ''' - return self.send(self.waypoint_current_encode(seq)) - - def waypoint_request_list_encode(self, target_system, target_component): - ''' - Request the overall list of waypoints from the system/component. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - msg = MAVLink_waypoint_request_list_message(target_system, target_component) - msg.pack(self) - return msg - - def waypoint_request_list_send(self, target_system, target_component): - ''' - Request the overall list of waypoints from the system/component. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - return self.send(self.waypoint_request_list_encode(target_system, target_component)) - - def waypoint_count_encode(self, target_system, target_component, count): - ''' - This message is emitted as response to WAYPOINT_REQUEST_LIST by the - MAV. The GCS can then request the individual waypoints - based on the knowledge of the total number of - waypoints. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - count : Number of Waypoints in the Sequence (uint16_t) - - ''' - msg = MAVLink_waypoint_count_message(target_system, target_component, count) - msg.pack(self) - return msg - - def waypoint_count_send(self, target_system, target_component, count): - ''' - This message is emitted as response to WAYPOINT_REQUEST_LIST by the - MAV. The GCS can then request the individual waypoints - based on the knowledge of the total number of - waypoints. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - count : Number of Waypoints in the Sequence (uint16_t) - - ''' - return self.send(self.waypoint_count_encode(target_system, target_component, count)) - - def waypoint_clear_all_encode(self, target_system, target_component): - ''' - Delete all waypoints at once. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - msg = MAVLink_waypoint_clear_all_message(target_system, target_component) - msg.pack(self) - return msg - - def waypoint_clear_all_send(self, target_system, target_component): - ''' - Delete all waypoints at once. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - return self.send(self.waypoint_clear_all_encode(target_system, target_component)) - - def waypoint_reached_encode(self, seq): - ''' - A certain waypoint has been reached. The system will either hold this - position (or circle on the orbit) or (if the - autocontinue on the WP was set) continue to the next - waypoint. - - seq : Sequence (uint16_t) - - ''' - msg = MAVLink_waypoint_reached_message(seq) - msg.pack(self) - return msg - - def waypoint_reached_send(self, seq): - ''' - A certain waypoint has been reached. The system will either hold this - position (or circle on the orbit) or (if the - autocontinue on the WP was set) continue to the next - waypoint. - - seq : Sequence (uint16_t) - - ''' - return self.send(self.waypoint_reached_encode(seq)) - - def waypoint_ack_encode(self, target_system, target_component, type): - ''' - Ack message during waypoint handling. The type field states if this - message is a positive ack (type=0) or if an error - happened (type=non-zero). - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - type : 0: OK, 1: Error (uint8_t) - - ''' - msg = MAVLink_waypoint_ack_message(target_system, target_component, type) - msg.pack(self) - return msg - - def waypoint_ack_send(self, target_system, target_component, type): - ''' - Ack message during waypoint handling. The type field states if this - message is a positive ack (type=0) or if an error - happened (type=non-zero). - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - type : 0: OK, 1: Error (uint8_t) - - ''' - return self.send(self.waypoint_ack_encode(target_system, target_component, type)) - - def gps_set_global_origin_encode(self, target_system, target_component, latitude, longitude, altitude): - ''' - As local waypoints exist, the global waypoint reference allows to - transform between the local coordinate frame and the - global (GPS) coordinate frame. This can be necessary - when e.g. in- and outdoor settings are connected and - the MAV should move from in- to outdoor. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - latitude : global position * 1E7 (int32_t) - longitude : global position * 1E7 (int32_t) - altitude : global position * 1000 (int32_t) - - ''' - msg = MAVLink_gps_set_global_origin_message(target_system, target_component, latitude, longitude, altitude) - msg.pack(self) - return msg - - def gps_set_global_origin_send(self, target_system, target_component, latitude, longitude, altitude): - ''' - As local waypoints exist, the global waypoint reference allows to - transform between the local coordinate frame and the - global (GPS) coordinate frame. This can be necessary - when e.g. in- and outdoor settings are connected and - the MAV should move from in- to outdoor. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - latitude : global position * 1E7 (int32_t) - longitude : global position * 1E7 (int32_t) - altitude : global position * 1000 (int32_t) - - ''' - return self.send(self.gps_set_global_origin_encode(target_system, target_component, latitude, longitude, altitude)) - - def gps_local_origin_set_encode(self, latitude, longitude, altitude): - ''' - Once the MAV sets a new GPS-Local correspondence, this message - announces the origin (0,0,0) position - - latitude : Latitude (WGS84), expressed as * 1E7 (int32_t) - longitude : Longitude (WGS84), expressed as * 1E7 (int32_t) - altitude : Altitude(WGS84), expressed as * 1000 (int32_t) - - ''' - msg = MAVLink_gps_local_origin_set_message(latitude, longitude, altitude) - msg.pack(self) - return msg - - def gps_local_origin_set_send(self, latitude, longitude, altitude): - ''' - Once the MAV sets a new GPS-Local correspondence, this message - announces the origin (0,0,0) position - - latitude : Latitude (WGS84), expressed as * 1E7 (int32_t) - longitude : Longitude (WGS84), expressed as * 1E7 (int32_t) - altitude : Altitude(WGS84), expressed as * 1000 (int32_t) - - ''' - return self.send(self.gps_local_origin_set_encode(latitude, longitude, altitude)) - - def local_position_setpoint_set_encode(self, target_system, target_component, x, y, z, yaw): - ''' - Set the setpoint for a local position controller. This is the position - in local coordinates the MAV should fly to. This - message is sent by the path/waypoint planner to the - onboard position controller. As some MAVs have a - degree of freedom in yaw (e.g. all - helicopters/quadrotors), the desired yaw angle is part - of the message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - x : x position (float) - y : y position (float) - z : z position (float) - yaw : Desired yaw angle (float) - - ''' - msg = MAVLink_local_position_setpoint_set_message(target_system, target_component, x, y, z, yaw) - msg.pack(self) - return msg - - def local_position_setpoint_set_send(self, target_system, target_component, x, y, z, yaw): - ''' - Set the setpoint for a local position controller. This is the position - in local coordinates the MAV should fly to. This - message is sent by the path/waypoint planner to the - onboard position controller. As some MAVs have a - degree of freedom in yaw (e.g. all - helicopters/quadrotors), the desired yaw angle is part - of the message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - x : x position (float) - y : y position (float) - z : z position (float) - yaw : Desired yaw angle (float) - - ''' - return self.send(self.local_position_setpoint_set_encode(target_system, target_component, x, y, z, yaw)) - - def local_position_setpoint_encode(self, x, y, z, yaw): - ''' - Transmit the current local setpoint of the controller to other MAVs - (collision avoidance) and to the GCS. - - x : x position (float) - y : y position (float) - z : z position (float) - yaw : Desired yaw angle (float) - - ''' - msg = MAVLink_local_position_setpoint_message(x, y, z, yaw) - msg.pack(self) - return msg - - def local_position_setpoint_send(self, x, y, z, yaw): - ''' - Transmit the current local setpoint of the controller to other MAVs - (collision avoidance) and to the GCS. - - x : x position (float) - y : y position (float) - z : z position (float) - yaw : Desired yaw angle (float) - - ''' - return self.send(self.local_position_setpoint_encode(x, y, z, yaw)) - - def control_status_encode(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw): - ''' - - - position_fix : Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix (uint8_t) - vision_fix : Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix (uint8_t) - gps_fix : GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix (uint8_t) - ahrs_health : Attitude estimation health: 0: poor, 255: excellent (uint8_t) - control_att : 0: Attitude control disabled, 1: enabled (uint8_t) - control_pos_xy : 0: X, Y position control disabled, 1: enabled (uint8_t) - control_pos_z : 0: Z position control disabled, 1: enabled (uint8_t) - control_pos_yaw : 0: Yaw angle control disabled, 1: enabled (uint8_t) - - ''' - msg = MAVLink_control_status_message(position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw) - msg.pack(self) - return msg - - def control_status_send(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw): - ''' - - - position_fix : Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix (uint8_t) - vision_fix : Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix (uint8_t) - gps_fix : GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix (uint8_t) - ahrs_health : Attitude estimation health: 0: poor, 255: excellent (uint8_t) - control_att : 0: Attitude control disabled, 1: enabled (uint8_t) - control_pos_xy : 0: X, Y position control disabled, 1: enabled (uint8_t) - control_pos_z : 0: Z position control disabled, 1: enabled (uint8_t) - control_pos_yaw : 0: Yaw angle control disabled, 1: enabled (uint8_t) - - ''' - return self.send(self.control_status_encode(position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw)) - - def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): - ''' - Set a safety zone (volume), which is defined by two corners of a cube. - This message can be used to tell the MAV which - setpoints/waypoints to accept and which to reject. - Safety areas are often enforced by national or - competition regulations. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) - p1x : x position 1 / Latitude 1 (float) - p1y : y position 1 / Longitude 1 (float) - p1z : z position 1 / Altitude 1 (float) - p2x : x position 2 / Latitude 2 (float) - p2y : y position 2 / Longitude 2 (float) - p2z : z position 2 / Altitude 2 (float) - - ''' - msg = MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) - msg.pack(self) - return msg - - def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): - ''' - Set a safety zone (volume), which is defined by two corners of a cube. - This message can be used to tell the MAV which - setpoints/waypoints to accept and which to reject. - Safety areas are often enforced by national or - competition regulations. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) - p1x : x position 1 / Latitude 1 (float) - p1y : y position 1 / Longitude 1 (float) - p1z : z position 1 / Altitude 1 (float) - p2x : x position 2 / Latitude 2 (float) - p2y : y position 2 / Longitude 2 (float) - p2z : z position 2 / Altitude 2 (float) - - ''' - return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) - - def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): - ''' - Read out the safety zone the MAV currently assumes. - - frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) - p1x : x position 1 / Latitude 1 (float) - p1y : y position 1 / Longitude 1 (float) - p1z : z position 1 / Altitude 1 (float) - p2x : x position 2 / Latitude 2 (float) - p2y : y position 2 / Longitude 2 (float) - p2z : z position 2 / Altitude 2 (float) - - ''' - msg = MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) - msg.pack(self) - return msg - - def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): - ''' - Read out the safety zone the MAV currently assumes. - - frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) - p1x : x position 1 / Latitude 1 (float) - p1y : y position 1 / Longitude 1 (float) - p1z : z position 1 / Altitude 1 (float) - p2x : x position 2 / Latitude 2 (float) - p2y : y position 2 / Longitude 2 (float) - p2z : z position 2 / Altitude 2 (float) - - ''' - return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) - - def set_roll_pitch_yaw_thrust_encode(self, target_system, target_component, roll, pitch, yaw, thrust): - ''' - Set roll, pitch and yaw. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - roll : Desired roll angle in radians (float) - pitch : Desired pitch angle in radians (float) - yaw : Desired yaw angle in radians (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - msg = MAVLink_set_roll_pitch_yaw_thrust_message(target_system, target_component, roll, pitch, yaw, thrust) - msg.pack(self) - return msg - - def set_roll_pitch_yaw_thrust_send(self, target_system, target_component, roll, pitch, yaw, thrust): - ''' - Set roll, pitch and yaw. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - roll : Desired roll angle in radians (float) - pitch : Desired pitch angle in radians (float) - yaw : Desired yaw angle in radians (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - return self.send(self.set_roll_pitch_yaw_thrust_encode(target_system, target_component, roll, pitch, yaw, thrust)) - - def set_roll_pitch_yaw_speed_thrust_encode(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): - ''' - Set roll, pitch and yaw. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - roll_speed : Desired roll angular speed in rad/s (float) - pitch_speed : Desired pitch angular speed in rad/s (float) - yaw_speed : Desired yaw angular speed in rad/s (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - msg = MAVLink_set_roll_pitch_yaw_speed_thrust_message(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust) - msg.pack(self) - return msg - - def set_roll_pitch_yaw_speed_thrust_send(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): - ''' - Set roll, pitch and yaw. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - roll_speed : Desired roll angular speed in rad/s (float) - pitch_speed : Desired pitch angular speed in rad/s (float) - yaw_speed : Desired yaw angular speed in rad/s (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - return self.send(self.set_roll_pitch_yaw_speed_thrust_encode(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust)) - - def roll_pitch_yaw_thrust_setpoint_encode(self, time_us, roll, pitch, yaw, thrust): - ''' - Setpoint in roll, pitch, yaw currently active on the system. - - time_us : Timestamp in micro seconds since unix epoch (uint64_t) - roll : Desired roll angle in radians (float) - pitch : Desired pitch angle in radians (float) - yaw : Desired yaw angle in radians (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - msg = MAVLink_roll_pitch_yaw_thrust_setpoint_message(time_us, roll, pitch, yaw, thrust) - msg.pack(self) - return msg - - def roll_pitch_yaw_thrust_setpoint_send(self, time_us, roll, pitch, yaw, thrust): - ''' - Setpoint in roll, pitch, yaw currently active on the system. - - time_us : Timestamp in micro seconds since unix epoch (uint64_t) - roll : Desired roll angle in radians (float) - pitch : Desired pitch angle in radians (float) - yaw : Desired yaw angle in radians (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - return self.send(self.roll_pitch_yaw_thrust_setpoint_encode(time_us, roll, pitch, yaw, thrust)) - - def roll_pitch_yaw_speed_thrust_setpoint_encode(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust): - ''' - Setpoint in rollspeed, pitchspeed, yawspeed currently active on the - system. - - time_us : Timestamp in micro seconds since unix epoch (uint64_t) - roll_speed : Desired roll angular speed in rad/s (float) - pitch_speed : Desired pitch angular speed in rad/s (float) - yaw_speed : Desired yaw angular speed in rad/s (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - msg = MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(time_us, roll_speed, pitch_speed, yaw_speed, thrust) - msg.pack(self) - return msg - - def roll_pitch_yaw_speed_thrust_setpoint_send(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust): - ''' - Setpoint in rollspeed, pitchspeed, yawspeed currently active on the - system. - - time_us : Timestamp in micro seconds since unix epoch (uint64_t) - roll_speed : Desired roll angular speed in rad/s (float) - pitch_speed : Desired pitch angular speed in rad/s (float) - yaw_speed : Desired yaw angular speed in rad/s (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - return self.send(self.roll_pitch_yaw_speed_thrust_setpoint_encode(time_us, roll_speed, pitch_speed, yaw_speed, thrust)) - - def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): - ''' - Outputs of the APM navigation controller. The primary use of this - message is to check the response and signs of the - controller before actual flight and to assist with - tuning controller parameters - - nav_roll : Current desired roll in degrees (float) - nav_pitch : Current desired pitch in degrees (float) - nav_bearing : Current desired heading in degrees (int16_t) - target_bearing : Bearing to current waypoint/target in degrees (int16_t) - wp_dist : Distance to active waypoint in meters (uint16_t) - alt_error : Current altitude error in meters (float) - aspd_error : Current airspeed error in meters/second (float) - xtrack_error : Current crosstrack error on x-y plane in meters (float) - - ''' - msg = MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) - msg.pack(self) - return msg - - def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): - ''' - Outputs of the APM navigation controller. The primary use of this - message is to check the response and signs of the - controller before actual flight and to assist with - tuning controller parameters - - nav_roll : Current desired roll in degrees (float) - nav_pitch : Current desired pitch in degrees (float) - nav_bearing : Current desired heading in degrees (int16_t) - target_bearing : Bearing to current waypoint/target in degrees (int16_t) - wp_dist : Distance to active waypoint in meters (uint16_t) - alt_error : Current altitude error in meters (float) - aspd_error : Current airspeed error in meters/second (float) - xtrack_error : Current crosstrack error on x-y plane in meters (float) - - ''' - return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) - - def position_target_encode(self, x, y, z, yaw): - ''' - The goal position of the system. This position is the input to any - navigation or path planning algorithm and does NOT - represent the current controller setpoint. - - x : x position (float) - y : y position (float) - z : z position (float) - yaw : yaw orientation in radians, 0 = NORTH (float) - - ''' - msg = MAVLink_position_target_message(x, y, z, yaw) - msg.pack(self) - return msg - - def position_target_send(self, x, y, z, yaw): - ''' - The goal position of the system. This position is the input to any - navigation or path planning algorithm and does NOT - represent the current controller setpoint. - - x : x position (float) - y : y position (float) - z : z position (float) - yaw : yaw orientation in radians, 0 = NORTH (float) - - ''' - return self.send(self.position_target_encode(x, y, z, yaw)) - - def state_correction_encode(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): - ''' - Corrects the systems state by adding an error correction term to the - position and velocity, and by rotating the attitude by - a correction angle. - - xErr : x position error (float) - yErr : y position error (float) - zErr : z position error (float) - rollErr : roll error (radians) (float) - pitchErr : pitch error (radians) (float) - yawErr : yaw error (radians) (float) - vxErr : x velocity (float) - vyErr : y velocity (float) - vzErr : z velocity (float) - - ''' - msg = MAVLink_state_correction_message(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr) - msg.pack(self) - return msg - - def state_correction_send(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): - ''' - Corrects the systems state by adding an error correction term to the - position and velocity, and by rotating the attitude by - a correction angle. - - xErr : x position error (float) - yErr : y position error (float) - zErr : z position error (float) - rollErr : roll error (radians) (float) - pitchErr : pitch error (radians) (float) - yawErr : yaw error (radians) (float) - vxErr : x velocity (float) - vyErr : y velocity (float) - vzErr : z velocity (float) - - ''' - return self.send(self.state_correction_encode(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr)) - - def set_altitude_encode(self, target, mode): - ''' - - - target : The system setting the altitude (uint8_t) - mode : The new altitude in meters (uint32_t) - - ''' - msg = MAVLink_set_altitude_message(target, mode) - msg.pack(self) - return msg - - def set_altitude_send(self, target, mode): - ''' - - - target : The system setting the altitude (uint8_t) - mode : The new altitude in meters (uint32_t) - - ''' - return self.send(self.set_altitude_encode(target, mode)) - - def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): - ''' - - - target_system : The target requested to send the message stream. (uint8_t) - target_component : The target requested to send the message stream. (uint8_t) - req_stream_id : The ID of the requested message type (uint8_t) - req_message_rate : Update rate in Hertz (uint16_t) - start_stop : 1 to start sending, 0 to stop sending. (uint8_t) - - ''' - msg = MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) - msg.pack(self) - return msg - - def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): - ''' - - - target_system : The target requested to send the message stream. (uint8_t) - target_component : The target requested to send the message stream. (uint8_t) - req_stream_id : The ID of the requested message type (uint8_t) - req_message_rate : Update rate in Hertz (uint16_t) - start_stop : 1 to start sending, 0 to stop sending. (uint8_t) - - ''' - return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) - - def hil_state_encode(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): - ''' - This packet is useful for high throughput applications - such as hardware in the loop simulations. - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - lat : Latitude, expressed as * 1E7 (int32_t) - lon : Longitude, expressed as * 1E7 (int32_t) - alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) - vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) - vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) - vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) - xacc : X acceleration (mg) (int16_t) - yacc : Y acceleration (mg) (int16_t) - zacc : Z acceleration (mg) (int16_t) - - ''' - msg = MAVLink_hil_state_message(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) - msg.pack(self) - return msg - - def hil_state_send(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): - ''' - This packet is useful for high throughput applications - such as hardware in the loop simulations. - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - lat : Latitude, expressed as * 1E7 (int32_t) - lon : Longitude, expressed as * 1E7 (int32_t) - alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) - vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) - vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) - vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) - xacc : X acceleration (mg) (int16_t) - yacc : Y acceleration (mg) (int16_t) - zacc : Z acceleration (mg) (int16_t) - - ''' - return self.send(self.hil_state_encode(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) - - def hil_controls_encode(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode): - ''' - Hardware in the loop control outputs - - time_us : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll_ailerons : Control output -3 .. 1 (float) - pitch_elevator : Control output -1 .. 1 (float) - yaw_rudder : Control output -1 .. 1 (float) - throttle : Throttle 0 .. 1 (float) - mode : System mode (MAV_MODE) (uint8_t) - nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) - - ''' - msg = MAVLink_hil_controls_message(time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode) - msg.pack(self) - return msg - - def hil_controls_send(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode): - ''' - Hardware in the loop control outputs - - time_us : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll_ailerons : Control output -3 .. 1 (float) - pitch_elevator : Control output -1 .. 1 (float) - yaw_rudder : Control output -1 .. 1 (float) - throttle : Throttle 0 .. 1 (float) - mode : System mode (MAV_MODE) (uint8_t) - nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) - - ''' - return self.send(self.hil_controls_encode(time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode)) - - def manual_control_encode(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): - ''' - - - target : The system to be controlled (uint8_t) - roll : roll (float) - pitch : pitch (float) - yaw : yaw (float) - thrust : thrust (float) - roll_manual : roll control enabled auto:0, manual:1 (uint8_t) - pitch_manual : pitch auto:0, manual:1 (uint8_t) - yaw_manual : yaw auto:0, manual:1 (uint8_t) - thrust_manual : thrust auto:0, manual:1 (uint8_t) - - ''' - msg = MAVLink_manual_control_message(target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual) - msg.pack(self) - return msg - - def manual_control_send(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): - ''' - - - target : The system to be controlled (uint8_t) - roll : roll (float) - pitch : pitch (float) - yaw : yaw (float) - thrust : thrust (float) - roll_manual : roll control enabled auto:0, manual:1 (uint8_t) - pitch_manual : pitch auto:0, manual:1 (uint8_t) - yaw_manual : yaw auto:0, manual:1 (uint8_t) - thrust_manual : thrust auto:0, manual:1 (uint8_t) - - ''' - return self.send(self.manual_control_encode(target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual)) - - def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): - ''' - The RAW values of the RC channels sent to the MAV to override info - received from the RC radio. A value of -1 means no - change to that channel. A value of 0 means control of - that channel should be released back to the RC radio. - The standard PPM modulation is as follows: 1000 - microseconds: 0%, 2000 microseconds: 100%. Individual - receivers/transmitters might violate this - specification. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - - ''' - msg = MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) - msg.pack(self) - return msg - - def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): - ''' - The RAW values of the RC channels sent to the MAV to override info - received from the RC radio. A value of -1 means no - change to that channel. A value of 0 means control of - that channel should be released back to the RC radio. - The standard PPM modulation is as follows: 1000 - microseconds: 0%, 2000 microseconds: 100%. Individual - receivers/transmitters might violate this - specification. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - - ''' - return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) - - def global_position_int_encode(self, lat, lon, alt, vx, vy, vz): - ''' - The filtered global position (e.g. fused GPS and accelerometers). The - position is in GPS-frame (right-handed, Z-up) - - lat : Latitude, expressed as * 1E7 (int32_t) - lon : Longitude, expressed as * 1E7 (int32_t) - alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) - vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) - vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) - vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) - - ''' - msg = MAVLink_global_position_int_message(lat, lon, alt, vx, vy, vz) - msg.pack(self) - return msg - - def global_position_int_send(self, lat, lon, alt, vx, vy, vz): - ''' - The filtered global position (e.g. fused GPS and accelerometers). The - position is in GPS-frame (right-handed, Z-up) - - lat : Latitude, expressed as * 1E7 (int32_t) - lon : Longitude, expressed as * 1E7 (int32_t) - alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) - vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) - vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) - vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) - - ''' - return self.send(self.global_position_int_encode(lat, lon, alt, vx, vy, vz)) - - def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): - ''' - Metrics typically displayed on a HUD for fixed wing aircraft - - airspeed : Current airspeed in m/s (float) - groundspeed : Current ground speed in m/s (float) - heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) - throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) - alt : Current altitude (MSL), in meters (float) - climb : Current climb rate in meters/second (float) - - ''' - msg = MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) - msg.pack(self) - return msg - - def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): - ''' - Metrics typically displayed on a HUD for fixed wing aircraft - - airspeed : Current airspeed in m/s (float) - groundspeed : Current ground speed in m/s (float) - heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) - throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) - alt : Current altitude (MSL), in meters (float) - climb : Current climb rate in meters/second (float) - - ''' - return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) - - def command_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4): - ''' - Send a command with up to four parameters to the MAV - - target_system : System which should execute the command (uint8_t) - target_component : Component which should execute the command, 0 for all components (uint8_t) - command : Command ID, as defined by MAV_CMD enum. (uint8_t) - confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) - param1 : Parameter 1, as defined by MAV_CMD enum. (float) - param2 : Parameter 2, as defined by MAV_CMD enum. (float) - param3 : Parameter 3, as defined by MAV_CMD enum. (float) - param4 : Parameter 4, as defined by MAV_CMD enum. (float) - - ''' - msg = MAVLink_command_message(target_system, target_component, command, confirmation, param1, param2, param3, param4) - msg.pack(self) - return msg - - def command_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4): - ''' - Send a command with up to four parameters to the MAV - - target_system : System which should execute the command (uint8_t) - target_component : Component which should execute the command, 0 for all components (uint8_t) - command : Command ID, as defined by MAV_CMD enum. (uint8_t) - confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) - param1 : Parameter 1, as defined by MAV_CMD enum. (float) - param2 : Parameter 2, as defined by MAV_CMD enum. (float) - param3 : Parameter 3, as defined by MAV_CMD enum. (float) - param4 : Parameter 4, as defined by MAV_CMD enum. (float) - - ''' - return self.send(self.command_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4)) - - def command_ack_encode(self, command, result): - ''' - Report status of a command. Includes feedback wether the command was - executed - - command : Current airspeed in m/s (float) - result : 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION (float) - - ''' - msg = MAVLink_command_ack_message(command, result) - msg.pack(self) - return msg - - def command_ack_send(self, command, result): - ''' - Report status of a command. Includes feedback wether the command was - executed - - command : Current airspeed in m/s (float) - result : 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION (float) - - ''' - return self.send(self.command_ack_encode(command, result)) - - def optical_flow_encode(self, time, sensor_id, flow_x, flow_y, quality, ground_distance): - ''' - Optical flow from a flow sensor (e.g. optical mouse sensor) - - time : Timestamp (UNIX) (uint64_t) - sensor_id : Sensor ID (uint8_t) - flow_x : Flow in pixels in x-sensor direction (int16_t) - flow_y : Flow in pixels in y-sensor direction (int16_t) - quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) - ground_distance : Ground distance in meters (float) - - ''' - msg = MAVLink_optical_flow_message(time, sensor_id, flow_x, flow_y, quality, ground_distance) - msg.pack(self) - return msg - - def optical_flow_send(self, time, sensor_id, flow_x, flow_y, quality, ground_distance): - ''' - Optical flow from a flow sensor (e.g. optical mouse sensor) - - time : Timestamp (UNIX) (uint64_t) - sensor_id : Sensor ID (uint8_t) - flow_x : Flow in pixels in x-sensor direction (int16_t) - flow_y : Flow in pixels in y-sensor direction (int16_t) - quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) - ground_distance : Ground distance in meters (float) - - ''' - return self.send(self.optical_flow_encode(time, sensor_id, flow_x, flow_y, quality, ground_distance)) - - def object_detection_event_encode(self, time, object_id, type, name, quality, bearing, distance): - ''' - Object has been detected - - time : Timestamp in milliseconds since system boot (uint32_t) - object_id : Object ID (uint16_t) - type : Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal (uint8_t) - name : Name of the object as defined by the detector (char) - quality : Detection quality / confidence. 0: bad, 255: maximum confidence (uint8_t) - bearing : Angle of the object with respect to the body frame in NED coordinates in radians. 0: front (float) - distance : Ground distance in meters (float) - - ''' - msg = MAVLink_object_detection_event_message(time, object_id, type, name, quality, bearing, distance) - msg.pack(self) - return msg - - def object_detection_event_send(self, time, object_id, type, name, quality, bearing, distance): - ''' - Object has been detected - - time : Timestamp in milliseconds since system boot (uint32_t) - object_id : Object ID (uint16_t) - type : Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal (uint8_t) - name : Name of the object as defined by the detector (char) - quality : Detection quality / confidence. 0: bad, 255: maximum confidence (uint8_t) - bearing : Angle of the object with respect to the body frame in NED coordinates in radians. 0: front (float) - distance : Ground distance in meters (float) - - ''' - return self.send(self.object_detection_event_encode(time, object_id, type, name, quality, bearing, distance)) - - def debug_vect_encode(self, name, usec, x, y, z): - ''' - - - name : Name (char) - usec : Timestamp (uint64_t) - x : x (float) - y : y (float) - z : z (float) - - ''' - msg = MAVLink_debug_vect_message(name, usec, x, y, z) - msg.pack(self) - return msg - - def debug_vect_send(self, name, usec, x, y, z): - ''' - - - name : Name (char) - usec : Timestamp (uint64_t) - x : x (float) - y : y (float) - z : z (float) - - ''' - return self.send(self.debug_vect_encode(name, usec, x, y, z)) - - def named_value_float_encode(self, name, value): - ''' - Send a key-value pair as float. The use of this message is discouraged - for normal packets, but a quite efficient way for - testing new messages and getting experimental debug - output. - - name : Name of the debug variable (char) - value : Floating point value (float) - - ''' - msg = MAVLink_named_value_float_message(name, value) - msg.pack(self) - return msg - - def named_value_float_send(self, name, value): - ''' - Send a key-value pair as float. The use of this message is discouraged - for normal packets, but a quite efficient way for - testing new messages and getting experimental debug - output. - - name : Name of the debug variable (char) - value : Floating point value (float) - - ''' - return self.send(self.named_value_float_encode(name, value)) - - def named_value_int_encode(self, name, value): - ''' - Send a key-value pair as integer. The use of this message is - discouraged for normal packets, but a quite efficient - way for testing new messages and getting experimental - debug output. - - name : Name of the debug variable (char) - value : Signed integer value (int32_t) - - ''' - msg = MAVLink_named_value_int_message(name, value) - msg.pack(self) - return msg - - def named_value_int_send(self, name, value): - ''' - Send a key-value pair as integer. The use of this message is - discouraged for normal packets, but a quite efficient - way for testing new messages and getting experimental - debug output. - - name : Name of the debug variable (char) - value : Signed integer value (int32_t) - - ''' - return self.send(self.named_value_int_encode(name, value)) - - def statustext_encode(self, severity, text): - ''' - Status text message. These messages are printed in yellow in the COMM - console of QGroundControl. WARNING: They consume quite - some bandwidth, so use only for important status and - error messages. If implemented wisely, these messages - are buffered on the MCU and sent only at a limited - rate (e.g. 10 Hz). - - severity : Severity of status, 0 = info message, 255 = critical fault (uint8_t) - text : Status text message, without null termination character (int8_t) - - ''' - msg = MAVLink_statustext_message(severity, text) - msg.pack(self) - return msg - - def statustext_send(self, severity, text): - ''' - Status text message. These messages are printed in yellow in the COMM - console of QGroundControl. WARNING: They consume quite - some bandwidth, so use only for important status and - error messages. If implemented wisely, these messages - are buffered on the MCU and sent only at a limited - rate (e.g. 10 Hz). - - severity : Severity of status, 0 = info message, 255 = critical fault (uint8_t) - text : Status text message, without null termination character (int8_t) - - ''' - return self.send(self.statustext_encode(severity, text)) - - def debug_encode(self, ind, value): - ''' - Send a debug value. The index is used to discriminate between values. - These values show up in the plot of QGroundControl as - DEBUG N. - - ind : index of debug variable (uint8_t) - value : DEBUG value (float) - - ''' - msg = MAVLink_debug_message(ind, value) - msg.pack(self) - return msg - - def debug_send(self, ind, value): - ''' - Send a debug value. The index is used to discriminate between values. - These values show up in the plot of QGroundControl as - DEBUG N. - - ind : index of debug variable (uint8_t) - value : DEBUG value (float) - - ''' - return self.send(self.debug_encode(ind, value)) - diff --git a/files/mavlink_generator/generator/mavlinkv10.py b/files/mavlink_generator/generator/mavlinkv10.py deleted file mode 100644 index 7037b7683208a370c640108de68444f7bee09975..0000000000000000000000000000000000000000 --- a/files/mavlink_generator/generator/mavlinkv10.py +++ /dev/null @@ -1,5130 +0,0 @@ -''' -MAVLink protocol implementation (auto-generated by mavgen.py) - -Generated from: ardupilotmega.xml,common.xml - -Note: this file has been auto-generated. DO NOT EDIT -''' - -import struct, array, mavutil, time - -WIRE_PROTOCOL_VERSION = "1.0" - -class MAVLink_header(object): - '''MAVLink message header''' - def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): - self.mlen = mlen - self.seq = seq - self.srcSystem = srcSystem - self.srcComponent = srcComponent - self.msgId = msgId - - def pack(self): - return struct.pack('BBBBBB', 254, self.mlen, self.seq, - self.srcSystem, self.srcComponent, self.msgId) - -class MAVLink_message(object): - '''base MAVLink message class''' - def __init__(self, msgId, name): - self._header = MAVLink_header(msgId) - self._payload = None - self._msgbuf = None - self._crc = None - self._fieldnames = [] - self._type = name - - def get_msgbuf(self): - return self._msgbuf - - def get_header(self): - return self._header - - def get_payload(self): - return self._payload - - def get_crc(self): - return self._crc - - def get_fieldnames(self): - return self._fieldnames - - def get_type(self): - return self._type - - def get_msgId(self): - return self._header.msgId - - def get_srcSystem(self): - return self._header.srcSystem - - def get_srcComponent(self): - return self._header.srcComponent - - def get_seq(self): - return self._header.seq - - def __str__(self): - ret = '%s {' % self._type - for a in self._fieldnames: - v = getattr(self, a) - ret += '%s : %s, ' % (a, v) - ret = ret[0:-2] + '}' - return ret - - def pack(self, mav, crc_extra, payload): - self._payload = payload - self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, - mav.srcSystem, mav.srcComponent) - self._msgbuf = self._header.pack() + payload - crc = mavutil.x25crc(self._msgbuf[1:]) - if True: # using CRC extra - crc.accumulate(chr(crc_extra)) - self._crc = crc.crc - self._msgbuf += struct.pack(' MAV. Also used to return a point from MAV -> GCS - ''' - def __init__(self, idx, count, lat, lng): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_FENCE_POINT, 'FENCE_POINT') - self._fieldnames = ['idx', 'count', 'lat', 'lng'] - self.idx = idx - self.count = count - self.lat = lat - self.lng = lng - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 18, struct.pack(' - value[float]. This allows to send a parameter to any other - component (such as the GCS) without the need of previous - knowledge of possible parameter names. Thus the same GCS can - store different parameters for different autopilots. See also - http://qgroundcontrol.org/parameter_interface for a full - documentation of QGroundControl and IMU code. - ''' - def __init__(self, target_system, target_component, param_id, param_index): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_REQUEST_READ, 'PARAM_REQUEST_READ') - self._fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] - self.target_system = target_system - self.target_component = target_component - self.param_id = param_id - self.param_index = param_index - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 214, struct.pack('= 1 and self.buf[0] != 254: - magic = self.buf[0] - self.buf = self.buf[1:] - if self.robust_parsing: - m = MAVLink_bad_data(chr(magic), "Bad prefix") - if self.callback: - self.callback(m, *self.callback_args, **self.callback_kwargs) - self.expected_length = 6 - self.total_receive_errors += 1 - return m - if self.have_prefix_error: - return None - self.have_prefix_error = True - self.total_receive_errors += 1 - raise MAVError("invalid MAVLink prefix '%s'" % magic) - self.have_prefix_error = False - if len(self.buf) >= 2: - (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) - self.expected_length += 8 - if self.expected_length >= 8 and len(self.buf) >= self.expected_length: - mbuf = self.buf[0:self.expected_length] - self.buf = self.buf[self.expected_length:] - self.expected_length = 6 - if self.robust_parsing: - try: - m = self.decode(mbuf) - self.total_packets_received += 1 - except MAVError as reason: - m = MAVLink_bad_data(mbuf, reason.message) - self.total_receive_errors += 1 - else: - m = self.decode(mbuf) - self.total_packets_received += 1 - if self.callback: - self.callback(m, *self.callback_args, **self.callback_kwargs) - return m - return None - - def parse_buffer(self, s): - '''input some data bytes, possibly returning a list of new messages''' - m = self.parse_char(s) - if m is None: - return None - ret = [m] - while True: - m = self.parse_char("") - if m is None: - return ret - ret.append(m) - return ret - - def decode(self, msgbuf): - '''decode a buffer as a MAVLink message''' - # decode the header - try: - magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) - except struct.error as emsg: - raise MAVError('Unable to unpack MAVLink header: %s' % emsg) - if ord(magic) != 254: - raise MAVError("invalid MAVLink prefix '%s'" % magic) - if mlen != len(msgbuf)-8: - raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) - - if not msgId in mavlink_map: - raise MAVError('unknown MAVLink message ID %u' % msgId) - - # decode the payload - (fmt, type, order_map, crc_extra) = mavlink_map[msgId] - - # decode the checksum - try: - crc, = struct.unpack(' MAV. - Also used to return a point from MAV -> GCS - - idx : point index (first point is 1, 0 is for return point) (uint8_t) - count : total number of points (for sanity checking) (uint8_t) - lat : Latitude of point (float) - lng : Longitude of point (float) - - ''' - msg = MAVLink_fence_point_message(idx, count, lat, lng) - msg.pack(self) - return msg - - def fence_point_send(self, idx, count, lat, lng): - ''' - A fence point. Used to set a point when from GCS -> MAV. - Also used to return a point from MAV -> GCS - - idx : point index (first point is 1, 0 is for return point) (uint8_t) - count : total number of points (for sanity checking) (uint8_t) - lat : Latitude of point (float) - lng : Longitude of point (float) - - ''' - return self.send(self.fence_point_encode(idx, count, lat, lng)) - - def fence_fetch_point_encode(self, idx): - ''' - Request a current fence point from MAV - - idx : point index (first point is 1, 0 is for return point) (uint8_t) - - ''' - msg = MAVLink_fence_fetch_point_message(idx) - msg.pack(self) - return msg - - def fence_fetch_point_send(self, idx): - ''' - Request a current fence point from MAV - - idx : point index (first point is 1, 0 is for return point) (uint8_t) - - ''' - return self.send(self.fence_fetch_point_encode(idx)) - - def heartbeat_encode(self, type, autopilot, base_mode, custom_mode, system_status, mavlink_version=3): - ''' - The heartbeat message shows that a system is present and responding. - The type of the MAV and Autopilot hardware allow the - receiving system to treat further messages from this - system appropriate (e.g. by laying out the user - interface based on the autopilot). - - type : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t) - autopilot : Autopilot type / class. defined in MAV_CLASS ENUM (uint8_t) - base_mode : System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h (uint8_t) - custom_mode : Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. (uint32_t) - system_status : System status flag, see MAV_STATUS ENUM (uint8_t) - mavlink_version : MAVLink version (uint8_t) - - ''' - msg = MAVLink_heartbeat_message(type, autopilot, base_mode, custom_mode, system_status, mavlink_version) - msg.pack(self) - return msg - - def heartbeat_send(self, type, autopilot, base_mode, custom_mode, system_status, mavlink_version=3): - ''' - The heartbeat message shows that a system is present and responding. - The type of the MAV and Autopilot hardware allow the - receiving system to treat further messages from this - system appropriate (e.g. by laying out the user - interface based on the autopilot). - - type : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t) - autopilot : Autopilot type / class. defined in MAV_CLASS ENUM (uint8_t) - base_mode : System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h (uint8_t) - custom_mode : Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. (uint32_t) - system_status : System status flag, see MAV_STATUS ENUM (uint8_t) - mavlink_version : MAVLink version (uint8_t) - - ''' - return self.send(self.heartbeat_encode(type, autopilot, base_mode, custom_mode, system_status, mavlink_version)) - - def sys_status_encode(self, onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4): - ''' - The general system state. If the system is following the MAVLink - standard, the system state is mainly defined by three - orthogonal states/modes: The system mode, which is - either LOCKED (motors shut down and locked), MANUAL - (system under RC control), GUIDED (system with - autonomous position control, position setpoint - controlled manually) or AUTO (system guided by - path/waypoint planner). The NAV_MODE defined the - current flight state: LIFTOFF (often an open-loop - maneuver), LANDING, WAYPOINTS or VECTOR. This - represents the internal navigation state machine. The - system status shows wether the system is currently - active or not and if an emergency occured. During the - CRITICAL and EMERGENCY states the MAV is still - considered to be active, but should start emergency - procedures autonomously. After a failure occured it - should first move from active to critical to allow - manual intervention and then move to emergency after a - certain timeout. - - onboard_control_sensors_present : Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control (uint32_t) - onboard_control_sensors_enabled : Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control (uint32_t) - onboard_control_sensors_health : Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control (uint32_t) - load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) - voltage_battery : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) - current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) - battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery (int8_t) - drop_rate_comm : Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t) - errors_comm : Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t) - errors_count1 : Autopilot-specific errors (uint16_t) - errors_count2 : Autopilot-specific errors (uint16_t) - errors_count3 : Autopilot-specific errors (uint16_t) - errors_count4 : Autopilot-specific errors (uint16_t) - - ''' - msg = MAVLink_sys_status_message(onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4) - msg.pack(self) - return msg - - def sys_status_send(self, onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4): - ''' - The general system state. If the system is following the MAVLink - standard, the system state is mainly defined by three - orthogonal states/modes: The system mode, which is - either LOCKED (motors shut down and locked), MANUAL - (system under RC control), GUIDED (system with - autonomous position control, position setpoint - controlled manually) or AUTO (system guided by - path/waypoint planner). The NAV_MODE defined the - current flight state: LIFTOFF (often an open-loop - maneuver), LANDING, WAYPOINTS or VECTOR. This - represents the internal navigation state machine. The - system status shows wether the system is currently - active or not and if an emergency occured. During the - CRITICAL and EMERGENCY states the MAV is still - considered to be active, but should start emergency - procedures autonomously. After a failure occured it - should first move from active to critical to allow - manual intervention and then move to emergency after a - certain timeout. - - onboard_control_sensors_present : Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control (uint32_t) - onboard_control_sensors_enabled : Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control (uint32_t) - onboard_control_sensors_health : Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control (uint32_t) - load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) - voltage_battery : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) - current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) - battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery (int8_t) - drop_rate_comm : Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t) - errors_comm : Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t) - errors_count1 : Autopilot-specific errors (uint16_t) - errors_count2 : Autopilot-specific errors (uint16_t) - errors_count3 : Autopilot-specific errors (uint16_t) - errors_count4 : Autopilot-specific errors (uint16_t) - - ''' - return self.send(self.sys_status_encode(onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4)) - - def system_time_encode(self, time_unix_usec, time_boot_ms): - ''' - The system time is the time of the master clock, typically the - computer clock of the main onboard computer. - - time_unix_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t) - time_boot_ms : Timestamp of the component clock since boot time in milliseconds. (uint32_t) - - ''' - msg = MAVLink_system_time_message(time_unix_usec, time_boot_ms) - msg.pack(self) - return msg - - def system_time_send(self, time_unix_usec, time_boot_ms): - ''' - The system time is the time of the master clock, typically the - computer clock of the main onboard computer. - - time_unix_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t) - time_boot_ms : Timestamp of the component clock since boot time in milliseconds. (uint32_t) - - ''' - return self.send(self.system_time_encode(time_unix_usec, time_boot_ms)) - - def ping_encode(self, time_usec, seq, target_system, target_component): - ''' - A ping message either requesting or responding to a ping. This allows - to measure the system latencies, including serial - port, radio modem and UDP connections. - - time_usec : Unix timestamp in microseconds (uint64_t) - seq : PING sequence (uint32_t) - target_system : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) - target_component : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) - - ''' - msg = MAVLink_ping_message(time_usec, seq, target_system, target_component) - msg.pack(self) - return msg - - def ping_send(self, time_usec, seq, target_system, target_component): - ''' - A ping message either requesting or responding to a ping. This allows - to measure the system latencies, including serial - port, radio modem and UDP connections. - - time_usec : Unix timestamp in microseconds (uint64_t) - seq : PING sequence (uint32_t) - target_system : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) - target_component : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) - - ''' - return self.send(self.ping_encode(time_usec, seq, target_system, target_component)) - - def change_operator_control_encode(self, target_system, control_request, version, passkey): - ''' - Request to control this MAV - - target_system : System the GCS requests control for (uint8_t) - control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) - version : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t) - passkey : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char) - - ''' - msg = MAVLink_change_operator_control_message(target_system, control_request, version, passkey) - msg.pack(self) - return msg - - def change_operator_control_send(self, target_system, control_request, version, passkey): - ''' - Request to control this MAV - - target_system : System the GCS requests control for (uint8_t) - control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) - version : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t) - passkey : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char) - - ''' - return self.send(self.change_operator_control_encode(target_system, control_request, version, passkey)) - - def change_operator_control_ack_encode(self, gcs_system_id, control_request, ack): - ''' - Accept / deny control of this MAV - - gcs_system_id : ID of the GCS this message (uint8_t) - control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) - ack : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t) - - ''' - msg = MAVLink_change_operator_control_ack_message(gcs_system_id, control_request, ack) - msg.pack(self) - return msg - - def change_operator_control_ack_send(self, gcs_system_id, control_request, ack): - ''' - Accept / deny control of this MAV - - gcs_system_id : ID of the GCS this message (uint8_t) - control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) - ack : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t) - - ''' - return self.send(self.change_operator_control_ack_encode(gcs_system_id, control_request, ack)) - - def auth_key_encode(self, key): - ''' - Emit an encrypted signature / key identifying this system. PLEASE - NOTE: This protocol has been kept simple, so - transmitting the key requires an encrypted channel for - true safety. - - key : key (char) - - ''' - msg = MAVLink_auth_key_message(key) - msg.pack(self) - return msg - - def auth_key_send(self, key): - ''' - Emit an encrypted signature / key identifying this system. PLEASE - NOTE: This protocol has been kept simple, so - transmitting the key requires an encrypted channel for - true safety. - - key : key (char) - - ''' - return self.send(self.auth_key_encode(key)) - - def set_mode_encode(self, target_system, base_mode, custom_mode): - ''' - Set the system mode, as defined by enum MAV_MODE. There is no target - component id as the mode is by definition for the - overall aircraft, not only for one component. - - target_system : The system setting the mode (uint8_t) - base_mode : The new base mode (uint8_t) - custom_mode : The new autopilot-specific mode. This field can be ignored by an autopilot. (uint32_t) - - ''' - msg = MAVLink_set_mode_message(target_system, base_mode, custom_mode) - msg.pack(self) - return msg - - def set_mode_send(self, target_system, base_mode, custom_mode): - ''' - Set the system mode, as defined by enum MAV_MODE. There is no target - component id as the mode is by definition for the - overall aircraft, not only for one component. - - target_system : The system setting the mode (uint8_t) - base_mode : The new base mode (uint8_t) - custom_mode : The new autopilot-specific mode. This field can be ignored by an autopilot. (uint32_t) - - ''' - return self.send(self.set_mode_encode(target_system, base_mode, custom_mode)) - - def param_request_read_encode(self, target_system, target_component, param_id, param_index): - ''' - Request to read the onboard parameter with the param_id string id. - Onboard parameters are stored as key[const char*] -> - value[float]. This allows to send a parameter to any - other component (such as the GCS) without the need of - previous knowledge of possible parameter names. Thus - the same GCS can store different parameters for - different autopilots. See also - http://qgroundcontrol.org/parameter_interface for a - full documentation of QGroundControl and IMU code. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - param_id : Onboard parameter id (char) - param_index : Parameter index. Send -1 to use the param ID field as identifier (int16_t) - - ''' - msg = MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) - msg.pack(self) - return msg - - def param_request_read_send(self, target_system, target_component, param_id, param_index): - ''' - Request to read the onboard parameter with the param_id string id. - Onboard parameters are stored as key[const char*] -> - value[float]. This allows to send a parameter to any - other component (such as the GCS) without the need of - previous knowledge of possible parameter names. Thus - the same GCS can store different parameters for - different autopilots. See also - http://qgroundcontrol.org/parameter_interface for a - full documentation of QGroundControl and IMU code. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - param_id : Onboard parameter id (char) - param_index : Parameter index. Send -1 to use the param ID field as identifier (int16_t) - - ''' - return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) - - def param_request_list_encode(self, target_system, target_component): - ''' - Request all parameters of this component. After his request, all - parameters are emitted. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - msg = MAVLink_param_request_list_message(target_system, target_component) - msg.pack(self) - return msg - - def param_request_list_send(self, target_system, target_component): - ''' - Request all parameters of this component. After his request, all - parameters are emitted. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - return self.send(self.param_request_list_encode(target_system, target_component)) - - def param_value_encode(self, param_id, param_value, param_type, param_count, param_index): - ''' - Emit the value of a onboard parameter. The inclusion of param_count - and param_index in the message allows the recipient to - keep track of received parameters and allows him to - re-request missing parameters after a loss or timeout. - - param_id : Onboard parameter id (char) - param_value : Onboard parameter value (float) - param_type : Onboard parameter type: see MAV_VAR enum (uint8_t) - param_count : Total number of onboard parameters (uint16_t) - param_index : Index of this onboard parameter (uint16_t) - - ''' - msg = MAVLink_param_value_message(param_id, param_value, param_type, param_count, param_index) - msg.pack(self) - return msg - - def param_value_send(self, param_id, param_value, param_type, param_count, param_index): - ''' - Emit the value of a onboard parameter. The inclusion of param_count - and param_index in the message allows the recipient to - keep track of received parameters and allows him to - re-request missing parameters after a loss or timeout. - - param_id : Onboard parameter id (char) - param_value : Onboard parameter value (float) - param_type : Onboard parameter type: see MAV_VAR enum (uint8_t) - param_count : Total number of onboard parameters (uint16_t) - param_index : Index of this onboard parameter (uint16_t) - - ''' - return self.send(self.param_value_encode(param_id, param_value, param_type, param_count, param_index)) - - def param_set_encode(self, target_system, target_component, param_id, param_value, param_type): - ''' - Set a parameter value TEMPORARILY to RAM. It will be reset to default - on system reboot. Send the ACTION - MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM - contents to EEPROM. IMPORTANT: The receiving component - should acknowledge the new parameter value by sending - a param_value message to all communication partners. - This will also ensure that multiple GCS all have an - up-to-date list of all parameters. If the sending GCS - did not receive a PARAM_VALUE message within its - timeout time, it should re-send the PARAM_SET message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - param_id : Onboard parameter id (char) - param_value : Onboard parameter value (float) - param_type : Onboard parameter type: see MAV_VAR enum (uint8_t) - - ''' - msg = MAVLink_param_set_message(target_system, target_component, param_id, param_value, param_type) - msg.pack(self) - return msg - - def param_set_send(self, target_system, target_component, param_id, param_value, param_type): - ''' - Set a parameter value TEMPORARILY to RAM. It will be reset to default - on system reboot. Send the ACTION - MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM - contents to EEPROM. IMPORTANT: The receiving component - should acknowledge the new parameter value by sending - a param_value message to all communication partners. - This will also ensure that multiple GCS all have an - up-to-date list of all parameters. If the sending GCS - did not receive a PARAM_VALUE message within its - timeout time, it should re-send the PARAM_SET message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - param_id : Onboard parameter id (char) - param_value : Onboard parameter value (float) - param_type : Onboard parameter type: see MAV_VAR enum (uint8_t) - - ''' - return self.send(self.param_set_encode(target_system, target_component, param_id, param_value, param_type)) - - def gps_raw_int_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): - ''' - The global position, as returned by the Global Positioning System - (GPS). This is NOT the global position - estimate of the sytem, but rather a RAW sensor value. - See message GLOBAL_POSITION for the global position - estimate. Coordinate frame is right-handed, Z-axis up - (GPS frame) - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) - lat : Latitude in 1E7 degrees (int32_t) - lon : Longitude in 1E7 degrees (int32_t) - alt : Altitude in 1E3 meters (millimeters) above MSL (int32_t) - eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) - epv : GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) - vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) - cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) - satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) - - ''' - msg = MAVLink_gps_raw_int_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible) - msg.pack(self) - return msg - - def gps_raw_int_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): - ''' - The global position, as returned by the Global Positioning System - (GPS). This is NOT the global position - estimate of the sytem, but rather a RAW sensor value. - See message GLOBAL_POSITION for the global position - estimate. Coordinate frame is right-handed, Z-axis up - (GPS frame) - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) - lat : Latitude in 1E7 degrees (int32_t) - lon : Longitude in 1E7 degrees (int32_t) - alt : Altitude in 1E3 meters (millimeters) above MSL (int32_t) - eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) - epv : GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) - vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) - cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) - satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) - - ''' - return self.send(self.gps_raw_int_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible)) - - def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): - ''' - The positioning status, as reported by GPS. This message is intended - to display status information about each satellite - visible to the receiver. See message GLOBAL_POSITION - for the global position estimate. This message can - contain information for up to 20 satellites. - - satellites_visible : Number of satellites visible (uint8_t) - satellite_prn : Global satellite ID (uint8_t) - satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) - satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) - satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) - satellite_snr : Signal to noise ratio of satellite (uint8_t) - - ''' - msg = MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) - msg.pack(self) - return msg - - def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): - ''' - The positioning status, as reported by GPS. This message is intended - to display status information about each satellite - visible to the receiver. See message GLOBAL_POSITION - for the global position estimate. This message can - contain information for up to 20 satellites. - - satellites_visible : Number of satellites visible (uint8_t) - satellite_prn : Global satellite ID (uint8_t) - satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) - satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) - satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) - satellite_snr : Signal to noise ratio of satellite (uint8_t) - - ''' - return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) - - def scaled_imu_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This message - should contain the scaled values to the described - units - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - xacc : X acceleration (mg) (int16_t) - yacc : Y acceleration (mg) (int16_t) - zacc : Z acceleration (mg) (int16_t) - xgyro : Angular speed around X axis (millirad /sec) (int16_t) - ygyro : Angular speed around Y axis (millirad /sec) (int16_t) - zgyro : Angular speed around Z axis (millirad /sec) (int16_t) - xmag : X Magnetic field (milli tesla) (int16_t) - ymag : Y Magnetic field (milli tesla) (int16_t) - zmag : Z Magnetic field (milli tesla) (int16_t) - - ''' - msg = MAVLink_scaled_imu_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) - msg.pack(self) - return msg - - def scaled_imu_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This message - should contain the scaled values to the described - units - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - xacc : X acceleration (mg) (int16_t) - yacc : Y acceleration (mg) (int16_t) - zacc : Z acceleration (mg) (int16_t) - xgyro : Angular speed around X axis (millirad /sec) (int16_t) - ygyro : Angular speed around Y axis (millirad /sec) (int16_t) - zgyro : Angular speed around Z axis (millirad /sec) (int16_t) - xmag : X Magnetic field (milli tesla) (int16_t) - ymag : Y Magnetic field (milli tesla) (int16_t) - zmag : Z Magnetic field (milli tesla) (int16_t) - - ''' - return self.send(self.scaled_imu_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) - - def raw_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This message - should always contain the true raw values without any - scaling to allow data capture and system debugging. - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - xacc : X acceleration (raw) (int16_t) - yacc : Y acceleration (raw) (int16_t) - zacc : Z acceleration (raw) (int16_t) - xgyro : Angular speed around X axis (raw) (int16_t) - ygyro : Angular speed around Y axis (raw) (int16_t) - zgyro : Angular speed around Z axis (raw) (int16_t) - xmag : X Magnetic field (raw) (int16_t) - ymag : Y Magnetic field (raw) (int16_t) - zmag : Z Magnetic field (raw) (int16_t) - - ''' - msg = MAVLink_raw_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) - msg.pack(self) - return msg - - def raw_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This message - should always contain the true raw values without any - scaling to allow data capture and system debugging. - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - xacc : X acceleration (raw) (int16_t) - yacc : Y acceleration (raw) (int16_t) - zacc : Z acceleration (raw) (int16_t) - xgyro : Angular speed around X axis (raw) (int16_t) - ygyro : Angular speed around Y axis (raw) (int16_t) - zgyro : Angular speed around Z axis (raw) (int16_t) - xmag : X Magnetic field (raw) (int16_t) - ymag : Y Magnetic field (raw) (int16_t) - zmag : Z Magnetic field (raw) (int16_t) - - ''' - return self.send(self.raw_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) - - def raw_pressure_encode(self, time_usec, press_abs, press_diff1, press_diff2, temperature): - ''' - The RAW pressure readings for the typical setup of one absolute - pressure and one differential pressure sensor. The - sensor values should be the raw, UNSCALED ADC values. - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - press_abs : Absolute pressure (raw) (int16_t) - press_diff1 : Differential pressure 1 (raw) (int16_t) - press_diff2 : Differential pressure 2 (raw) (int16_t) - temperature : Raw Temperature measurement (raw) (int16_t) - - ''' - msg = MAVLink_raw_pressure_message(time_usec, press_abs, press_diff1, press_diff2, temperature) - msg.pack(self) - return msg - - def raw_pressure_send(self, time_usec, press_abs, press_diff1, press_diff2, temperature): - ''' - The RAW pressure readings for the typical setup of one absolute - pressure and one differential pressure sensor. The - sensor values should be the raw, UNSCALED ADC values. - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - press_abs : Absolute pressure (raw) (int16_t) - press_diff1 : Differential pressure 1 (raw) (int16_t) - press_diff2 : Differential pressure 2 (raw) (int16_t) - temperature : Raw Temperature measurement (raw) (int16_t) - - ''' - return self.send(self.raw_pressure_encode(time_usec, press_abs, press_diff1, press_diff2, temperature)) - - def scaled_pressure_encode(self, time_boot_ms, press_abs, press_diff, temperature): - ''' - The pressure readings for the typical setup of one absolute and - differential pressure sensor. The units are as - specified in each field. - - time_boot_ms : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint32_t) - press_abs : Absolute pressure (hectopascal) (float) - press_diff : Differential pressure 1 (hectopascal) (float) - temperature : Temperature measurement (0.01 degrees celsius) (int16_t) - - ''' - msg = MAVLink_scaled_pressure_message(time_boot_ms, press_abs, press_diff, temperature) - msg.pack(self) - return msg - - def scaled_pressure_send(self, time_boot_ms, press_abs, press_diff, temperature): - ''' - The pressure readings for the typical setup of one absolute and - differential pressure sensor. The units are as - specified in each field. - - time_boot_ms : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint32_t) - press_abs : Absolute pressure (hectopascal) (float) - press_diff : Differential pressure 1 (hectopascal) (float) - temperature : Temperature measurement (0.01 degrees celsius) (int16_t) - - ''' - return self.send(self.scaled_pressure_encode(time_boot_ms, press_abs, press_diff, temperature)) - - def attitude_encode(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): - ''' - The attitude in the aeronautical frame (right-handed, Z-down, X-front, - Y-right). - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - - ''' - msg = MAVLink_attitude_message(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) - msg.pack(self) - return msg - - def attitude_send(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): - ''' - The attitude in the aeronautical frame (right-handed, Z-down, X-front, - Y-right). - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - - ''' - return self.send(self.attitude_encode(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) - - def attitude_quaternion_encode(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): - ''' - The attitude in the aeronautical frame (right-handed, Z-down, X-front, - Y-right), expressed as quaternion. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - q1 : Quaternion component 1 (float) - q2 : Quaternion component 2 (float) - q3 : Quaternion component 3 (float) - q4 : Quaternion component 4 (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - - ''' - msg = MAVLink_attitude_quaternion_message(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed) - msg.pack(self) - return msg - - def attitude_quaternion_send(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): - ''' - The attitude in the aeronautical frame (right-handed, Z-down, X-front, - Y-right), expressed as quaternion. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - q1 : Quaternion component 1 (float) - q2 : Quaternion component 2 (float) - q3 : Quaternion component 3 (float) - q4 : Quaternion component 4 (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - - ''' - return self.send(self.attitude_quaternion_encode(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed)) - - def local_position_ned_encode(self, time_boot_ms, x, y, z, vx, vy, vz): - ''' - The filtered local position (e.g. fused computer vision and - accelerometers). Coordinate frame is right-handed, - Z-axis down (aeronautical frame, NED / north-east-down - convention) - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - x : X Position (float) - y : Y Position (float) - z : Z Position (float) - vx : X Speed (float) - vy : Y Speed (float) - vz : Z Speed (float) - - ''' - msg = MAVLink_local_position_ned_message(time_boot_ms, x, y, z, vx, vy, vz) - msg.pack(self) - return msg - - def local_position_ned_send(self, time_boot_ms, x, y, z, vx, vy, vz): - ''' - The filtered local position (e.g. fused computer vision and - accelerometers). Coordinate frame is right-handed, - Z-axis down (aeronautical frame, NED / north-east-down - convention) - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - x : X Position (float) - y : Y Position (float) - z : Z Position (float) - vx : X Speed (float) - vy : Y Speed (float) - vz : Z Speed (float) - - ''' - return self.send(self.local_position_ned_encode(time_boot_ms, x, y, z, vx, vy, vz)) - - def global_position_int_encode(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): - ''' - The filtered global position (e.g. fused GPS and accelerometers). The - position is in GPS-frame (right-handed, Z-up). It - is designed as scaled integer message since the - resolution of float is not sufficient. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - lat : Latitude, expressed as * 1E7 (int32_t) - lon : Longitude, expressed as * 1E7 (int32_t) - alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) - relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) - vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) - vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) - vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) - hdg : Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) - - ''' - msg = MAVLink_global_position_int_message(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg) - msg.pack(self) - return msg - - def global_position_int_send(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): - ''' - The filtered global position (e.g. fused GPS and accelerometers). The - position is in GPS-frame (right-handed, Z-up). It - is designed as scaled integer message since the - resolution of float is not sufficient. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - lat : Latitude, expressed as * 1E7 (int32_t) - lon : Longitude, expressed as * 1E7 (int32_t) - alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) - relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) - vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) - vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) - vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) - hdg : Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) - - ''' - return self.send(self.global_position_int_encode(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg)) - - def rc_channels_scaled_encode(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): - ''' - The scaled values of the RC channels received. (-100%) -10000, (0%) 0, - (100%) 10000 - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) - chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - msg = MAVLink_rc_channels_scaled_message(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) - msg.pack(self) - return msg - - def rc_channels_scaled_send(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): - ''' - The scaled values of the RC channels received. (-100%) -10000, (0%) 0, - (100%) 10000 - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) - chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - return self.send(self.rc_channels_scaled_encode(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) - - def rc_channels_raw_encode(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): - ''' - The RAW values of the RC channels received. The standard PPM - modulation is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. Individual receivers/transmitters - might violate this specification. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - msg = MAVLink_rc_channels_raw_message(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) - msg.pack(self) - return msg - - def rc_channels_raw_send(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): - ''' - The RAW values of the RC channels received. The standard PPM - modulation is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. Individual receivers/transmitters - might violate this specification. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - return self.send(self.rc_channels_raw_encode(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) - - def servo_output_raw_encode(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): - ''' - The RAW values of the servo outputs (for RC input from the remote, use - the RC_CHANNELS messages). The standard PPM modulation - is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. - - time_usec : Timestamp (since UNIX epoch or microseconds since system boot) (uint32_t) - port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) - servo1_raw : Servo output 1 value, in microseconds (uint16_t) - servo2_raw : Servo output 2 value, in microseconds (uint16_t) - servo3_raw : Servo output 3 value, in microseconds (uint16_t) - servo4_raw : Servo output 4 value, in microseconds (uint16_t) - servo5_raw : Servo output 5 value, in microseconds (uint16_t) - servo6_raw : Servo output 6 value, in microseconds (uint16_t) - servo7_raw : Servo output 7 value, in microseconds (uint16_t) - servo8_raw : Servo output 8 value, in microseconds (uint16_t) - - ''' - msg = MAVLink_servo_output_raw_message(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) - msg.pack(self) - return msg - - def servo_output_raw_send(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): - ''' - The RAW values of the servo outputs (for RC input from the remote, use - the RC_CHANNELS messages). The standard PPM modulation - is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. - - time_usec : Timestamp (since UNIX epoch or microseconds since system boot) (uint32_t) - port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) - servo1_raw : Servo output 1 value, in microseconds (uint16_t) - servo2_raw : Servo output 2 value, in microseconds (uint16_t) - servo3_raw : Servo output 3 value, in microseconds (uint16_t) - servo4_raw : Servo output 4 value, in microseconds (uint16_t) - servo5_raw : Servo output 5 value, in microseconds (uint16_t) - servo6_raw : Servo output 6 value, in microseconds (uint16_t) - servo7_raw : Servo output 7 value, in microseconds (uint16_t) - servo8_raw : Servo output 8 value, in microseconds (uint16_t) - - ''' - return self.send(self.servo_output_raw_encode(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) - - def mission_request_partial_list_encode(self, target_system, target_component, start_index, end_index): - ''' - Request the overall list of MISSIONs from the system/component. - http://qgroundcontrol.org/mavlink/waypoint_protocol - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - start_index : Start index, 0 by default (int16_t) - end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) - - ''' - msg = MAVLink_mission_request_partial_list_message(target_system, target_component, start_index, end_index) - msg.pack(self) - return msg - - def mission_request_partial_list_send(self, target_system, target_component, start_index, end_index): - ''' - Request the overall list of MISSIONs from the system/component. - http://qgroundcontrol.org/mavlink/waypoint_protocol - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - start_index : Start index, 0 by default (int16_t) - end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) - - ''' - return self.send(self.mission_request_partial_list_encode(target_system, target_component, start_index, end_index)) - - def mission_write_partial_list_encode(self, target_system, target_component, start_index, end_index): - ''' - This message is sent to the MAV to write a partial list. If start - index == end index, only one item will be transmitted - / updated. If the start index is NOT 0 and above the - current list size, this request should be REJECTED! - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) - end_index : End index, equal or greater than start index. (int16_t) - - ''' - msg = MAVLink_mission_write_partial_list_message(target_system, target_component, start_index, end_index) - msg.pack(self) - return msg - - def mission_write_partial_list_send(self, target_system, target_component, start_index, end_index): - ''' - This message is sent to the MAV to write a partial list. If start - index == end index, only one item will be transmitted - / updated. If the start index is NOT 0 and above the - current list size, this request should be REJECTED! - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) - end_index : End index, equal or greater than start index. (int16_t) - - ''' - return self.send(self.mission_write_partial_list_encode(target_system, target_component, start_index, end_index)) - - def mission_item_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): - ''' - Message encoding a mission item. This message is emitted to announce - the presence of a mission item and to set a mission - item on the system. The mission item can be either in - x, y, z meters (type: LOCAL) or x:lat, y:lon, - z:altitude. Local frame is Z-down, right handed (NED), - global frame is Z-up, right handed (ENU). - http://qgroundcontrol.org/mavlink/waypoint_protocol - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) - command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) - current : false:0, true:1 (uint8_t) - autocontinue : autocontinue to next wp (uint8_t) - param1 : PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters (float) - param2 : PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float) - param3 : PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float) - param4 : PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH (float) - x : PARAM5 / local: x position, global: latitude (float) - y : PARAM6 / y position: global: longitude (float) - z : PARAM7 / z position: global: altitude (float) - - ''' - msg = MAVLink_mission_item_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) - msg.pack(self) - return msg - - def mission_item_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): - ''' - Message encoding a mission item. This message is emitted to announce - the presence of a mission item and to set a mission - item on the system. The mission item can be either in - x, y, z meters (type: LOCAL) or x:lat, y:lon, - z:altitude. Local frame is Z-down, right handed (NED), - global frame is Z-up, right handed (ENU). - http://qgroundcontrol.org/mavlink/waypoint_protocol - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) - command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) - current : false:0, true:1 (uint8_t) - autocontinue : autocontinue to next wp (uint8_t) - param1 : PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters (float) - param2 : PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float) - param3 : PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float) - param4 : PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH (float) - x : PARAM5 / local: x position, global: latitude (float) - y : PARAM6 / y position: global: longitude (float) - z : PARAM7 / z position: global: altitude (float) - - ''' - return self.send(self.mission_item_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) - - def mission_request_encode(self, target_system, target_component, seq): - ''' - Request the information of the mission item with the sequence number - seq. The response of the system to this message should - be a MISSION_ITEM message. - http://qgroundcontrol.org/mavlink/waypoint_protocol - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - - ''' - msg = MAVLink_mission_request_message(target_system, target_component, seq) - msg.pack(self) - return msg - - def mission_request_send(self, target_system, target_component, seq): - ''' - Request the information of the mission item with the sequence number - seq. The response of the system to this message should - be a MISSION_ITEM message. - http://qgroundcontrol.org/mavlink/waypoint_protocol - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - - ''' - return self.send(self.mission_request_encode(target_system, target_component, seq)) - - def mission_set_current_encode(self, target_system, target_component, seq): - ''' - Set the mission item with sequence number seq as current item. This - means that the MAV will continue to this mission item - on the shortest path (not following the mission items - in-between). - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - - ''' - msg = MAVLink_mission_set_current_message(target_system, target_component, seq) - msg.pack(self) - return msg - - def mission_set_current_send(self, target_system, target_component, seq): - ''' - Set the mission item with sequence number seq as current item. This - means that the MAV will continue to this mission item - on the shortest path (not following the mission items - in-between). - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - - ''' - return self.send(self.mission_set_current_encode(target_system, target_component, seq)) - - def mission_current_encode(self, seq): - ''' - Message that announces the sequence number of the current active - mission item. The MAV will fly towards this mission - item. - - seq : Sequence (uint16_t) - - ''' - msg = MAVLink_mission_current_message(seq) - msg.pack(self) - return msg - - def mission_current_send(self, seq): - ''' - Message that announces the sequence number of the current active - mission item. The MAV will fly towards this mission - item. - - seq : Sequence (uint16_t) - - ''' - return self.send(self.mission_current_encode(seq)) - - def mission_request_list_encode(self, target_system, target_component): - ''' - Request the overall list of mission items from the system/component. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - msg = MAVLink_mission_request_list_message(target_system, target_component) - msg.pack(self) - return msg - - def mission_request_list_send(self, target_system, target_component): - ''' - Request the overall list of mission items from the system/component. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - return self.send(self.mission_request_list_encode(target_system, target_component)) - - def mission_count_encode(self, target_system, target_component, count): - ''' - This message is emitted as response to MISSION_REQUEST_LIST by the MAV - and to initiate a write transaction. The GCS can then - request the individual mission item based on the - knowledge of the total number of MISSIONs. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - count : Number of mission items in the sequence (uint16_t) - - ''' - msg = MAVLink_mission_count_message(target_system, target_component, count) - msg.pack(self) - return msg - - def mission_count_send(self, target_system, target_component, count): - ''' - This message is emitted as response to MISSION_REQUEST_LIST by the MAV - and to initiate a write transaction. The GCS can then - request the individual mission item based on the - knowledge of the total number of MISSIONs. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - count : Number of mission items in the sequence (uint16_t) - - ''' - return self.send(self.mission_count_encode(target_system, target_component, count)) - - def mission_clear_all_encode(self, target_system, target_component): - ''' - Delete all mission items at once. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - msg = MAVLink_mission_clear_all_message(target_system, target_component) - msg.pack(self) - return msg - - def mission_clear_all_send(self, target_system, target_component): - ''' - Delete all mission items at once. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - return self.send(self.mission_clear_all_encode(target_system, target_component)) - - def mission_item_reached_encode(self, seq): - ''' - A certain mission item has been reached. The system will either hold - this position (or circle on the orbit) or (if the - autocontinue on the WP was set) continue to the next - MISSION. - - seq : Sequence (uint16_t) - - ''' - msg = MAVLink_mission_item_reached_message(seq) - msg.pack(self) - return msg - - def mission_item_reached_send(self, seq): - ''' - A certain mission item has been reached. The system will either hold - this position (or circle on the orbit) or (if the - autocontinue on the WP was set) continue to the next - MISSION. - - seq : Sequence (uint16_t) - - ''' - return self.send(self.mission_item_reached_encode(seq)) - - def mission_ack_encode(self, target_system, target_component, type): - ''' - Ack message during MISSION handling. The type field states if this - message is a positive ack (type=0) or if an error - happened (type=non-zero). - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - type : See MAV_MISSION_RESULT enum (uint8_t) - - ''' - msg = MAVLink_mission_ack_message(target_system, target_component, type) - msg.pack(self) - return msg - - def mission_ack_send(self, target_system, target_component, type): - ''' - Ack message during MISSION handling. The type field states if this - message is a positive ack (type=0) or if an error - happened (type=non-zero). - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - type : See MAV_MISSION_RESULT enum (uint8_t) - - ''' - return self.send(self.mission_ack_encode(target_system, target_component, type)) - - def set_gps_global_origin_encode(self, target_system, latitude, longitude, altitude): - ''' - As local MISSIONs exist, the global MISSION reference allows to - transform between the local coordinate frame and the - global (GPS) coordinate frame. This can be necessary - when e.g. in- and outdoor settings are connected and - the MAV should move from in- to outdoor. - - target_system : System ID (uint8_t) - latitude : global position * 1E7 (int32_t) - longitude : global position * 1E7 (int32_t) - altitude : global position * 1000 (int32_t) - - ''' - msg = MAVLink_set_gps_global_origin_message(target_system, latitude, longitude, altitude) - msg.pack(self) - return msg - - def set_gps_global_origin_send(self, target_system, latitude, longitude, altitude): - ''' - As local MISSIONs exist, the global MISSION reference allows to - transform between the local coordinate frame and the - global (GPS) coordinate frame. This can be necessary - when e.g. in- and outdoor settings are connected and - the MAV should move from in- to outdoor. - - target_system : System ID (uint8_t) - latitude : global position * 1E7 (int32_t) - longitude : global position * 1E7 (int32_t) - altitude : global position * 1000 (int32_t) - - ''' - return self.send(self.set_gps_global_origin_encode(target_system, latitude, longitude, altitude)) - - def gps_global_origin_encode(self, latitude, longitude, altitude): - ''' - Once the MAV sets a new GPS-Local correspondence, this message - announces the origin (0,0,0) position - - latitude : Latitude (WGS84), expressed as * 1E7 (int32_t) - longitude : Longitude (WGS84), expressed as * 1E7 (int32_t) - altitude : Altitude(WGS84), expressed as * 1000 (int32_t) - - ''' - msg = MAVLink_gps_global_origin_message(latitude, longitude, altitude) - msg.pack(self) - return msg - - def gps_global_origin_send(self, latitude, longitude, altitude): - ''' - Once the MAV sets a new GPS-Local correspondence, this message - announces the origin (0,0,0) position - - latitude : Latitude (WGS84), expressed as * 1E7 (int32_t) - longitude : Longitude (WGS84), expressed as * 1E7 (int32_t) - altitude : Altitude(WGS84), expressed as * 1000 (int32_t) - - ''' - return self.send(self.gps_global_origin_encode(latitude, longitude, altitude)) - - def set_local_position_setpoint_encode(self, target_system, target_component, coordinate_frame, x, y, z, yaw): - ''' - Set the setpoint for a local position controller. This is the position - in local coordinates the MAV should fly to. This - message is sent by the path/MISSION planner to the - onboard position controller. As some MAVs have a - degree of freedom in yaw (e.g. all - helicopters/quadrotors), the desired yaw angle is part - of the message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t) - x : x position (float) - y : y position (float) - z : z position (float) - yaw : Desired yaw angle (float) - - ''' - msg = MAVLink_set_local_position_setpoint_message(target_system, target_component, coordinate_frame, x, y, z, yaw) - msg.pack(self) - return msg - - def set_local_position_setpoint_send(self, target_system, target_component, coordinate_frame, x, y, z, yaw): - ''' - Set the setpoint for a local position controller. This is the position - in local coordinates the MAV should fly to. This - message is sent by the path/MISSION planner to the - onboard position controller. As some MAVs have a - degree of freedom in yaw (e.g. all - helicopters/quadrotors), the desired yaw angle is part - of the message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t) - x : x position (float) - y : y position (float) - z : z position (float) - yaw : Desired yaw angle (float) - - ''' - return self.send(self.set_local_position_setpoint_encode(target_system, target_component, coordinate_frame, x, y, z, yaw)) - - def local_position_setpoint_encode(self, coordinate_frame, x, y, z, yaw): - ''' - Transmit the current local setpoint of the controller to other MAVs - (collision avoidance) and to the GCS. - - coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t) - x : x position (float) - y : y position (float) - z : z position (float) - yaw : Desired yaw angle (float) - - ''' - msg = MAVLink_local_position_setpoint_message(coordinate_frame, x, y, z, yaw) - msg.pack(self) - return msg - - def local_position_setpoint_send(self, coordinate_frame, x, y, z, yaw): - ''' - Transmit the current local setpoint of the controller to other MAVs - (collision avoidance) and to the GCS. - - coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t) - x : x position (float) - y : y position (float) - z : z position (float) - yaw : Desired yaw angle (float) - - ''' - return self.send(self.local_position_setpoint_encode(coordinate_frame, x, y, z, yaw)) - - def global_position_setpoint_int_encode(self, coordinate_frame, latitude, longitude, altitude, yaw): - ''' - Transmit the current local setpoint of the controller to other MAVs - (collision avoidance) and to the GCS. - - coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t) - latitude : WGS84 Latitude position in degrees * 1E7 (int32_t) - longitude : WGS84 Longitude position in degrees * 1E7 (int32_t) - altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t) - yaw : Desired yaw angle in degrees * 100 (int16_t) - - ''' - msg = MAVLink_global_position_setpoint_int_message(coordinate_frame, latitude, longitude, altitude, yaw) - msg.pack(self) - return msg - - def global_position_setpoint_int_send(self, coordinate_frame, latitude, longitude, altitude, yaw): - ''' - Transmit the current local setpoint of the controller to other MAVs - (collision avoidance) and to the GCS. - - coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t) - latitude : WGS84 Latitude position in degrees * 1E7 (int32_t) - longitude : WGS84 Longitude position in degrees * 1E7 (int32_t) - altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t) - yaw : Desired yaw angle in degrees * 100 (int16_t) - - ''' - return self.send(self.global_position_setpoint_int_encode(coordinate_frame, latitude, longitude, altitude, yaw)) - - def set_global_position_setpoint_int_encode(self, coordinate_frame, latitude, longitude, altitude, yaw): - ''' - Set the current global position setpoint. - - coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t) - latitude : WGS84 Latitude position in degrees * 1E7 (int32_t) - longitude : WGS84 Longitude position in degrees * 1E7 (int32_t) - altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t) - yaw : Desired yaw angle in degrees * 100 (int16_t) - - ''' - msg = MAVLink_set_global_position_setpoint_int_message(coordinate_frame, latitude, longitude, altitude, yaw) - msg.pack(self) - return msg - - def set_global_position_setpoint_int_send(self, coordinate_frame, latitude, longitude, altitude, yaw): - ''' - Set the current global position setpoint. - - coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t) - latitude : WGS84 Latitude position in degrees * 1E7 (int32_t) - longitude : WGS84 Longitude position in degrees * 1E7 (int32_t) - altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t) - yaw : Desired yaw angle in degrees * 100 (int16_t) - - ''' - return self.send(self.set_global_position_setpoint_int_encode(coordinate_frame, latitude, longitude, altitude, yaw)) - - def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): - ''' - Set a safety zone (volume), which is defined by two corners of a cube. - This message can be used to tell the MAV which - setpoints/MISSIONs to accept and which to reject. - Safety areas are often enforced by national or - competition regulations. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) - p1x : x position 1 / Latitude 1 (float) - p1y : y position 1 / Longitude 1 (float) - p1z : z position 1 / Altitude 1 (float) - p2x : x position 2 / Latitude 2 (float) - p2y : y position 2 / Longitude 2 (float) - p2z : z position 2 / Altitude 2 (float) - - ''' - msg = MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) - msg.pack(self) - return msg - - def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): - ''' - Set a safety zone (volume), which is defined by two corners of a cube. - This message can be used to tell the MAV which - setpoints/MISSIONs to accept and which to reject. - Safety areas are often enforced by national or - competition regulations. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) - p1x : x position 1 / Latitude 1 (float) - p1y : y position 1 / Longitude 1 (float) - p1z : z position 1 / Altitude 1 (float) - p2x : x position 2 / Latitude 2 (float) - p2y : y position 2 / Longitude 2 (float) - p2z : z position 2 / Altitude 2 (float) - - ''' - return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) - - def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): - ''' - Read out the safety zone the MAV currently assumes. - - frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) - p1x : x position 1 / Latitude 1 (float) - p1y : y position 1 / Longitude 1 (float) - p1z : z position 1 / Altitude 1 (float) - p2x : x position 2 / Latitude 2 (float) - p2y : y position 2 / Longitude 2 (float) - p2z : z position 2 / Altitude 2 (float) - - ''' - msg = MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) - msg.pack(self) - return msg - - def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): - ''' - Read out the safety zone the MAV currently assumes. - - frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) - p1x : x position 1 / Latitude 1 (float) - p1y : y position 1 / Longitude 1 (float) - p1z : z position 1 / Altitude 1 (float) - p2x : x position 2 / Latitude 2 (float) - p2y : y position 2 / Longitude 2 (float) - p2z : z position 2 / Altitude 2 (float) - - ''' - return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) - - def set_roll_pitch_yaw_thrust_encode(self, target_system, target_component, roll, pitch, yaw, thrust): - ''' - Set roll, pitch and yaw. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - roll : Desired roll angle in radians (float) - pitch : Desired pitch angle in radians (float) - yaw : Desired yaw angle in radians (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - msg = MAVLink_set_roll_pitch_yaw_thrust_message(target_system, target_component, roll, pitch, yaw, thrust) - msg.pack(self) - return msg - - def set_roll_pitch_yaw_thrust_send(self, target_system, target_component, roll, pitch, yaw, thrust): - ''' - Set roll, pitch and yaw. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - roll : Desired roll angle in radians (float) - pitch : Desired pitch angle in radians (float) - yaw : Desired yaw angle in radians (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - return self.send(self.set_roll_pitch_yaw_thrust_encode(target_system, target_component, roll, pitch, yaw, thrust)) - - def set_roll_pitch_yaw_speed_thrust_encode(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): - ''' - Set roll, pitch and yaw. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - roll_speed : Desired roll angular speed in rad/s (float) - pitch_speed : Desired pitch angular speed in rad/s (float) - yaw_speed : Desired yaw angular speed in rad/s (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - msg = MAVLink_set_roll_pitch_yaw_speed_thrust_message(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust) - msg.pack(self) - return msg - - def set_roll_pitch_yaw_speed_thrust_send(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): - ''' - Set roll, pitch and yaw. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - roll_speed : Desired roll angular speed in rad/s (float) - pitch_speed : Desired pitch angular speed in rad/s (float) - yaw_speed : Desired yaw angular speed in rad/s (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - return self.send(self.set_roll_pitch_yaw_speed_thrust_encode(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust)) - - def roll_pitch_yaw_thrust_setpoint_encode(self, time_boot_ms, roll, pitch, yaw, thrust): - ''' - Setpoint in roll, pitch, yaw currently active on the system. - - time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) - roll : Desired roll angle in radians (float) - pitch : Desired pitch angle in radians (float) - yaw : Desired yaw angle in radians (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - msg = MAVLink_roll_pitch_yaw_thrust_setpoint_message(time_boot_ms, roll, pitch, yaw, thrust) - msg.pack(self) - return msg - - def roll_pitch_yaw_thrust_setpoint_send(self, time_boot_ms, roll, pitch, yaw, thrust): - ''' - Setpoint in roll, pitch, yaw currently active on the system. - - time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) - roll : Desired roll angle in radians (float) - pitch : Desired pitch angle in radians (float) - yaw : Desired yaw angle in radians (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - return self.send(self.roll_pitch_yaw_thrust_setpoint_encode(time_boot_ms, roll, pitch, yaw, thrust)) - - def roll_pitch_yaw_speed_thrust_setpoint_encode(self, time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust): - ''' - Setpoint in rollspeed, pitchspeed, yawspeed currently active on the - system. - - time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) - roll_speed : Desired roll angular speed in rad/s (float) - pitch_speed : Desired pitch angular speed in rad/s (float) - yaw_speed : Desired yaw angular speed in rad/s (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - msg = MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust) - msg.pack(self) - return msg - - def roll_pitch_yaw_speed_thrust_setpoint_send(self, time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust): - ''' - Setpoint in rollspeed, pitchspeed, yawspeed currently active on the - system. - - time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) - roll_speed : Desired roll angular speed in rad/s (float) - pitch_speed : Desired pitch angular speed in rad/s (float) - yaw_speed : Desired yaw angular speed in rad/s (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - return self.send(self.roll_pitch_yaw_speed_thrust_setpoint_encode(time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust)) - - def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): - ''' - Outputs of the APM navigation controller. The primary use of this - message is to check the response and signs - of the controller before actual flight and to assist - with tuning controller parameters - - nav_roll : Current desired roll in degrees (float) - nav_pitch : Current desired pitch in degrees (float) - nav_bearing : Current desired heading in degrees (int16_t) - target_bearing : Bearing to current MISSION/target in degrees (int16_t) - wp_dist : Distance to active MISSION in meters (uint16_t) - alt_error : Current altitude error in meters (float) - aspd_error : Current airspeed error in meters/second (float) - xtrack_error : Current crosstrack error on x-y plane in meters (float) - - ''' - msg = MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) - msg.pack(self) - return msg - - def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): - ''' - Outputs of the APM navigation controller. The primary use of this - message is to check the response and signs - of the controller before actual flight and to assist - with tuning controller parameters - - nav_roll : Current desired roll in degrees (float) - nav_pitch : Current desired pitch in degrees (float) - nav_bearing : Current desired heading in degrees (int16_t) - target_bearing : Bearing to current MISSION/target in degrees (int16_t) - wp_dist : Distance to active MISSION in meters (uint16_t) - alt_error : Current altitude error in meters (float) - aspd_error : Current airspeed error in meters/second (float) - xtrack_error : Current crosstrack error on x-y plane in meters (float) - - ''' - return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) - - def state_correction_encode(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): - ''' - Corrects the systems state by adding an error correction term to the - position and velocity, and by rotating the attitude by - a correction angle. - - xErr : x position error (float) - yErr : y position error (float) - zErr : z position error (float) - rollErr : roll error (radians) (float) - pitchErr : pitch error (radians) (float) - yawErr : yaw error (radians) (float) - vxErr : x velocity (float) - vyErr : y velocity (float) - vzErr : z velocity (float) - - ''' - msg = MAVLink_state_correction_message(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr) - msg.pack(self) - return msg - - def state_correction_send(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): - ''' - Corrects the systems state by adding an error correction term to the - position and velocity, and by rotating the attitude by - a correction angle. - - xErr : x position error (float) - yErr : y position error (float) - zErr : z position error (float) - rollErr : roll error (radians) (float) - pitchErr : pitch error (radians) (float) - yawErr : yaw error (radians) (float) - vxErr : x velocity (float) - vyErr : y velocity (float) - vzErr : z velocity (float) - - ''' - return self.send(self.state_correction_encode(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr)) - - def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): - ''' - - - target_system : The target requested to send the message stream. (uint8_t) - target_component : The target requested to send the message stream. (uint8_t) - req_stream_id : The ID of the requested data stream (uint8_t) - req_message_rate : The requested interval between two messages of this type (uint16_t) - start_stop : 1 to start sending, 0 to stop sending. (uint8_t) - - ''' - msg = MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) - msg.pack(self) - return msg - - def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): - ''' - - - target_system : The target requested to send the message stream. (uint8_t) - target_component : The target requested to send the message stream. (uint8_t) - req_stream_id : The ID of the requested data stream (uint8_t) - req_message_rate : The requested interval between two messages of this type (uint16_t) - start_stop : 1 to start sending, 0 to stop sending. (uint8_t) - - ''' - return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) - - def data_stream_encode(self, stream_id, message_rate, on_off): - ''' - - - stream_id : The ID of the requested data stream (uint8_t) - message_rate : The requested interval between two messages of this type (uint16_t) - on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) - - ''' - msg = MAVLink_data_stream_message(stream_id, message_rate, on_off) - msg.pack(self) - return msg - - def data_stream_send(self, stream_id, message_rate, on_off): - ''' - - - stream_id : The ID of the requested data stream (uint8_t) - message_rate : The requested interval between two messages of this type (uint16_t) - on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) - - ''' - return self.send(self.data_stream_encode(stream_id, message_rate, on_off)) - - def manual_control_encode(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): - ''' - - - target : The system to be controlled (uint8_t) - roll : roll (float) - pitch : pitch (float) - yaw : yaw (float) - thrust : thrust (float) - roll_manual : roll control enabled auto:0, manual:1 (uint8_t) - pitch_manual : pitch auto:0, manual:1 (uint8_t) - yaw_manual : yaw auto:0, manual:1 (uint8_t) - thrust_manual : thrust auto:0, manual:1 (uint8_t) - - ''' - msg = MAVLink_manual_control_message(target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual) - msg.pack(self) - return msg - - def manual_control_send(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): - ''' - - - target : The system to be controlled (uint8_t) - roll : roll (float) - pitch : pitch (float) - yaw : yaw (float) - thrust : thrust (float) - roll_manual : roll control enabled auto:0, manual:1 (uint8_t) - pitch_manual : pitch auto:0, manual:1 (uint8_t) - yaw_manual : yaw auto:0, manual:1 (uint8_t) - thrust_manual : thrust auto:0, manual:1 (uint8_t) - - ''' - return self.send(self.manual_control_encode(target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual)) - - def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): - ''' - The RAW values of the RC channels sent to the MAV to override info - received from the RC radio. A value of -1 means no - change to that channel. A value of 0 means control of - that channel should be released back to the RC radio. - The standard PPM modulation is as follows: 1000 - microseconds: 0%, 2000 microseconds: 100%. Individual - receivers/transmitters might violate this - specification. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - - ''' - msg = MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) - msg.pack(self) - return msg - - def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): - ''' - The RAW values of the RC channels sent to the MAV to override info - received from the RC radio. A value of -1 means no - change to that channel. A value of 0 means control of - that channel should be released back to the RC radio. - The standard PPM modulation is as follows: 1000 - microseconds: 0%, 2000 microseconds: 100%. Individual - receivers/transmitters might violate this - specification. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - - ''' - return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) - - def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): - ''' - Metrics typically displayed on a HUD for fixed wing aircraft - - airspeed : Current airspeed in m/s (float) - groundspeed : Current ground speed in m/s (float) - heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) - throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) - alt : Current altitude (MSL), in meters (float) - climb : Current climb rate in meters/second (float) - - ''' - msg = MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) - msg.pack(self) - return msg - - def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): - ''' - Metrics typically displayed on a HUD for fixed wing aircraft - - airspeed : Current airspeed in m/s (float) - groundspeed : Current ground speed in m/s (float) - heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) - throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) - alt : Current altitude (MSL), in meters (float) - climb : Current climb rate in meters/second (float) - - ''' - return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) - - def command_long_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): - ''' - Send a command with up to four parameters to the MAV - - target_system : System which should execute the command (uint8_t) - target_component : Component which should execute the command, 0 for all components (uint8_t) - command : Command ID, as defined by MAV_CMD enum. (uint16_t) - confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) - param1 : Parameter 1, as defined by MAV_CMD enum. (float) - param2 : Parameter 2, as defined by MAV_CMD enum. (float) - param3 : Parameter 3, as defined by MAV_CMD enum. (float) - param4 : Parameter 4, as defined by MAV_CMD enum. (float) - param5 : Parameter 5, as defined by MAV_CMD enum. (float) - param6 : Parameter 6, as defined by MAV_CMD enum. (float) - param7 : Parameter 7, as defined by MAV_CMD enum. (float) - - ''' - msg = MAVLink_command_long_message(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7) - msg.pack(self) - return msg - - def command_long_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): - ''' - Send a command with up to four parameters to the MAV - - target_system : System which should execute the command (uint8_t) - target_component : Component which should execute the command, 0 for all components (uint8_t) - command : Command ID, as defined by MAV_CMD enum. (uint16_t) - confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) - param1 : Parameter 1, as defined by MAV_CMD enum. (float) - param2 : Parameter 2, as defined by MAV_CMD enum. (float) - param3 : Parameter 3, as defined by MAV_CMD enum. (float) - param4 : Parameter 4, as defined by MAV_CMD enum. (float) - param5 : Parameter 5, as defined by MAV_CMD enum. (float) - param6 : Parameter 6, as defined by MAV_CMD enum. (float) - param7 : Parameter 7, as defined by MAV_CMD enum. (float) - - ''' - return self.send(self.command_long_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7)) - - def command_ack_encode(self, command, result): - ''' - Report status of a command. Includes feedback wether the command was - executed - - command : Command ID, as defined by MAV_CMD enum. (uint16_t) - result : See MAV_RESULT enum (uint8_t) - - ''' - msg = MAVLink_command_ack_message(command, result) - msg.pack(self) - return msg - - def command_ack_send(self, command, result): - ''' - Report status of a command. Includes feedback wether the command was - executed - - command : Command ID, as defined by MAV_CMD enum. (uint16_t) - result : See MAV_RESULT enum (uint8_t) - - ''' - return self.send(self.command_ack_encode(command, result)) - - def hil_state_encode(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): - ''' - Sent from simulation to autopilot. This packet is useful for high - throughput applications such as - hardware in the loop simulations. - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - lat : Latitude, expressed as * 1E7 (int32_t) - lon : Longitude, expressed as * 1E7 (int32_t) - alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) - vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) - vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) - vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) - xacc : X acceleration (mg) (int16_t) - yacc : Y acceleration (mg) (int16_t) - zacc : Z acceleration (mg) (int16_t) - - ''' - msg = MAVLink_hil_state_message(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) - msg.pack(self) - return msg - - def hil_state_send(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): - ''' - Sent from simulation to autopilot. This packet is useful for high - throughput applications such as - hardware in the loop simulations. - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - lat : Latitude, expressed as * 1E7 (int32_t) - lon : Longitude, expressed as * 1E7 (int32_t) - alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) - vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) - vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) - vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) - xacc : X acceleration (mg) (int16_t) - yacc : Y acceleration (mg) (int16_t) - zacc : Z acceleration (mg) (int16_t) - - ''' - return self.send(self.hil_state_encode(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) - - def hil_controls_encode(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): - ''' - Sent from autopilot to simulation. Hardware in the loop control - outputs - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll_ailerons : Control output -1 .. 1 (float) - pitch_elevator : Control output -1 .. 1 (float) - yaw_rudder : Control output -1 .. 1 (float) - throttle : Throttle 0 .. 1 (float) - aux1 : Aux 1, -1 .. 1 (float) - aux2 : Aux 2, -1 .. 1 (float) - aux3 : Aux 3, -1 .. 1 (float) - aux4 : Aux 4, -1 .. 1 (float) - mode : System mode (MAV_MODE) (uint8_t) - nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) - - ''' - msg = MAVLink_hil_controls_message(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode) - msg.pack(self) - return msg - - def hil_controls_send(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): - ''' - Sent from autopilot to simulation. Hardware in the loop control - outputs - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll_ailerons : Control output -1 .. 1 (float) - pitch_elevator : Control output -1 .. 1 (float) - yaw_rudder : Control output -1 .. 1 (float) - throttle : Throttle 0 .. 1 (float) - aux1 : Aux 1, -1 .. 1 (float) - aux2 : Aux 2, -1 .. 1 (float) - aux3 : Aux 3, -1 .. 1 (float) - aux4 : Aux 4, -1 .. 1 (float) - mode : System mode (MAV_MODE) (uint8_t) - nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) - - ''' - return self.send(self.hil_controls_encode(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode)) - - def hil_rc_inputs_raw_encode(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): - ''' - Sent from simulation to autopilot. The RAW values of the RC channels - received. The standard PPM modulation is as follows: - 1000 microseconds: 0%, 2000 microseconds: 100%. - Individual receivers/transmitters might violate this - specification. - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - chan9_raw : RC channel 9 value, in microseconds (uint16_t) - chan10_raw : RC channel 10 value, in microseconds (uint16_t) - chan11_raw : RC channel 11 value, in microseconds (uint16_t) - chan12_raw : RC channel 12 value, in microseconds (uint16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - msg = MAVLink_hil_rc_inputs_raw_message(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi) - msg.pack(self) - return msg - - def hil_rc_inputs_raw_send(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): - ''' - Sent from simulation to autopilot. The RAW values of the RC channels - received. The standard PPM modulation is as follows: - 1000 microseconds: 0%, 2000 microseconds: 100%. - Individual receivers/transmitters might violate this - specification. - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - chan9_raw : RC channel 9 value, in microseconds (uint16_t) - chan10_raw : RC channel 10 value, in microseconds (uint16_t) - chan11_raw : RC channel 11 value, in microseconds (uint16_t) - chan12_raw : RC channel 12 value, in microseconds (uint16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - return self.send(self.hil_rc_inputs_raw_encode(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi)) - - def optical_flow_encode(self, time_usec, sensor_id, flow_x, flow_y, quality, ground_distance): - ''' - Optical flow from a flow sensor (e.g. optical mouse sensor) - - time_usec : Timestamp (UNIX) (uint64_t) - sensor_id : Sensor ID (uint8_t) - flow_x : Flow in pixels in x-sensor direction (int16_t) - flow_y : Flow in pixels in y-sensor direction (int16_t) - quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) - ground_distance : Ground distance in meters (float) - - ''' - msg = MAVLink_optical_flow_message(time_usec, sensor_id, flow_x, flow_y, quality, ground_distance) - msg.pack(self) - return msg - - def optical_flow_send(self, time_usec, sensor_id, flow_x, flow_y, quality, ground_distance): - ''' - Optical flow from a flow sensor (e.g. optical mouse sensor) - - time_usec : Timestamp (UNIX) (uint64_t) - sensor_id : Sensor ID (uint8_t) - flow_x : Flow in pixels in x-sensor direction (int16_t) - flow_y : Flow in pixels in y-sensor direction (int16_t) - quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) - ground_distance : Ground distance in meters (float) - - ''' - return self.send(self.optical_flow_encode(time_usec, sensor_id, flow_x, flow_y, quality, ground_distance)) - - def global_vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): - ''' - - - usec : Timestamp (milliseconds) (uint64_t) - x : Global X position (float) - y : Global Y position (float) - z : Global Z position (float) - roll : Roll angle in rad (float) - pitch : Pitch angle in rad (float) - yaw : Yaw angle in rad (float) - - ''' - msg = MAVLink_global_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) - msg.pack(self) - return msg - - def global_vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): - ''' - - - usec : Timestamp (milliseconds) (uint64_t) - x : Global X position (float) - y : Global Y position (float) - z : Global Z position (float) - roll : Roll angle in rad (float) - pitch : Pitch angle in rad (float) - yaw : Yaw angle in rad (float) - - ''' - return self.send(self.global_vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) - - def vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): - ''' - - - usec : Timestamp (milliseconds) (uint64_t) - x : Global X position (float) - y : Global Y position (float) - z : Global Z position (float) - roll : Roll angle in rad (float) - pitch : Pitch angle in rad (float) - yaw : Yaw angle in rad (float) - - ''' - msg = MAVLink_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) - msg.pack(self) - return msg - - def vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): - ''' - - - usec : Timestamp (milliseconds) (uint64_t) - x : Global X position (float) - y : Global Y position (float) - z : Global Z position (float) - roll : Roll angle in rad (float) - pitch : Pitch angle in rad (float) - yaw : Yaw angle in rad (float) - - ''' - return self.send(self.vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) - - def vision_speed_estimate_encode(self, usec, x, y, z): - ''' - - - usec : Timestamp (milliseconds) (uint64_t) - x : Global X speed (float) - y : Global Y speed (float) - z : Global Z speed (float) - - ''' - msg = MAVLink_vision_speed_estimate_message(usec, x, y, z) - msg.pack(self) - return msg - - def vision_speed_estimate_send(self, usec, x, y, z): - ''' - - - usec : Timestamp (milliseconds) (uint64_t) - x : Global X speed (float) - y : Global Y speed (float) - z : Global Z speed (float) - - ''' - return self.send(self.vision_speed_estimate_encode(usec, x, y, z)) - - def vicon_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): - ''' - - - usec : Timestamp (milliseconds) (uint64_t) - x : Global X position (float) - y : Global Y position (float) - z : Global Z position (float) - roll : Roll angle in rad (float) - pitch : Pitch angle in rad (float) - yaw : Yaw angle in rad (float) - - ''' - msg = MAVLink_vicon_position_estimate_message(usec, x, y, z, roll, pitch, yaw) - msg.pack(self) - return msg - - def vicon_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): - ''' - - - usec : Timestamp (milliseconds) (uint64_t) - x : Global X position (float) - y : Global Y position (float) - z : Global Z position (float) - roll : Roll angle in rad (float) - pitch : Pitch angle in rad (float) - yaw : Yaw angle in rad (float) - - ''' - return self.send(self.vicon_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) - - def memory_vect_encode(self, address, ver, type, value): - ''' - Send raw controller memory. The use of this message is discouraged for - normal packets, but a quite efficient way for testing - new messages and getting experimental debug output. - - address : Starting address of the debug variables (uint16_t) - ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) - type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) - value : Memory contents at specified address (int8_t) - - ''' - msg = MAVLink_memory_vect_message(address, ver, type, value) - msg.pack(self) - return msg - - def memory_vect_send(self, address, ver, type, value): - ''' - Send raw controller memory. The use of this message is discouraged for - normal packets, but a quite efficient way for testing - new messages and getting experimental debug output. - - address : Starting address of the debug variables (uint16_t) - ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) - type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) - value : Memory contents at specified address (int8_t) - - ''' - return self.send(self.memory_vect_encode(address, ver, type, value)) - - def debug_vect_encode(self, name, time_usec, x, y, z): - ''' - - - name : Name (char) - time_usec : Timestamp (uint64_t) - x : x (float) - y : y (float) - z : z (float) - - ''' - msg = MAVLink_debug_vect_message(name, time_usec, x, y, z) - msg.pack(self) - return msg - - def debug_vect_send(self, name, time_usec, x, y, z): - ''' - - - name : Name (char) - time_usec : Timestamp (uint64_t) - x : x (float) - y : y (float) - z : z (float) - - ''' - return self.send(self.debug_vect_encode(name, time_usec, x, y, z)) - - def named_value_float_encode(self, time_boot_ms, name, value): - ''' - Send a key-value pair as float. The use of this message is discouraged - for normal packets, but a quite efficient way for - testing new messages and getting experimental debug - output. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - name : Name of the debug variable (char) - value : Floating point value (float) - - ''' - msg = MAVLink_named_value_float_message(time_boot_ms, name, value) - msg.pack(self) - return msg - - def named_value_float_send(self, time_boot_ms, name, value): - ''' - Send a key-value pair as float. The use of this message is discouraged - for normal packets, but a quite efficient way for - testing new messages and getting experimental debug - output. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - name : Name of the debug variable (char) - value : Floating point value (float) - - ''' - return self.send(self.named_value_float_encode(time_boot_ms, name, value)) - - def named_value_int_encode(self, time_boot_ms, name, value): - ''' - Send a key-value pair as integer. The use of this message is - discouraged for normal packets, but a quite efficient - way for testing new messages and getting experimental - debug output. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - name : Name of the debug variable (char) - value : Signed integer value (int32_t) - - ''' - msg = MAVLink_named_value_int_message(time_boot_ms, name, value) - msg.pack(self) - return msg - - def named_value_int_send(self, time_boot_ms, name, value): - ''' - Send a key-value pair as integer. The use of this message is - discouraged for normal packets, but a quite efficient - way for testing new messages and getting experimental - debug output. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - name : Name of the debug variable (char) - value : Signed integer value (int32_t) - - ''' - return self.send(self.named_value_int_encode(time_boot_ms, name, value)) - - def statustext_encode(self, severity, text): - ''' - Status text message. These messages are printed in yellow in the COMM - console of QGroundControl. WARNING: They consume quite - some bandwidth, so use only for important status and - error messages. If implemented wisely, these messages - are buffered on the MCU and sent only at a limited - rate (e.g. 10 Hz). - - severity : Severity of status, 0 = info message, 255 = critical fault (uint8_t) - text : Status text message, without null termination character (char) - - ''' - msg = MAVLink_statustext_message(severity, text) - msg.pack(self) - return msg - - def statustext_send(self, severity, text): - ''' - Status text message. These messages are printed in yellow in the COMM - console of QGroundControl. WARNING: They consume quite - some bandwidth, so use only for important status and - error messages. If implemented wisely, these messages - are buffered on the MCU and sent only at a limited - rate (e.g. 10 Hz). - - severity : Severity of status, 0 = info message, 255 = critical fault (uint8_t) - text : Status text message, without null termination character (char) - - ''' - return self.send(self.statustext_encode(severity, text)) - - def debug_encode(self, time_boot_ms, ind, value): - ''' - Send a debug value. The index is used to discriminate between values. - These values show up in the plot of QGroundControl as - DEBUG N. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - ind : index of debug variable (uint8_t) - value : DEBUG value (float) - - ''' - msg = MAVLink_debug_message(time_boot_ms, ind, value) - msg.pack(self) - return msg - - def debug_send(self, time_boot_ms, ind, value): - ''' - Send a debug value. The index is used to discriminate between values. - These values show up in the plot of QGroundControl as - DEBUG N. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - ind : index of debug variable (uint8_t) - value : DEBUG value (float) - - ''' - return self.send(self.debug_encode(time_boot_ms, ind, value)) - - def extended_message_encode(self, target_system, target_component, protocol_flags): - ''' - Extended message spacer. - - target_system : System which should execute the command (uint8_t) - target_component : Component which should execute the command, 0 for all components (uint8_t) - protocol_flags : Retransmission / ACK flags (uint8_t) - - ''' - msg = MAVLink_extended_message_message(target_system, target_component, protocol_flags) - msg.pack(self) - return msg - - def extended_message_send(self, target_system, target_component, protocol_flags): - ''' - Extended message spacer. - - target_system : System which should execute the command (uint8_t) - target_component : Component which should execute the command, 0 for all components (uint8_t) - protocol_flags : Retransmission / ACK flags (uint8_t) - - ''' - return self.send(self.extended_message_encode(target_system, target_component, protocol_flags)) - diff --git a/files/mavlink_generator/generator/mavparse.py b/files/mavlink_generator/generator/mavparse.py index 23ce40ee1cb33f59648edcc33c5b258b3e9da740..cd2e6a55f87cf43d49d8d6df8d94f2d9ff1cb5ad 100644 --- a/files/mavlink_generator/generator/mavparse.py +++ b/files/mavlink_generator/generator/mavparse.py @@ -6,7 +6,7 @@ Copyright Andrew Tridgell 2011 Released under GNU GPL version 3 or later ''' -import xml.parsers.expat, os, time, sys, operator, mavutil +import xml.parsers.expat, os, errno, time, sys, operator, mavutil PROTOCOL_0_9 = "0.9" PROTOCOL_1_0 = "1.0" @@ -272,7 +272,7 @@ class MAVXML(object): self.largest_payload = m.wire_length if m.wire_length+8 > 64: - print("Warning: message %s is longer than 64 bytes long (%u bytes)" % (m.name, m.wire_length+8)) + print("Note: message %s is longer than 64 bytes long (%u bytes), which can cause fragmentation since many radio modems use 64 bytes as maximum air transfer unit." % (m.name, m.wire_length+8)) def __str__(self): return "MAVXML for %s from %s (%u message, %u enums)" % ( @@ -359,16 +359,12 @@ def total_msgs(xml): return count def mkdir_p(dir): - '''like mkdir -p''' - if not dir: - return - if dir.endswith("/"): - mkdir_p(dir[:-1]) - return - if os.path.isdir(dir): - return - mkdir_p(os.path.dirname(dir)) - os.mkdir(dir) + try: + os.makedirs(dir) + except OSError as exc: + if exc.errno == errno.EEXIST: + pass + else: raise # check version consistent # add test.xml diff --git a/files/mavlink_generator/generator/mavtestgen.py b/files/mavlink_generator/generator/mavtestgen.py index e7db2334271a213ee12ba714bf491f9390778d4b..faffa1c194ce3e6523a7397085809087e4dc7ed9 100755 --- a/files/mavlink_generator/generator/mavtestgen.py +++ b/files/mavlink_generator/generator/mavtestgen.py @@ -8,6 +8,9 @@ Released under GNU GPL version 3 or later import sys, textwrap from optparse import OptionParser + +# mavparse is up a directory level +sys.path.append('..') import mavparse def gen_value(f, i, language): @@ -62,11 +65,11 @@ Note: this file has been auto-generated. DO NOT EDIT import mavlink def generate_outputs(mav): - '''generate all message types as outputs''' + '''generate all message types as outputs''' """) for m in msgs: if m.name == "HEARTBEAT": continue - outf.write("\tmav.%s_send(" % m.name.lower()) + outf.write("\tmav.%s_send(" % m.name.lower()) for i in range(0, len(m.fields)): f = m.fields[i] outf.write("%s=%s" % (f.name, gen_value(f, i, 'py'))) @@ -90,7 +93,7 @@ static void mavtest_generate_outputs(mavlink_channel_t chan) """) for m in msgs: if m.name == "HEARTBEAT": continue - outf.write("\tmavlink_msg_%s_send(chan," % m.name.lower()) + outf.write("\tmavlink_msg_%s_send(chan," % m.name.lower()) for i in range(0, len(m.fields)): f = m.fields[i] outf.write("%s" % gen_value(f, i, 'C')) @@ -104,8 +107,8 @@ static void mavtest_generate_outputs(mavlink_channel_t chan) ###################################################################### '''main program''' -parser = OptionParser("mavtestgen.py [options] ") -parser.add_option("-o", "--output", dest="output", default="mavtest", help="output file base name") +parser = OptionParser("%prog [options] ") +parser.add_option("-o", "--output", dest="output", default="mavtest", help="output folder [default: %default]") (opts, args) = parser.parse_args() if len(args) < 1: @@ -116,9 +119,9 @@ msgs = [] enums = [] for fname in args: - (m, e) = mavparse.parse_mavlink_xml(fname) - msgs.extend(m) - enums.extend(e) + (m, e) = mavparse.parse_mavlink_xml(fname) + msgs.extend(m) + enums.extend(e) if mavparse.check_duplicates(msgs): diff --git a/files/mavlink_generator/generator/mavutil.py b/files/mavlink_generator/generator/mavutil.py deleted file mode 100644 index ab28f837082cfdfedbc13dff3b8157b87f45a9aa..0000000000000000000000000000000000000000 --- a/files/mavlink_generator/generator/mavutil.py +++ /dev/null @@ -1,658 +0,0 @@ -#!/usr/bin/env python -''' -mavlink python utility functions - -Copyright Andrew Tridgell 2011 -Released under GNU GPL version 3 or later -''' - -import socket, math, struct, time, os, fnmatch, array, sys, errno -from math import * -from mavextra import * - -if os.getenv('MAVLINK10'): - import mavlinkv10 as mavlink -else: - import mavlink - -def evaluate_expression(expression, vars): - '''evaluation an expression''' - try: - v = eval(expression, globals(), vars) - except NameError: - return None - return v - -def evaluate_condition(condition, vars): - '''evaluation a conditional (boolean) statement''' - if condition is None: - return True - v = evaluate_expression(condition, vars) - if v is None: - return False - return v - - -class mavfile(object): - '''a generic mavlink port''' - def __init__(self, fd, address, source_system=255): - self.fd = fd - self.address = address - self.messages = { 'MAV' : self } - if mavlink.WIRE_PROTOCOL_VERSION == "1.0": - self.messages['HOME'] = mavlink.MAVLink_gps_raw_int_message(0,0,0,0,0,0,0,0,0,0) - mavlink.MAVLink_waypoint_message = mavlink.MAVLink_mission_item_message - else: - self.messages['HOME'] = mavlink.MAVLink_gps_raw_message(0,0,0,0,0,0,0,0,0) - self.params = {} - self.mav = None - self.target_system = 0 - self.target_component = 0 - self.mav = mavlink.MAVLink(self, srcSystem=source_system) - self.mav.robust_parsing = True - self.logfile = None - self.logfile_raw = None - self.param_fetch_in_progress = False - self.param_fetch_complete = False - self.start_time = time.time() - self.flightmode = "UNKNOWN" - self.timestamp = 0 - self.message_hooks = [] - self.idle_hooks = [] - - def recv(self, n=None): - '''default recv method''' - raise RuntimeError('no recv() method supplied') - - def close(self, n=None): - '''default close method''' - raise RuntimeError('no close() method supplied') - - def write(self, buf): - '''default write method''' - raise RuntimeError('no write() method supplied') - - def pre_message(self): - '''default pre message call''' - return - - def post_message(self, msg): - '''default post message call''' - msg._timestamp = time.time() - type = msg.get_type() - self.messages[type] = msg - self.timestamp = msg._timestamp - if type == 'HEARTBEAT': - self.target_system = msg.get_srcSystem() - self.target_component = msg.get_srcComponent() - if mavlink.WIRE_PROTOCOL_VERSION == '1.0': - self.flightmode = mode_string_v10(msg) - elif type == 'PARAM_VALUE': - self.params[str(msg.param_id)] = msg.param_value - if msg.param_index+1 == msg.param_count: - self.param_fetch_in_progress = False - self.param_fetch_complete = True - elif type == 'SYS_STATUS' and mavlink.WIRE_PROTOCOL_VERSION == '0.9': - self.flightmode = mode_string_v09(msg) - elif type == 'GPS_RAW': - if self.messages['HOME'].fix_type < 2: - self.messages['HOME'] = msg - for hook in self.message_hooks: - hook(self, msg) - - - def recv_msg(self): - '''message receive routine''' - self.pre_message() - while True: - n = self.mav.bytes_needed() - s = self.recv(n) - if len(s) == 0 and len(self.mav.buf) == 0: - return None - if self.logfile_raw: - self.logfile_raw.write(str(s)) - msg = self.mav.parse_char(s) - if msg: - self.post_message(msg) - return msg - - def recv_match(self, condition=None, type=None, blocking=False): - '''recv the next MAVLink message that matches the given condition''' - while True: - m = self.recv_msg() - if m is None: - if blocking: - for hook in self.idle_hooks: - hook(self) - time.sleep(0.01) - continue - return None - if type is not None and type != m.get_type(): - continue - if not evaluate_condition(condition, self.messages): - continue - return m - - def setup_logfile(self, logfile, mode='w'): - '''start logging to the given logfile, with timestamps''' - self.logfile = open(logfile, mode=mode) - - def setup_logfile_raw(self, logfile, mode='w'): - '''start logging raw bytes to the given logfile, without timestamps''' - self.logfile_raw = open(logfile, mode=mode) - - def wait_heartbeat(self, blocking=True): - '''wait for a heartbeat so we know the target system IDs''' - return self.recv_match(type='HEARTBEAT', blocking=blocking) - - def param_fetch_all(self): - '''initiate fetch of all parameters''' - if time.time() - getattr(self, 'param_fetch_start', 0) < 2.0: - # don't fetch too often - return - self.param_fetch_start = time.time() - self.param_fetch_in_progress = True - self.mav.param_request_list_send(self.target_system, self.target_component) - - def time_since(self, mtype): - '''return the time since the last message of type mtype was received''' - if not mtype in self.messages: - return time.time() - self.start_time - return time.time() - self.messages[mtype]._timestamp - - def param_set_send(self, parm_name, parm_value, parm_type=None): - '''wrapper for parameter set''' - if mavlink.WIRE_PROTOCOL_VERSION == '1.0': - if parm_type == None: - parm_type = mavlink.MAV_VAR_FLOAT - self.mav.param_set_send(self.target_system, self.target_component, - parm_name, parm_value, parm_type) - else: - self.mav.param_set_send(self.target_system, self.target_component, - parm_name, parm_value) - - def waypoint_request_list_send(self): - '''wrapper for waypoint_request_list_send''' - if mavlink.WIRE_PROTOCOL_VERSION == '1.0': - self.mav.mission_request_list_send(self.target_system, self.target_component) - else: - self.mav.waypoint_request_list_send(self.target_system, self.target_component) - - def waypoint_clear_all_send(self): - '''wrapper for waypoint_clear_all_send''' - if mavlink.WIRE_PROTOCOL_VERSION == '1.0': - self.mav.mission_clear_all_send(self.target_system, self.target_component) - else: - self.mav.waypoint_clear_all_send(self.target_system, self.target_component) - - def waypoint_request_send(self, seq): - '''wrapper for waypoint_request_send''' - if mavlink.WIRE_PROTOCOL_VERSION == '1.0': - self.mav.mission_request_send(self.target_system, self.target_component, seq) - else: - self.mav.waypoint_request_send(self.target_system, self.target_component, seq) - - def waypoint_set_current_send(self, seq): - '''wrapper for waypoint_set_current_send''' - if mavlink.WIRE_PROTOCOL_VERSION == '1.0': - self.mav.mission_set_current_send(self.target_system, self.target_component, seq) - else: - self.mav.waypoint_set_current_send(self.target_system, self.target_component, seq) - - def waypoint_count_send(self, seq): - '''wrapper for waypoint_count_send''' - if mavlink.WIRE_PROTOCOL_VERSION == '1.0': - self.mav.mission_count_send(self.target_system, self.target_component, seq) - else: - self.mav.waypoint_count_send(self.target_system, self.target_component, seq) - - -class mavserial(mavfile): - '''a serial mavlink port''' - def __init__(self, device, baud=115200, autoreconnect=False, source_system=255): - import serial - self.baud = baud - self.device = device - self.autoreconnect = autoreconnect - self.port = serial.Serial(self.device, self.baud, timeout=0, - dsrdtr=False, rtscts=False, xonxoff=False) - - try: - fd = self.port.fileno() - except Exception: - fd = None - mavfile.__init__(self, fd, device, source_system=source_system) - - def close(self): - self.port.close() - - def recv(self,n=None): - if n is None: - n = self.mav.bytes_needed() - if self.fd is None: - waiting = self.port.inWaiting() - if waiting < n: - n = waiting - return self.port.read(n) - - def write(self, buf): - try: - return self.port.write(buf) - except OSError: - if self.autoreconnect: - self.reset() - return -1 - - def reset(self): - import serial - self.port.close() - while True: - try: - self.port = serial.Serial(self.device, self.baud, timeout=1, - dsrdtr=False, rtscts=False, xonxoff=False) - try: - self.fd = self.port.fileno() - except Exception: - self.fd = None - return - except Exception: - print("Failed to reopen %s" % self.device) - time.sleep(1) - - -class mavudp(mavfile): - '''a UDP mavlink socket''' - def __init__(self, device, input=True, source_system=255): - a = device.split(':') - if len(a) != 2: - print("UDP ports must be specified as host:port") - sys.exit(1) - self.port = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) - self.udp_server = input - if input: - self.port.bind((a[0], int(a[1]))) - else: - self.destination_addr = (a[0], int(a[1])) - self.port.setblocking(0) - self.last_address = None - mavfile.__init__(self, self.port.fileno(), device, source_system=source_system) - - def close(self): - self.port.close() - - def recv(self,n=None): - try: - data, self.last_address = self.port.recvfrom(300) - except socket.error as e: - if e.errno in [ errno.EAGAIN, errno.EWOULDBLOCK ]: - return "" - raise - return data - - def write(self, buf): - try: - if self.udp_server: - if self.last_address: - self.port.sendto(buf, self.last_address) - else: - self.port.sendto(buf, self.destination_addr) - except socket.error: - pass - - def recv_msg(self): - '''message receive routine for UDP link''' - self.pre_message() - s = self.recv() - if len(s) == 0: - return None - msg = self.mav.parse_buffer(s) - if msg is not None: - for m in msg: - self.post_message(m) - return msg[0] - return None - - -class mavtcp(mavfile): - '''a TCP mavlink socket''' - def __init__(self, device, source_system=255): - a = device.split(':') - if len(a) != 2: - print("TCP ports must be specified as host:port") - sys.exit(1) - self.port = socket.socket(socket.AF_INET, socket.SOCK_STREAM) - self.destination_addr = (a[0], int(a[1])) - self.port.connect(self.destination_addr) - self.port.setblocking(0) - self.port.setsockopt(socket.SOL_TCP, socket.TCP_NODELAY, 1) - mavfile.__init__(self, self.port.fileno(), device, source_system=source_system) - - def close(self): - self.port.close() - - def recv(self,n=None): - if n is None: - n = self.mav.bytes_needed() - try: - data = self.port.recv(n) - except socket.error as e: - if e.errno in [ errno.EAGAIN, errno.EWOULDBLOCK ]: - return "" - raise - return data - - def write(self, buf): - try: - self.port.send(buf) - except socket.error: - pass - - -class mavlogfile(mavfile): - '''a MAVLink logfile reader/writer''' - def __init__(self, filename, planner_format=None, - write=False, append=False, - robust_parsing=True, notimestamps=False, source_system=255): - self.filename = filename - self.writeable = write - self.robust_parsing = robust_parsing - self.planner_format = planner_format - self.notimestamps = notimestamps - self._two64 = math.pow(2.0, 63) - mode = 'rb' - if self.writeable: - if append: - mode = 'ab' - else: - mode = 'wb' - self.f = open(filename, mode) - mavfile.__init__(self, None, filename, source_system=source_system) - - def close(self): - self.f.close() - - def recv(self,n=None): - if n is None: - n = self.mav.bytes_needed() - return self.f.read(n) - - def write(self, buf): - self.f.write(buf) - - def pre_message(self): - '''read timestamp if needed''' - # read the timestamp - if self.notimestamps: - return - if self.planner_format: - tbuf = self.f.read(21) - if len(tbuf) != 21 or tbuf[0] != '-' or tbuf[20] != ':': - raise RuntimeError('bad planner timestamp %s' % tbuf) - hnsec = self._two64 + float(tbuf[0:20]) - t = hnsec * 1.0e-7 # convert to seconds - t -= 719163 * 24 * 60 * 60 # convert to 1970 base - else: - tbuf = self.f.read(8) - if len(tbuf) != 8: - return - (tusec,) = struct.unpack('>Q', tbuf) - t = tusec * 1.0e-6 - self._timestamp = t - - def post_message(self, msg): - '''add timestamp to message''' - # read the timestamp - super(mavlogfile, self).post_message(msg) - if self.notimestamps: - msg._timestamp = time.time() - else: - msg._timestamp = self._timestamp - if self.planner_format: - self.f.read(1) # trailing newline - self.timestamp = msg._timestamp - -class mavchildexec(mavfile): - '''a MAVLink child processes reader/writer''' - def __init__(self, filename, source_system=255): - from subprocess import Popen, PIPE - import fcntl - - self.filename = filename - self.child = Popen(filename, shell=True, stdout=PIPE, stdin=PIPE) - self.fd = self.child.stdout.fileno() - - fl = fcntl.fcntl(self.fd, fcntl.F_GETFL) - fcntl.fcntl(self.fd, fcntl.F_SETFL, fl | os.O_NONBLOCK) - - fl = fcntl.fcntl(self.child.stdout.fileno(), fcntl.F_GETFL) - fcntl.fcntl(self.child.stdout.fileno(), fcntl.F_SETFL, fl | os.O_NONBLOCK) - - mavfile.__init__(self, self.fd, filename, source_system=source_system) - - def close(self): - self.child.close() - - def recv(self,n=None): - try: - x = self.child.stdout.read(1) - except Exception: - return '' - return x - - def write(self, buf): - self.child.stdin.write(buf) - - -def mavlink_connection(device, baud=115200, source_system=255, - planner_format=None, write=False, append=False, - robust_parsing=True, notimestamps=False, input=True): - '''make a serial or UDP mavlink connection''' - if device.startswith('tcp:'): - return mavtcp(device[4:], source_system=source_system) - if device.startswith('udp:'): - return mavudp(device[4:], input=input, source_system=source_system) - if device.find(':') != -1 and not device.endswith('log'): - return mavudp(device, source_system=source_system, input=input) - if os.path.isfile(device): - if device.endswith(".elf"): - return mavchildexec(device, source_system=source_system) - else: - return mavlogfile(device, planner_format=planner_format, write=write, - append=append, robust_parsing=robust_parsing, notimestamps=notimestamps, - source_system=source_system) - return mavserial(device, baud=baud, source_system=source_system) - -class periodic_event(object): - '''a class for fixed frequency events''' - def __init__(self, frequency): - self.frequency = float(frequency) - self.last_time = time.time() - def trigger(self): - '''return True if we should trigger now''' - tnow = time.time() - if self.last_time + (1.0/self.frequency) <= tnow: - self.last_time = tnow - return True - return False - - -try: - from curses import ascii - have_ascii = True -except: - have_ascii = False - -def is_printable(c): - '''see if a character is printable''' - global have_ascii - if have_ascii: - return ascii.isprint(c) - if isinstance(c, int): - ic = c - else: - ic = ord(c) - return ic >= 32 and ic <= 126 - -def all_printable(buf): - '''see if a string is all printable''' - for c in buf: - if not is_printable(c) and not c in ['\r', '\n', '\t']: - return False - return True - -class SerialPort(object): - '''auto-detected serial port''' - def __init__(self, device, description=None, hwid=None): - self.device = device - self.description = description - self.hwid = hwid - - def __str__(self): - ret = self.device - if self.description is not None: - ret += " : " + self.description - if self.hwid is not None: - ret += " : " + self.hwid - return ret - -def auto_detect_serial_win32(preferred_list=['*']): - '''try to auto-detect serial ports on win32''' - try: - import scanwin32 - list = sorted(scanwin32.comports()) - except: - return [] - ret = [] - for order, port, desc, hwid in list: - for preferred in preferred_list: - if fnmatch.fnmatch(desc, preferred) or fnmatch.fnmatch(hwid, preferred): - ret.append(SerialPort(port, description=desc, hwid=hwid)) - if len(ret) > 0: - return ret - # now the rest - for order, port, desc, hwid in list: - ret.append(SerialPort(port, description=desc, hwid=hwid)) - return ret - - - - -def auto_detect_serial_unix(preferred_list=['*']): - '''try to auto-detect serial ports on win32''' - import glob - glist = glob.glob('/dev/ttyS*') + glob.glob('/dev/ttyUSB*') + glob.glob('/dev/ttyACM*') + glob.glob('/dev/serial/by-id/*') - ret = [] - # try preferred ones first - for d in glist: - for preferred in preferred_list: - if fnmatch.fnmatch(d, preferred): - ret.append(SerialPort(d)) - if len(ret) > 0: - return ret - # now the rest - for d in glist: - ret.append(SerialPort(d)) - return ret - - - -def auto_detect_serial(preferred_list=['*']): - '''try to auto-detect serial port''' - # see if - if os.name == 'nt': - return auto_detect_serial_win32(preferred_list=preferred_list) - return auto_detect_serial_unix(preferred_list=preferred_list) - -def mode_string_v09(msg): - '''mode string for 0.9 protocol''' - mode = msg.mode - nav_mode = msg.nav_mode - - MAV_MODE_UNINIT = 0 - MAV_MODE_MANUAL = 2 - MAV_MODE_GUIDED = 3 - MAV_MODE_AUTO = 4 - MAV_MODE_TEST1 = 5 - MAV_MODE_TEST2 = 6 - MAV_MODE_TEST3 = 7 - - MAV_NAV_GROUNDED = 0 - MAV_NAV_LIFTOFF = 1 - MAV_NAV_HOLD = 2 - MAV_NAV_WAYPOINT = 3 - MAV_NAV_VECTOR = 4 - MAV_NAV_RETURNING = 5 - MAV_NAV_LANDING = 6 - MAV_NAV_LOST = 7 - MAV_NAV_LOITER = 8 - - cmode = (mode, nav_mode) - mapping = { - (MAV_MODE_UNINIT, MAV_NAV_GROUNDED) : "INITIALISING", - (MAV_MODE_MANUAL, MAV_NAV_VECTOR) : "MANUAL", - (MAV_MODE_TEST3, MAV_NAV_VECTOR) : "CIRCLE", - (MAV_MODE_GUIDED, MAV_NAV_VECTOR) : "GUIDED", - (MAV_MODE_TEST1, MAV_NAV_VECTOR) : "STABILIZE", - (MAV_MODE_TEST2, MAV_NAV_LIFTOFF) : "FBWA", - (MAV_MODE_AUTO, MAV_NAV_WAYPOINT) : "AUTO", - (MAV_MODE_AUTO, MAV_NAV_RETURNING) : "RTL", - (MAV_MODE_AUTO, MAV_NAV_LOITER) : "LOITER", - (MAV_MODE_AUTO, MAV_NAV_LIFTOFF) : "TAKEOFF", - (MAV_MODE_AUTO, MAV_NAV_LANDING) : "LANDING", - (MAV_MODE_AUTO, MAV_NAV_HOLD) : "LOITER", - (MAV_MODE_GUIDED, MAV_NAV_VECTOR) : "GUIDED", - (100, MAV_NAV_VECTOR) : "STABILIZE", - (101, MAV_NAV_VECTOR) : "ACRO", - (102, MAV_NAV_VECTOR) : "ALT_HOLD", - (107, MAV_NAV_VECTOR) : "CIRCLE", - (109, MAV_NAV_VECTOR) : "LAND", - } - if cmode in mapping: - return mapping[cmode] - return "Mode(%s,%s)" % cmode - -def mode_string_v10(msg): - '''mode string for 1.0 protocol, from heartbeat''' - if not msg.base_mode & mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED: - return "Mode(0x%08x)" % msg.base_mode - mapping = { - 0 : 'MANUAL', - 1 : 'CIRCLE', - 2 : 'STABILIZE', - 5 : 'FBWA', - 6 : 'FBWB', - 7 : 'FBWC', - 10 : 'AUTO', - 11 : 'RTL', - 12 : 'LOITER', - 13 : 'TAKEOFF', - 14 : 'LAND', - 15 : 'GUIDED', - 16 : 'INITIALISING' - } - if msg.custom_mode in mapping: - return mapping[msg.custom_mode] - return "Mode(%u)" % msg.custom_mode - - - -class x25crc(object): - '''x25 CRC - based on checksum.h from mavlink library''' - def __init__(self, buf=''): - self.crc = 0xffff - self.accumulate(buf) - - def accumulate(self, buf): - '''add in some more bytes''' - bytes = array.array('B') - if isinstance(buf, array.array): - bytes.extend(buf) - else: - bytes.fromstring(buf) - accum = self.crc - for b in bytes: - tmp = b ^ (accum & 0xff) - tmp = (tmp ^ (tmp<<4)) & 0xFF - accum = (accum>>8) ^ (tmp<<8) ^ (tmp<<3) ^ (tmp>>4) - accum = accum & 0xFFFF - self.crc = accum diff --git a/files/mavlink_generator/generator/mavwp.py b/files/mavlink_generator/generator/mavwp.py deleted file mode 100644 index 6fd1e10e2bffb74b3ed565f5af1f42897a9087b7..0000000000000000000000000000000000000000 --- a/files/mavlink_generator/generator/mavwp.py +++ /dev/null @@ -1,200 +0,0 @@ -''' -module for loading/saving waypoints -''' - -import os - -if os.getenv('MAVLINK10'): - import mavlinkv10 as mavlink -else: - import mavlink - -class MAVWPError(Exception): - '''MAVLink WP error class''' - def __init__(self, msg): - Exception.__init__(self, msg) - self.message = msg - -class MAVWPLoader(object): - '''MAVLink waypoint loader''' - def __init__(self, target_system=0, target_component=0): - self.wpoints = [] - self.target_system = target_system - self.target_component = target_component - - - def count(self): - '''return number of waypoints''' - return len(self.wpoints) - - def wp(self, i): - '''return a waypoint''' - return self.wpoints[i] - - def add(self, w): - '''add a waypoint''' - w.seq = self.count() - self.wpoints.append(w) - - def remove(self, w): - '''remove a waypoint''' - self.wpoints.remove(w) - - def clear(self): - '''clear waypoint list''' - self.wpoints = [] - - def _read_waypoint_v100(self, line): - '''read a version 100 waypoint''' - cmdmap = { - 2 : mavlink.MAV_CMD_NAV_TAKEOFF, - 3 : mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, - 4 : mavlink.MAV_CMD_NAV_LAND, - 24: mavlink.MAV_CMD_NAV_TAKEOFF, - 26: mavlink.MAV_CMD_NAV_LAND, - 25: mavlink.MAV_CMD_NAV_WAYPOINT , - 27: mavlink.MAV_CMD_NAV_LOITER_UNLIM - } - a = line.split() - if len(a) != 13: - raise MAVWPError("invalid waypoint line with %u values" % len(a)) - w = mavlink.MAVLink_waypoint_message(self.target_system, self.target_component, - int(a[0]), # seq - int(a[1]), # frame - int(a[2]), # action - int(a[7]), # current - int(a[12]), # autocontinue - float(a[5]), # param1, - float(a[6]), # param2, - float(a[3]), # param3 - float(a[4]), # param4 - float(a[9]), # x, latitude - float(a[8]), # y, longitude - float(a[10]) # z - ) - if not w.command in cmdmap: - raise MAVWPError("Unknown v100 waypoint action %u" % w.command) - - w.command = cmdmap[w.command] - return w - - def _read_waypoint_v110(self, line): - '''read a version 110 waypoint''' - a = line.split() - if len(a) != 12: - raise MAVWPError("invalid waypoint line with %u values" % len(a)) - w = mavlink.MAVLink_waypoint_message(self.target_system, self.target_component, - int(a[0]), # seq - int(a[2]), # frame - int(a[3]), # command - int(a[1]), # current - int(a[11]), # autocontinue - float(a[4]), # param1, - float(a[5]), # param2, - float(a[6]), # param3 - float(a[7]), # param4 - float(a[8]), # x (latitude) - float(a[9]), # y (longitude) - float(a[10]) # z (altitude) - ) - return w - - - def load(self, filename): - '''load waypoints from a file. - returns number of waypoints loaded''' - f = open(filename, mode='r') - version_line = f.readline().strip() - if version_line == "QGC WPL 100": - readfn = self._read_waypoint_v100 - elif version_line == "QGC WPL 110": - readfn = self._read_waypoint_v110 - else: - f.close() - raise MAVWPError("Unsupported waypoint format '%s'" % version_line) - - self.clear() - - for line in f: - if line.startswith('#'): - continue - line = line.strip() - if not line: - continue - w = readfn(line) - if w is not None: - self.add(w) - f.close() - return len(self.wpoints) - - - def save(self, filename): - '''save waypoints to a file''' - f = open(filename, mode='w') - f.write("QGC WPL 110\n") - for w in self.wpoints: - f.write("%u\t%u\t%u\t%u\t%f\t%f\t%f\t%f\t%f\t%f\t%f\t%u\n" % ( - w.seq, w.current, w.frame, w.command, - w.param1, w.param2, w.param3, w.param4, - w.x, w.y, w.z, w.autocontinue)) - f.close() - - -class MAVFenceError(Exception): - '''MAVLink fence error class''' - def __init__(self, msg): - Exception.__init__(self, msg) - self.message = msg - -class MAVFenceLoader(object): - '''MAVLink geo-fence loader''' - def __init__(self, target_system=0, target_component=0): - self.points = [] - self.target_system = target_system - self.target_component = target_component - - def count(self): - '''return number of points''' - return len(self.points) - - def point(self, i): - '''return a point''' - return self.points[i] - - def add(self, p): - '''add a point''' - self.points.append(p) - - def clear(self): - '''clear point list''' - self.points = [] - - def load(self, filename): - '''load points from a file. - returns number of points loaded''' - f = open(filename, mode='r') - self.clear() - for line in f: - if line.startswith('#'): - continue - line = line.strip() - if not line: - continue - a = line.split() - if len(a) != 2: - raise MAVFenceError("invalid fence point line: %s" % line) - p = mavlink.MAVLink_fence_point_message(self.target_system, self.target_component, - self.count(), 0, float(a[0]), float(a[1])) - self.add(p) - f.close() - for i in range(self.count()): - self.points[i].count = self.count() - return len(self.points) - - - def save(self, filename): - '''save fence points to a file''' - f = open(filename, mode='w') - for p in self.points: - f.write("%f\t%f\n" % (p.lat, p.lng)) - f.close() diff --git a/files/mavlink_generator/generator/pyexpat.pyd b/files/mavlink_generator/generator/pyexpat.pyd deleted file mode 100644 index 03c607001ccfa956e83f38fcab4edc5eab33899b..0000000000000000000000000000000000000000 Binary files a/files/mavlink_generator/generator/pyexpat.pyd and /dev/null differ diff --git a/files/mavlink_generator/generator/python27.dll b/files/mavlink_generator/generator/python27.dll deleted file mode 100644 index 9b03b95e80bf87624389f3c348fcfbfd43d8db8e..0000000000000000000000000000000000000000 Binary files a/files/mavlink_generator/generator/python27.dll and /dev/null differ diff --git a/files/mavlink_generator/generator/scanwin32.py b/files/mavlink_generator/generator/scanwin32.py deleted file mode 100644 index f90ed5f4d8f4dae890ecaf9d8e6bfeb9869810ed..0000000000000000000000000000000000000000 --- a/files/mavlink_generator/generator/scanwin32.py +++ /dev/null @@ -1,236 +0,0 @@ -#!/usr/bin/env python - -# this is taken from the pySerial documentation at -# http://pyserial.sourceforge.net/examples.html -import ctypes -import re - -def ValidHandle(value): - if value == 0: - raise ctypes.WinError() - return value - -NULL = 0 -HDEVINFO = ctypes.c_int -BOOL = ctypes.c_int -CHAR = ctypes.c_char -PCTSTR = ctypes.c_char_p -HWND = ctypes.c_uint -DWORD = ctypes.c_ulong -PDWORD = ctypes.POINTER(DWORD) -ULONG = ctypes.c_ulong -ULONG_PTR = ctypes.POINTER(ULONG) -#~ PBYTE = ctypes.c_char_p -PBYTE = ctypes.c_void_p - -class GUID(ctypes.Structure): - _fields_ = [ - ('Data1', ctypes.c_ulong), - ('Data2', ctypes.c_ushort), - ('Data3', ctypes.c_ushort), - ('Data4', ctypes.c_ubyte*8), - ] - def __str__(self): - return "{%08x-%04x-%04x-%s-%s}" % ( - self.Data1, - self.Data2, - self.Data3, - ''.join(["%02x" % d for d in self.Data4[:2]]), - ''.join(["%02x" % d for d in self.Data4[2:]]), - ) - -class SP_DEVINFO_DATA(ctypes.Structure): - _fields_ = [ - ('cbSize', DWORD), - ('ClassGuid', GUID), - ('DevInst', DWORD), - ('Reserved', ULONG_PTR), - ] - def __str__(self): - return "ClassGuid:%s DevInst:%s" % (self.ClassGuid, self.DevInst) -PSP_DEVINFO_DATA = ctypes.POINTER(SP_DEVINFO_DATA) - -class SP_DEVICE_INTERFACE_DATA(ctypes.Structure): - _fields_ = [ - ('cbSize', DWORD), - ('InterfaceClassGuid', GUID), - ('Flags', DWORD), - ('Reserved', ULONG_PTR), - ] - def __str__(self): - return "InterfaceClassGuid:%s Flags:%s" % (self.InterfaceClassGuid, self.Flags) - -PSP_DEVICE_INTERFACE_DATA = ctypes.POINTER(SP_DEVICE_INTERFACE_DATA) - -PSP_DEVICE_INTERFACE_DETAIL_DATA = ctypes.c_void_p - -class dummy(ctypes.Structure): - _fields_=[("d1", DWORD), ("d2", CHAR)] - _pack_ = 1 -SIZEOF_SP_DEVICE_INTERFACE_DETAIL_DATA_A = ctypes.sizeof(dummy) - -SetupDiDestroyDeviceInfoList = ctypes.windll.setupapi.SetupDiDestroyDeviceInfoList -SetupDiDestroyDeviceInfoList.argtypes = [HDEVINFO] -SetupDiDestroyDeviceInfoList.restype = BOOL - -SetupDiGetClassDevs = ctypes.windll.setupapi.SetupDiGetClassDevsA -SetupDiGetClassDevs.argtypes = [ctypes.POINTER(GUID), PCTSTR, HWND, DWORD] -SetupDiGetClassDevs.restype = ValidHandle # HDEVINFO - -SetupDiEnumDeviceInterfaces = ctypes.windll.setupapi.SetupDiEnumDeviceInterfaces -SetupDiEnumDeviceInterfaces.argtypes = [HDEVINFO, PSP_DEVINFO_DATA, ctypes.POINTER(GUID), DWORD, PSP_DEVICE_INTERFACE_DATA] -SetupDiEnumDeviceInterfaces.restype = BOOL - -SetupDiGetDeviceInterfaceDetail = ctypes.windll.setupapi.SetupDiGetDeviceInterfaceDetailA -SetupDiGetDeviceInterfaceDetail.argtypes = [HDEVINFO, PSP_DEVICE_INTERFACE_DATA, PSP_DEVICE_INTERFACE_DETAIL_DATA, DWORD, PDWORD, PSP_DEVINFO_DATA] -SetupDiGetDeviceInterfaceDetail.restype = BOOL - -SetupDiGetDeviceRegistryProperty = ctypes.windll.setupapi.SetupDiGetDeviceRegistryPropertyA -SetupDiGetDeviceRegistryProperty.argtypes = [HDEVINFO, PSP_DEVINFO_DATA, DWORD, PDWORD, PBYTE, DWORD, PDWORD] -SetupDiGetDeviceRegistryProperty.restype = BOOL - - -GUID_CLASS_COMPORT = GUID(0x86e0d1e0L, 0x8089, 0x11d0, - (ctypes.c_ubyte*8)(0x9c, 0xe4, 0x08, 0x00, 0x3e, 0x30, 0x1f, 0x73)) - -DIGCF_PRESENT = 2 -DIGCF_DEVICEINTERFACE = 16 -INVALID_HANDLE_VALUE = 0 -ERROR_INSUFFICIENT_BUFFER = 122 -SPDRP_HARDWAREID = 1 -SPDRP_FRIENDLYNAME = 12 -SPDRP_LOCATION_INFORMATION = 13 -ERROR_NO_MORE_ITEMS = 259 - -def comports(available_only=True): - """This generator scans the device registry for com ports and yields - (order, port, desc, hwid). If available_only is true only return currently - existing ports. Order is a helper to get sorted lists. it can be ignored - otherwise.""" - flags = DIGCF_DEVICEINTERFACE - if available_only: - flags |= DIGCF_PRESENT - g_hdi = SetupDiGetClassDevs(ctypes.byref(GUID_CLASS_COMPORT), None, NULL, flags); - #~ for i in range(256): - for dwIndex in range(256): - did = SP_DEVICE_INTERFACE_DATA() - did.cbSize = ctypes.sizeof(did) - - if not SetupDiEnumDeviceInterfaces( - g_hdi, - None, - ctypes.byref(GUID_CLASS_COMPORT), - dwIndex, - ctypes.byref(did) - ): - if ctypes.GetLastError() != ERROR_NO_MORE_ITEMS: - raise ctypes.WinError() - break - - dwNeeded = DWORD() - # get the size - if not SetupDiGetDeviceInterfaceDetail( - g_hdi, - ctypes.byref(did), - None, 0, ctypes.byref(dwNeeded), - None - ): - # Ignore ERROR_INSUFFICIENT_BUFFER - if ctypes.GetLastError() != ERROR_INSUFFICIENT_BUFFER: - raise ctypes.WinError() - # allocate buffer - class SP_DEVICE_INTERFACE_DETAIL_DATA_A(ctypes.Structure): - _fields_ = [ - ('cbSize', DWORD), - ('DevicePath', CHAR*(dwNeeded.value - ctypes.sizeof(DWORD))), - ] - def __str__(self): - return "DevicePath:%s" % (self.DevicePath,) - idd = SP_DEVICE_INTERFACE_DETAIL_DATA_A() - idd.cbSize = SIZEOF_SP_DEVICE_INTERFACE_DETAIL_DATA_A - devinfo = SP_DEVINFO_DATA() - devinfo.cbSize = ctypes.sizeof(devinfo) - if not SetupDiGetDeviceInterfaceDetail( - g_hdi, - ctypes.byref(did), - ctypes.byref(idd), dwNeeded, None, - ctypes.byref(devinfo) - ): - raise ctypes.WinError() - - # hardware ID - szHardwareID = ctypes.create_string_buffer(250) - if not SetupDiGetDeviceRegistryProperty( - g_hdi, - ctypes.byref(devinfo), - SPDRP_HARDWAREID, - None, - ctypes.byref(szHardwareID), ctypes.sizeof(szHardwareID) - 1, - None - ): - # Ignore ERROR_INSUFFICIENT_BUFFER - if ctypes.GetLastError() != ERROR_INSUFFICIENT_BUFFER: - raise ctypes.WinError() - - # friendly name - szFriendlyName = ctypes.create_string_buffer(1024) - if not SetupDiGetDeviceRegistryProperty( - g_hdi, - ctypes.byref(devinfo), - SPDRP_FRIENDLYNAME, - None, - ctypes.byref(szFriendlyName), ctypes.sizeof(szFriendlyName) - 1, - None - ): - # Ignore ERROR_INSUFFICIENT_BUFFER - if ctypes.GetLastError() != ERROR_INSUFFICIENT_BUFFER: - #~ raise ctypes.WinError() - # not getting friendly name for com0com devices, try something else - szFriendlyName = ctypes.create_string_buffer(1024) - if SetupDiGetDeviceRegistryProperty( - g_hdi, - ctypes.byref(devinfo), - SPDRP_LOCATION_INFORMATION, - None, - ctypes.byref(szFriendlyName), ctypes.sizeof(szFriendlyName) - 1, - None - ): - port_name = "\\\\.\\" + szFriendlyName.value - order = None - else: - port_name = szFriendlyName.value - order = None - else: - try: - m = re.search(r"\((.*?(\d+))\)", szFriendlyName.value) - #~ print szFriendlyName.value, m.groups() - port_name = m.group(1) - order = int(m.group(2)) - except AttributeError, msg: - port_name = szFriendlyName.value - order = None - yield order, port_name, szFriendlyName.value, szHardwareID.value - - SetupDiDestroyDeviceInfoList(g_hdi) - - -if __name__ == '__main__': - import serial - print "-"*78 - print "Serial ports" - print "-"*78 - for order, port, desc, hwid in sorted(comports()): - print "%-10s: %s (%s) ->" % (port, desc, hwid), - try: - serial.Serial(port) # test open - except serial.serialutil.SerialException: - print "can't be openend" - else: - print "Ready" - print - # list of all ports the system knows - print "-"*78 - print "All serial ports (registry)" - print "-"*78 - for order, port, desc, hwid in sorted(comports(False)): - print "%-10s: %s (%s)" % (port, desc, hwid) diff --git a/files/mavlink_generator/generator/select.pyd b/files/mavlink_generator/generator/select.pyd deleted file mode 100644 index e1b0ec2c49f1108286fcd941a922070976c0e9ab..0000000000000000000000000000000000000000 Binary files a/files/mavlink_generator/generator/select.pyd and /dev/null differ diff --git a/files/mavlink_generator/generator/unicodedata.pyd b/files/mavlink_generator/generator/unicodedata.pyd deleted file mode 100644 index a5c460d6fb27d2c938ea4b3c7401ed2358e14e3a..0000000000000000000000000000000000000000 Binary files a/files/mavlink_generator/generator/unicodedata.pyd and /dev/null differ diff --git a/files/mavlink_generator/generator/w9xpopen.exe b/files/mavlink_generator/generator/w9xpopen.exe deleted file mode 100644 index f6033fdeaaaf14dc80579adeb1a8827f08d1de4f..0000000000000000000000000000000000000000 Binary files a/files/mavlink_generator/generator/w9xpopen.exe and /dev/null differ diff --git a/mavlink/include/v0.9/ardupilotmega/ardupilotmega.h b/mavlink/include/mavlink/v0.9/ardupilotmega/ardupilotmega.h similarity index 54% rename from mavlink/include/v0.9/ardupilotmega/ardupilotmega.h rename to mavlink/include/mavlink/v0.9/ardupilotmega/ardupilotmega.h index 99a5b60d8e759d1cf6fdbf444651988d43545b8a..4148b5a6a954f29ebaf3cdb77b406bea41364c21 100644 --- a/mavlink/include/v0.9/ardupilotmega/ardupilotmega.h +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/ardupilotmega.h @@ -12,15 +12,15 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5} +#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 3, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 118, 242, 19, 97, 233, 0, 18, 68, 136, 205, 42, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7} +#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 118, 242, 19, 97, 233, 0, 18, 68, 136, 127, 42, 21, 93, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7} #endif #ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_BOOT, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, MAVLINK_MESSAGE_INFO_ACTION_ACK, MAVLINK_MESSAGE_INFO_ACTION, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_SET_NAV_MODE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, {NULL}, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_LOCAL_POSITION, MAVLINK_MESSAGE_INFO_GPS_RAW, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_WAYPOINT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST, MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT, MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL, MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED, MAVLINK_MESSAGE_INFO_WAYPOINT_ACK, MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_CONTROL_STATUS, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_POSITION_TARGET, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_SET_ALTITUDE, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {NULL}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_DCM, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG} +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_BOOT, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACTION_ACK, MAVLINK_MESSAGE_INFO_ACTION, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_SET_NAV_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_LOCAL_POSITION, MAVLINK_MESSAGE_INFO_GPS_RAW, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_WAYPOINT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST, MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT, MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL, MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED, MAVLINK_MESSAGE_INFO_WAYPOINT_ACK, MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_CONTROL_STATUS, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_POSITION_TARGET, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_SET_ALTITUDE, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG} #endif #include "../protocol.h" @@ -143,9 +143,10 @@ enum FENCE_BREACH #include "./mavlink_msg_fence_point.h" #include "./mavlink_msg_fence_fetch_point.h" #include "./mavlink_msg_fence_status.h" -#include "./mavlink_msg_dcm.h" +#include "./mavlink_msg_ahrs.h" #include "./mavlink_msg_simstate.h" #include "./mavlink_msg_hwstatus.h" +#include "./mavlink_msg_radio.h" #ifdef __cplusplus } diff --git a/mavlink/include/v0.9/ardupilotmega/mavlink.h b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink.h similarity index 100% rename from mavlink/include/v0.9/ardupilotmega/mavlink.h rename to mavlink/include/mavlink/v0.9/ardupilotmega/mavlink.h diff --git a/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_ahrs.h b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_ahrs.h new file mode 100644 index 0000000000000000000000000000000000000000..9cb06e6b1af3146c7e61ecf7d2229c67e3582f98 --- /dev/null +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_ahrs.h @@ -0,0 +1,276 @@ +// MESSAGE AHRS PACKING + +#define MAVLINK_MSG_ID_AHRS 163 + +typedef struct __mavlink_ahrs_t +{ + float omegaIx; ///< X gyro drift estimate rad/s + float omegaIy; ///< Y gyro drift estimate rad/s + float omegaIz; ///< Z gyro drift estimate rad/s + float accel_weight; ///< average accel_weight + float renorm_val; ///< average renormalisation value + float error_rp; ///< average error_roll_pitch value + float error_yaw; ///< average error_yaw value +} mavlink_ahrs_t; + +#define MAVLINK_MSG_ID_AHRS_LEN 28 +#define MAVLINK_MSG_ID_163_LEN 28 + + + +#define MAVLINK_MESSAGE_INFO_AHRS { \ + "AHRS", \ + 7, \ + { { "omegaIx", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs_t, omegaIx) }, \ + { "omegaIy", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs_t, omegaIy) }, \ + { "omegaIz", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs_t, omegaIz) }, \ + { "accel_weight", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs_t, accel_weight) }, \ + { "renorm_val", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ahrs_t, renorm_val) }, \ + { "error_rp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ahrs_t, error_rp) }, \ + { "error_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ahrs_t, error_yaw) }, \ + } \ +} + + +/** + * @brief Pack a ahrs 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 omegaIx X gyro drift estimate rad/s + * @param omegaIy Y gyro drift estimate rad/s + * @param omegaIz Z gyro drift estimate rad/s + * @param accel_weight average accel_weight + * @param renorm_val average renormalisation value + * @param error_rp average error_roll_pitch value + * @param error_yaw average error_yaw value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ahrs_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_float(buf, 0, omegaIx); + _mav_put_float(buf, 4, omegaIy); + _mav_put_float(buf, 8, omegaIz); + _mav_put_float(buf, 12, accel_weight); + _mav_put_float(buf, 16, renorm_val); + _mav_put_float(buf, 20, error_rp); + _mav_put_float(buf, 24, error_yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); +#else + mavlink_ahrs_t packet; + packet.omegaIx = omegaIx; + packet.omegaIy = omegaIy; + packet.omegaIz = omegaIz; + packet.accel_weight = accel_weight; + packet.renorm_val = renorm_val; + packet.error_rp = error_rp; + packet.error_yaw = error_yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_AHRS; + return mavlink_finalize_message(msg, system_id, component_id, 28); +} + +/** + * @brief Pack a ahrs 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 omegaIx X gyro drift estimate rad/s + * @param omegaIy Y gyro drift estimate rad/s + * @param omegaIz Z gyro drift estimate rad/s + * @param accel_weight average accel_weight + * @param renorm_val average renormalisation value + * @param error_rp average error_roll_pitch value + * @param error_yaw average error_yaw value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ahrs_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float omegaIx,float omegaIy,float omegaIz,float accel_weight,float renorm_val,float error_rp,float error_yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_float(buf, 0, omegaIx); + _mav_put_float(buf, 4, omegaIy); + _mav_put_float(buf, 8, omegaIz); + _mav_put_float(buf, 12, accel_weight); + _mav_put_float(buf, 16, renorm_val); + _mav_put_float(buf, 20, error_rp); + _mav_put_float(buf, 24, error_yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); +#else + mavlink_ahrs_t packet; + packet.omegaIx = omegaIx; + packet.omegaIy = omegaIy; + packet.omegaIz = omegaIz; + packet.accel_weight = accel_weight; + packet.renorm_val = renorm_val; + packet.error_rp = error_rp; + packet.error_yaw = error_yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_AHRS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28); +} + +/** + * @brief Encode a ahrs 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 ahrs C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_ahrs_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ahrs_t* ahrs) +{ + return mavlink_msg_ahrs_pack(system_id, component_id, msg, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw); +} + +/** + * @brief Send a ahrs message + * @param chan MAVLink channel to send the message + * + * @param omegaIx X gyro drift estimate rad/s + * @param omegaIy Y gyro drift estimate rad/s + * @param omegaIz Z gyro drift estimate rad/s + * @param accel_weight average accel_weight + * @param renorm_val average renormalisation value + * @param error_rp average error_roll_pitch value + * @param error_yaw average error_yaw value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_ahrs_send(mavlink_channel_t chan, float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_float(buf, 0, omegaIx); + _mav_put_float(buf, 4, omegaIy); + _mav_put_float(buf, 8, omegaIz); + _mav_put_float(buf, 12, accel_weight); + _mav_put_float(buf, 16, renorm_val); + _mav_put_float(buf, 20, error_rp); + _mav_put_float(buf, 24, error_yaw); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, 28); +#else + mavlink_ahrs_t packet; + packet.omegaIx = omegaIx; + packet.omegaIy = omegaIy; + packet.omegaIz = omegaIz; + packet.accel_weight = accel_weight; + packet.renorm_val = renorm_val; + packet.error_rp = error_rp; + packet.error_yaw = error_yaw; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)&packet, 28); +#endif +} + +#endif + +// MESSAGE AHRS UNPACKING + + +/** + * @brief Get field omegaIx from ahrs message + * + * @return X gyro drift estimate rad/s + */ +static inline float mavlink_msg_ahrs_get_omegaIx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field omegaIy from ahrs message + * + * @return Y gyro drift estimate rad/s + */ +static inline float mavlink_msg_ahrs_get_omegaIy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field omegaIz from ahrs message + * + * @return Z gyro drift estimate rad/s + */ +static inline float mavlink_msg_ahrs_get_omegaIz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field accel_weight from ahrs message + * + * @return average accel_weight + */ +static inline float mavlink_msg_ahrs_get_accel_weight(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field renorm_val from ahrs message + * + * @return average renormalisation value + */ +static inline float mavlink_msg_ahrs_get_renorm_val(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field error_rp from ahrs message + * + * @return average error_roll_pitch value + */ +static inline float mavlink_msg_ahrs_get_error_rp(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field error_yaw from ahrs message + * + * @return average error_yaw value + */ +static inline float mavlink_msg_ahrs_get_error_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a ahrs message into a struct + * + * @param msg The message to decode + * @param ahrs C-struct to decode the message contents into + */ +static inline void mavlink_msg_ahrs_decode(const mavlink_message_t* msg, mavlink_ahrs_t* ahrs) +{ +#if MAVLINK_NEED_BYTE_SWAP + ahrs->omegaIx = mavlink_msg_ahrs_get_omegaIx(msg); + ahrs->omegaIy = mavlink_msg_ahrs_get_omegaIy(msg); + ahrs->omegaIz = mavlink_msg_ahrs_get_omegaIz(msg); + ahrs->accel_weight = mavlink_msg_ahrs_get_accel_weight(msg); + ahrs->renorm_val = mavlink_msg_ahrs_get_renorm_val(msg); + ahrs->error_rp = mavlink_msg_ahrs_get_error_rp(msg); + ahrs->error_yaw = mavlink_msg_ahrs_get_error_yaw(msg); +#else + memcpy(ahrs, _MAV_PAYLOAD(msg), 28); +#endif +} diff --git a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_ap_adc.h b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_ap_adc.h similarity index 96% rename from mavlink/include/v0.9/ardupilotmega/mavlink_msg_ap_adc.h rename to mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_ap_adc.h index d42edb15d39a782153fdf0556231b35349bed88d..07eacc9a917df163d2ed37cd94277d3c20097651 100644 --- a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_ap_adc.h +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_ap_adc.h @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t compon _mav_put_uint16_t(buf, 8, adc5); _mav_put_uint16_t(buf, 10, adc6); - memcpy(_MAV_PAYLOAD(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); #else mavlink_ap_adc_t packet; packet.adc1 = adc1; @@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t compon packet.adc5 = adc5; packet.adc6 = adc6; - memcpy(_MAV_PAYLOAD(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); #endif msg->msgid = MAVLINK_MSG_ID_AP_ADC; @@ -100,7 +100,7 @@ static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t c _mav_put_uint16_t(buf, 8, adc5); _mav_put_uint16_t(buf, 10, adc6); - memcpy(_MAV_PAYLOAD(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); #else mavlink_ap_adc_t packet; packet.adc1 = adc1; @@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t c packet.adc5 = adc5; packet.adc6 = adc6; - memcpy(_MAV_PAYLOAD(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); #endif msg->msgid = MAVLINK_MSG_ID_AP_ADC; diff --git a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_dcm.h b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_dcm.h similarity index 97% rename from mavlink/include/v0.9/ardupilotmega/mavlink_msg_dcm.h rename to mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_dcm.h index 60b89c1afd280e1e8863efa4bd4f1e65e1c6f058..93996514cbaa2d2e552a5eedeee07d0c6524b1fa 100644 --- a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_dcm.h +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_dcm.h @@ -60,7 +60,7 @@ static inline uint16_t mavlink_msg_dcm_pack(uint8_t system_id, uint8_t component _mav_put_float(buf, 20, error_rp); _mav_put_float(buf, 24, error_yaw); - memcpy(_MAV_PAYLOAD(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); #else mavlink_dcm_t packet; packet.omegaIx = omegaIx; @@ -71,7 +71,7 @@ static inline uint16_t mavlink_msg_dcm_pack(uint8_t system_id, uint8_t component packet.error_rp = error_rp; packet.error_yaw = error_yaw; - memcpy(_MAV_PAYLOAD(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); #endif msg->msgid = MAVLINK_MSG_ID_DCM; @@ -107,7 +107,7 @@ static inline uint16_t mavlink_msg_dcm_pack_chan(uint8_t system_id, uint8_t comp _mav_put_float(buf, 20, error_rp); _mav_put_float(buf, 24, error_yaw); - memcpy(_MAV_PAYLOAD(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); #else mavlink_dcm_t packet; packet.omegaIx = omegaIx; @@ -118,7 +118,7 @@ static inline uint16_t mavlink_msg_dcm_pack_chan(uint8_t system_id, uint8_t comp packet.error_rp = error_rp; packet.error_yaw = error_yaw; - memcpy(_MAV_PAYLOAD(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); #endif msg->msgid = MAVLINK_MSG_ID_DCM; diff --git a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_digicam_configure.h b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_digicam_configure.h similarity index 98% rename from mavlink/include/v0.9/ardupilotmega/mavlink_msg_digicam_configure.h rename to mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_digicam_configure.h index 92263b86a290fed442585644e449bdabc1d59863..8df0a00d8b9ef062920c95563db62a94fa094888 100644 --- a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_digicam_configure.h +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_digicam_configure.h @@ -76,7 +76,7 @@ static inline uint16_t mavlink_msg_digicam_configure_pack(uint8_t system_id, uin _mav_put_uint8_t(buf, 10, extra_param); _mav_put_float(buf, 11, extra_value); - memcpy(_MAV_PAYLOAD(msg), buf, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); #else mavlink_digicam_configure_t packet; packet.target_system = target_system; @@ -91,7 +91,7 @@ static inline uint16_t mavlink_msg_digicam_configure_pack(uint8_t system_id, uin packet.extra_param = extra_param; packet.extra_value = extra_value; - memcpy(_MAV_PAYLOAD(msg), &packet, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); #endif msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE; @@ -135,7 +135,7 @@ static inline uint16_t mavlink_msg_digicam_configure_pack_chan(uint8_t system_id _mav_put_uint8_t(buf, 10, extra_param); _mav_put_float(buf, 11, extra_value); - memcpy(_MAV_PAYLOAD(msg), buf, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); #else mavlink_digicam_configure_t packet; packet.target_system = target_system; @@ -150,7 +150,7 @@ static inline uint16_t mavlink_msg_digicam_configure_pack_chan(uint8_t system_id packet.extra_param = extra_param; packet.extra_value = extra_value; - memcpy(_MAV_PAYLOAD(msg), &packet, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); #endif msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE; diff --git a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_digicam_control.h b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_digicam_control.h similarity index 98% rename from mavlink/include/v0.9/ardupilotmega/mavlink_msg_digicam_control.h rename to mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_digicam_control.h index ee7d68124c0699dab52ff075d52b2170ac9e9a6f..f0cc511de72884603f6229d5c7da29eee983f704 100644 --- a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_digicam_control.h +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_digicam_control.h @@ -72,7 +72,7 @@ static inline uint16_t mavlink_msg_digicam_control_pack(uint8_t system_id, uint8 _mav_put_uint8_t(buf, 8, extra_param); _mav_put_float(buf, 9, extra_value); - memcpy(_MAV_PAYLOAD(msg), buf, 13); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13); #else mavlink_digicam_control_t packet; packet.target_system = target_system; @@ -86,7 +86,7 @@ static inline uint16_t mavlink_msg_digicam_control_pack(uint8_t system_id, uint8 packet.extra_param = extra_param; packet.extra_value = extra_value; - memcpy(_MAV_PAYLOAD(msg), &packet, 13); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13); #endif msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL; @@ -128,7 +128,7 @@ static inline uint16_t mavlink_msg_digicam_control_pack_chan(uint8_t system_id, _mav_put_uint8_t(buf, 8, extra_param); _mav_put_float(buf, 9, extra_value); - memcpy(_MAV_PAYLOAD(msg), buf, 13); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13); #else mavlink_digicam_control_t packet; packet.target_system = target_system; @@ -142,7 +142,7 @@ static inline uint16_t mavlink_msg_digicam_control_pack_chan(uint8_t system_id, packet.extra_param = extra_param; packet.extra_value = extra_value; - memcpy(_MAV_PAYLOAD(msg), &packet, 13); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13); #endif msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL; diff --git a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_fence_fetch_point.h b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_fence_fetch_point.h similarity index 96% rename from mavlink/include/v0.9/ardupilotmega/mavlink_msg_fence_fetch_point.h rename to mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_fence_fetch_point.h index fb2a9831a4cafcd8e9874693c238c79c9c7fb6aa..112b1ecf07ed3456d21f699f4645ea6f6f8df2e0 100644 --- a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_fence_fetch_point.h +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_fence_fetch_point.h @@ -44,14 +44,14 @@ static inline uint16_t mavlink_msg_fence_fetch_point_pack(uint8_t system_id, uin _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, idx); - memcpy(_MAV_PAYLOAD(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); #else mavlink_fence_fetch_point_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.idx = idx; - memcpy(_MAV_PAYLOAD(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); #endif msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT; @@ -79,14 +79,14 @@ static inline uint16_t mavlink_msg_fence_fetch_point_pack_chan(uint8_t system_id _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, idx); - memcpy(_MAV_PAYLOAD(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); #else mavlink_fence_fetch_point_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.idx = idx; - memcpy(_MAV_PAYLOAD(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); #endif msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT; diff --git a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_fence_point.h b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_fence_point.h similarity index 97% rename from mavlink/include/v0.9/ardupilotmega/mavlink_msg_fence_point.h rename to mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_fence_point.h index 35d41de4107af1083f4b3bd029ca2cbdbbf61070..b46b259f44b312df5738a5d1e51560011d1c8537 100644 --- a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_fence_point.h +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_fence_point.h @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t c _mav_put_float(buf, 4, lat); _mav_put_float(buf, 8, lng); - memcpy(_MAV_PAYLOAD(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); #else mavlink_fence_point_t packet; packet.target_system = target_system; @@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t c packet.lat = lat; packet.lng = lng; - memcpy(_MAV_PAYLOAD(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); #endif msg->msgid = MAVLINK_MSG_ID_FENCE_POINT; @@ -100,7 +100,7 @@ static inline uint16_t mavlink_msg_fence_point_pack_chan(uint8_t system_id, uint _mav_put_float(buf, 4, lat); _mav_put_float(buf, 8, lng); - memcpy(_MAV_PAYLOAD(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); #else mavlink_fence_point_t packet; packet.target_system = target_system; @@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_fence_point_pack_chan(uint8_t system_id, uint packet.lat = lat; packet.lng = lng; - memcpy(_MAV_PAYLOAD(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); #endif msg->msgid = MAVLINK_MSG_ID_FENCE_POINT; diff --git a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_fence_status.h b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_fence_status.h similarity index 97% rename from mavlink/include/v0.9/ardupilotmega/mavlink_msg_fence_status.h rename to mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_fence_status.h index cb72301117e2c9775112d51fcadcd9a7b7a72e44..77b3e56310dfa3c61dccaa185947a4a8ef2de80f 100644 --- a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_fence_status.h +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_fence_status.h @@ -48,7 +48,7 @@ static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t _mav_put_uint8_t(buf, 3, breach_type); _mav_put_uint32_t(buf, 4, breach_time); - memcpy(_MAV_PAYLOAD(msg), buf, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); #else mavlink_fence_status_t packet; packet.breach_status = breach_status; @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t packet.breach_type = breach_type; packet.breach_time = breach_time; - memcpy(_MAV_PAYLOAD(msg), &packet, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); #endif msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS; @@ -86,7 +86,7 @@ static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uin _mav_put_uint8_t(buf, 3, breach_type); _mav_put_uint32_t(buf, 4, breach_time); - memcpy(_MAV_PAYLOAD(msg), buf, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); #else mavlink_fence_status_t packet; packet.breach_status = breach_status; @@ -94,7 +94,7 @@ static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uin packet.breach_type = breach_type; packet.breach_time = breach_time; - memcpy(_MAV_PAYLOAD(msg), &packet, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); #endif msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS; diff --git a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_hwstatus.h b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_hwstatus.h similarity index 95% rename from mavlink/include/v0.9/ardupilotmega/mavlink_msg_hwstatus.h rename to mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_hwstatus.h index 20fca8139cd7bbe46744b76939659e8cf097a7db..47cc21484af952f77b5a65df2003fbdef74eaa18 100644 --- a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_hwstatus.h +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_hwstatus.h @@ -40,13 +40,13 @@ static inline uint16_t mavlink_msg_hwstatus_pack(uint8_t system_id, uint8_t comp _mav_put_uint16_t(buf, 0, Vcc); _mav_put_uint8_t(buf, 2, I2Cerr); - memcpy(_MAV_PAYLOAD(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); #else mavlink_hwstatus_t packet; packet.Vcc = Vcc; packet.I2Cerr = I2Cerr; - memcpy(_MAV_PAYLOAD(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); #endif msg->msgid = MAVLINK_MSG_ID_HWSTATUS; @@ -72,13 +72,13 @@ static inline uint16_t mavlink_msg_hwstatus_pack_chan(uint8_t system_id, uint8_t _mav_put_uint16_t(buf, 0, Vcc); _mav_put_uint8_t(buf, 2, I2Cerr); - memcpy(_MAV_PAYLOAD(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); #else mavlink_hwstatus_t packet; packet.Vcc = Vcc; packet.I2Cerr = I2Cerr; - memcpy(_MAV_PAYLOAD(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); #endif msg->msgid = MAVLINK_MSG_ID_HWSTATUS; diff --git a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_meminfo.h b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_meminfo.h similarity index 95% rename from mavlink/include/v0.9/ardupilotmega/mavlink_msg_meminfo.h rename to mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_meminfo.h index b131967df97b4d08fc0b7682dcbb37bbb5de186c..e9efa5da22370551b097ef72e4aafe11d1f23405 100644 --- a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_meminfo.h +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_meminfo.h @@ -40,13 +40,13 @@ static inline uint16_t mavlink_msg_meminfo_pack(uint8_t system_id, uint8_t compo _mav_put_uint16_t(buf, 0, brkval); _mav_put_uint16_t(buf, 2, freemem); - memcpy(_MAV_PAYLOAD(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); #else mavlink_meminfo_t packet; packet.brkval = brkval; packet.freemem = freemem; - memcpy(_MAV_PAYLOAD(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); #endif msg->msgid = MAVLINK_MSG_ID_MEMINFO; @@ -72,13 +72,13 @@ static inline uint16_t mavlink_msg_meminfo_pack_chan(uint8_t system_id, uint8_t _mav_put_uint16_t(buf, 0, brkval); _mav_put_uint16_t(buf, 2, freemem); - memcpy(_MAV_PAYLOAD(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); #else mavlink_meminfo_t packet; packet.brkval = brkval; packet.freemem = freemem; - memcpy(_MAV_PAYLOAD(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); #endif msg->msgid = MAVLINK_MSG_ID_MEMINFO; diff --git a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_mount_configure.h b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_mount_configure.h similarity index 97% rename from mavlink/include/v0.9/ardupilotmega/mavlink_msg_mount_configure.h rename to mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_mount_configure.h index f2c73d301f2a6b4973810578efafb6c5eb12f097..688d89415ab0bf44e8370511f1ee6f5139b7ba5a 100644 --- a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_mount_configure.h +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_mount_configure.h @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_mount_configure_pack(uint8_t system_id, uint8 _mav_put_uint8_t(buf, 4, stab_pitch); _mav_put_uint8_t(buf, 5, stab_yaw); - memcpy(_MAV_PAYLOAD(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); #else mavlink_mount_configure_t packet; packet.target_system = target_system; @@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_mount_configure_pack(uint8_t system_id, uint8 packet.stab_pitch = stab_pitch; packet.stab_yaw = stab_yaw; - memcpy(_MAV_PAYLOAD(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); #endif msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE; @@ -100,7 +100,7 @@ static inline uint16_t mavlink_msg_mount_configure_pack_chan(uint8_t system_id, _mav_put_uint8_t(buf, 4, stab_pitch); _mav_put_uint8_t(buf, 5, stab_yaw); - memcpy(_MAV_PAYLOAD(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); #else mavlink_mount_configure_t packet; packet.target_system = target_system; @@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_mount_configure_pack_chan(uint8_t system_id, packet.stab_pitch = stab_pitch; packet.stab_yaw = stab_yaw; - memcpy(_MAV_PAYLOAD(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); #endif msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE; diff --git a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_mount_control.h b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_mount_control.h similarity index 97% rename from mavlink/include/v0.9/ardupilotmega/mavlink_msg_mount_control.h rename to mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_mount_control.h index 5f1d13eb8e5c144d52f382b2bebbb36b5d91f89e..f13bea2d9fa35ca9f69943bf3520ec31291a01ca 100644 --- a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_mount_control.h +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_mount_control.h @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_mount_control_pack(uint8_t system_id, uint8_t _mav_put_int32_t(buf, 10, input_c); _mav_put_uint8_t(buf, 14, save_position); - memcpy(_MAV_PAYLOAD(msg), buf, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); #else mavlink_mount_control_t packet; packet.target_system = target_system; @@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_mount_control_pack(uint8_t system_id, uint8_t packet.input_c = input_c; packet.save_position = save_position; - memcpy(_MAV_PAYLOAD(msg), &packet, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); #endif msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL; @@ -100,7 +100,7 @@ static inline uint16_t mavlink_msg_mount_control_pack_chan(uint8_t system_id, ui _mav_put_int32_t(buf, 10, input_c); _mav_put_uint8_t(buf, 14, save_position); - memcpy(_MAV_PAYLOAD(msg), buf, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); #else mavlink_mount_control_t packet; packet.target_system = target_system; @@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_mount_control_pack_chan(uint8_t system_id, ui packet.input_c = input_c; packet.save_position = save_position; - memcpy(_MAV_PAYLOAD(msg), &packet, 15); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); #endif msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL; diff --git a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_mount_status.h b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_mount_status.h similarity index 97% rename from mavlink/include/v0.9/ardupilotmega/mavlink_msg_mount_status.h rename to mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_mount_status.h index 04bddae2877503e90f5bf0da18de4b06543dff73..75a44321ec169e179ac73dae5172816ef26e8c4e 100644 --- a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_mount_status.h +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_mount_status.h @@ -52,7 +52,7 @@ static inline uint16_t mavlink_msg_mount_status_pack(uint8_t system_id, uint8_t _mav_put_int32_t(buf, 6, pointing_b); _mav_put_int32_t(buf, 10, pointing_c); - memcpy(_MAV_PAYLOAD(msg), buf, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); #else mavlink_mount_status_t packet; packet.target_system = target_system; @@ -61,7 +61,7 @@ static inline uint16_t mavlink_msg_mount_status_pack(uint8_t system_id, uint8_t packet.pointing_b = pointing_b; packet.pointing_c = pointing_c; - memcpy(_MAV_PAYLOAD(msg), &packet, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); #endif msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS; @@ -93,7 +93,7 @@ static inline uint16_t mavlink_msg_mount_status_pack_chan(uint8_t system_id, uin _mav_put_int32_t(buf, 6, pointing_b); _mav_put_int32_t(buf, 10, pointing_c); - memcpy(_MAV_PAYLOAD(msg), buf, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); #else mavlink_mount_status_t packet; packet.target_system = target_system; @@ -102,7 +102,7 @@ static inline uint16_t mavlink_msg_mount_status_pack_chan(uint8_t system_id, uin packet.pointing_b = pointing_b; packet.pointing_c = pointing_c; - memcpy(_MAV_PAYLOAD(msg), &packet, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); #endif msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS; diff --git a/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_radio.h b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_radio.h new file mode 100644 index 0000000000000000000000000000000000000000..50b23b4e0f5c3f4fbe6f5ca6b865099bfe3c295d --- /dev/null +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_radio.h @@ -0,0 +1,276 @@ +// MESSAGE RADIO PACKING + +#define MAVLINK_MSG_ID_RADIO 166 + +typedef struct __mavlink_radio_t +{ + uint8_t rssi; ///< local signal strength + uint8_t remrssi; ///< remote signal strength + uint8_t txbuf; ///< how full the tx buffer is as a percentage + uint8_t noise; ///< background noise level + uint8_t remnoise; ///< remote background noise level + uint16_t rxerrors; ///< receive errors + uint16_t fixed; ///< count of error corrected packets +} mavlink_radio_t; + +#define MAVLINK_MSG_ID_RADIO_LEN 9 +#define MAVLINK_MSG_ID_166_LEN 9 + + + +#define MAVLINK_MESSAGE_INFO_RADIO { \ + "RADIO", \ + 7, \ + { { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_radio_t, rssi) }, \ + { "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_radio_t, remrssi) }, \ + { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_radio_t, txbuf) }, \ + { "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_radio_t, noise) }, \ + { "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_t, remnoise) }, \ + { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 5, offsetof(mavlink_radio_t, rxerrors) }, \ + { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 7, offsetof(mavlink_radio_t, fixed) }, \ + } \ +} + + +/** + * @brief Pack a radio 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 rssi local signal strength + * @param remrssi remote signal strength + * @param txbuf how full the tx buffer is as a percentage + * @param noise background noise level + * @param remnoise remote background noise level + * @param rxerrors receive errors + * @param fixed count of error corrected packets + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint8_t(buf, 0, rssi); + _mav_put_uint8_t(buf, 1, remrssi); + _mav_put_uint8_t(buf, 2, txbuf); + _mav_put_uint8_t(buf, 3, noise); + _mav_put_uint8_t(buf, 4, remnoise); + _mav_put_uint16_t(buf, 5, rxerrors); + _mav_put_uint16_t(buf, 7, fixed); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); +#else + mavlink_radio_t packet; + packet.rssi = rssi; + packet.remrssi = remrssi; + packet.txbuf = txbuf; + packet.noise = noise; + packet.remnoise = remnoise; + packet.rxerrors = rxerrors; + packet.fixed = fixed; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); +#endif + + msg->msgid = MAVLINK_MSG_ID_RADIO; + return mavlink_finalize_message(msg, system_id, component_id, 9); +} + +/** + * @brief Pack a radio 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 rssi local signal strength + * @param remrssi remote signal strength + * @param txbuf how full the tx buffer is as a percentage + * @param noise background noise level + * @param remnoise remote background noise level + * @param rxerrors receive errors + * @param fixed count of error corrected packets + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint8_t noise,uint8_t remnoise,uint16_t rxerrors,uint16_t fixed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint8_t(buf, 0, rssi); + _mav_put_uint8_t(buf, 1, remrssi); + _mav_put_uint8_t(buf, 2, txbuf); + _mav_put_uint8_t(buf, 3, noise); + _mav_put_uint8_t(buf, 4, remnoise); + _mav_put_uint16_t(buf, 5, rxerrors); + _mav_put_uint16_t(buf, 7, fixed); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); +#else + mavlink_radio_t packet; + packet.rssi = rssi; + packet.remrssi = remrssi; + packet.txbuf = txbuf; + packet.noise = noise; + packet.remnoise = remnoise; + packet.rxerrors = rxerrors; + packet.fixed = fixed; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); +#endif + + msg->msgid = MAVLINK_MSG_ID_RADIO; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9); +} + +/** + * @brief Encode a radio 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 radio C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_radio_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_t* radio) +{ + return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed); +} + +/** + * @brief Send a radio message + * @param chan MAVLink channel to send the message + * + * @param rssi local signal strength + * @param remrssi remote signal strength + * @param txbuf how full the tx buffer is as a percentage + * @param noise background noise level + * @param remnoise remote background noise level + * @param rxerrors receive errors + * @param fixed count of error corrected packets + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint8_t(buf, 0, rssi); + _mav_put_uint8_t(buf, 1, remrssi); + _mav_put_uint8_t(buf, 2, txbuf); + _mav_put_uint8_t(buf, 3, noise); + _mav_put_uint8_t(buf, 4, remnoise); + _mav_put_uint16_t(buf, 5, rxerrors); + _mav_put_uint16_t(buf, 7, fixed); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, 9); +#else + mavlink_radio_t packet; + packet.rssi = rssi; + packet.remrssi = remrssi; + packet.txbuf = txbuf; + packet.noise = noise; + packet.remnoise = remnoise; + packet.rxerrors = rxerrors; + packet.fixed = fixed; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, 9); +#endif +} + +#endif + +// MESSAGE RADIO UNPACKING + + +/** + * @brief Get field rssi from radio message + * + * @return local signal strength + */ +static inline uint8_t mavlink_msg_radio_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field remrssi from radio message + * + * @return remote signal strength + */ +static inline uint8_t mavlink_msg_radio_get_remrssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field txbuf from radio message + * + * @return how full the tx buffer is as a percentage + */ +static inline uint8_t mavlink_msg_radio_get_txbuf(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field noise from radio message + * + * @return background noise level + */ +static inline uint8_t mavlink_msg_radio_get_noise(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field remnoise from radio message + * + * @return remote background noise level + */ +static inline uint8_t mavlink_msg_radio_get_remnoise(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field rxerrors from radio message + * + * @return receive errors + */ +static inline uint16_t mavlink_msg_radio_get_rxerrors(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 5); +} + +/** + * @brief Get field fixed from radio message + * + * @return count of error corrected packets + */ +static inline uint16_t mavlink_msg_radio_get_fixed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 7); +} + +/** + * @brief Decode a radio message into a struct + * + * @param msg The message to decode + * @param radio C-struct to decode the message contents into + */ +static inline void mavlink_msg_radio_decode(const mavlink_message_t* msg, mavlink_radio_t* radio) +{ +#if MAVLINK_NEED_BYTE_SWAP + radio->rssi = mavlink_msg_radio_get_rssi(msg); + radio->remrssi = mavlink_msg_radio_get_remrssi(msg); + radio->txbuf = mavlink_msg_radio_get_txbuf(msg); + radio->noise = mavlink_msg_radio_get_noise(msg); + radio->remnoise = mavlink_msg_radio_get_remnoise(msg); + radio->rxerrors = mavlink_msg_radio_get_rxerrors(msg); + radio->fixed = mavlink_msg_radio_get_fixed(msg); +#else + memcpy(radio, _MAV_PAYLOAD(msg), 9); +#endif +} diff --git a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_sensor_offsets.h b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_sensor_offsets.h similarity index 98% rename from mavlink/include/v0.9/ardupilotmega/mavlink_msg_sensor_offsets.h rename to mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_sensor_offsets.h index 216211a8f85db66e0d646abb13f69fd64bf58864..3016ea9bd944cb62b840951892a862e255874f2c 100644 --- a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_sensor_offsets.h +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_sensor_offsets.h @@ -80,7 +80,7 @@ static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_ _mav_put_float(buf, 34, accel_cal_y); _mav_put_float(buf, 38, accel_cal_z); - memcpy(_MAV_PAYLOAD(msg), buf, 42); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42); #else mavlink_sensor_offsets_t packet; packet.mag_ofs_x = mag_ofs_x; @@ -96,7 +96,7 @@ static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_ packet.accel_cal_y = accel_cal_y; packet.accel_cal_z = accel_cal_z; - memcpy(_MAV_PAYLOAD(msg), &packet, 42); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42); #endif msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS; @@ -142,7 +142,7 @@ static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, u _mav_put_float(buf, 34, accel_cal_y); _mav_put_float(buf, 38, accel_cal_z); - memcpy(_MAV_PAYLOAD(msg), buf, 42); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42); #else mavlink_sensor_offsets_t packet; packet.mag_ofs_x = mag_ofs_x; @@ -158,7 +158,7 @@ static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, u packet.accel_cal_y = accel_cal_y; packet.accel_cal_z = accel_cal_z; - memcpy(_MAV_PAYLOAD(msg), &packet, 42); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42); #endif msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS; diff --git a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_set_mag_offsets.h b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_set_mag_offsets.h similarity index 97% rename from mavlink/include/v0.9/ardupilotmega/mavlink_msg_set_mag_offsets.h rename to mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_set_mag_offsets.h index 6243b440a972316c499fa8e339e1f9723da229e1..99473e2f121a504271013927c4d46b4e26b0eba2 100644 --- a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_set_mag_offsets.h +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_set_mag_offsets.h @@ -52,7 +52,7 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8 _mav_put_int16_t(buf, 4, mag_ofs_y); _mav_put_int16_t(buf, 6, mag_ofs_z); - memcpy(_MAV_PAYLOAD(msg), buf, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); #else mavlink_set_mag_offsets_t packet; packet.target_system = target_system; @@ -61,7 +61,7 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8 packet.mag_ofs_y = mag_ofs_y; packet.mag_ofs_z = mag_ofs_z; - memcpy(_MAV_PAYLOAD(msg), &packet, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); #endif msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS; @@ -93,7 +93,7 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack_chan(uint8_t system_id, _mav_put_int16_t(buf, 4, mag_ofs_y); _mav_put_int16_t(buf, 6, mag_ofs_z); - memcpy(_MAV_PAYLOAD(msg), buf, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); #else mavlink_set_mag_offsets_t packet; packet.target_system = target_system; @@ -102,7 +102,7 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack_chan(uint8_t system_id, packet.mag_ofs_y = mag_ofs_y; packet.mag_ofs_z = mag_ofs_z; - memcpy(_MAV_PAYLOAD(msg), &packet, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); #endif msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS; diff --git a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_simstate.h b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_simstate.h similarity index 97% rename from mavlink/include/v0.9/ardupilotmega/mavlink_msg_simstate.h rename to mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_simstate.h index 4d487c99b5bfb8efc0ce72db2ad733b26841cde3..05f9ca3cc4e256dd55060fab79866bd25315ed91 100644 --- a/mavlink/include/v0.9/ardupilotmega/mavlink_msg_simstate.h +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_simstate.h @@ -68,7 +68,7 @@ static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t comp _mav_put_float(buf, 28, ygyro); _mav_put_float(buf, 32, zgyro); - memcpy(_MAV_PAYLOAD(msg), buf, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); #else mavlink_simstate_t packet; packet.roll = roll; @@ -81,7 +81,7 @@ static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t comp packet.ygyro = ygyro; packet.zgyro = zgyro; - memcpy(_MAV_PAYLOAD(msg), &packet, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); #endif msg->msgid = MAVLINK_MSG_ID_SIMSTATE; @@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t _mav_put_float(buf, 28, ygyro); _mav_put_float(buf, 32, zgyro); - memcpy(_MAV_PAYLOAD(msg), buf, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); #else mavlink_simstate_t packet; packet.roll = roll; @@ -134,7 +134,7 @@ static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t packet.ygyro = ygyro; packet.zgyro = zgyro; - memcpy(_MAV_PAYLOAD(msg), &packet, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); #endif msg->msgid = MAVLINK_MSG_ID_SIMSTATE; diff --git a/mavlink/include/mavlink/v0.9/ardupilotmega/testsuite.h b/mavlink/include/mavlink/v0.9/ardupilotmega/testsuite.h new file mode 100644 index 0000000000000000000000000000000000000000..a3ac5476ca26c3666f464b5e7fb0f67349ff9a0d --- /dev/null +++ b/mavlink/include/mavlink/v0.9/ardupilotmega/testsuite.h @@ -0,0 +1,908 @@ +/** @file + * @brief MAVLink comm protocol testsuite generated from ardupilotmega.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef ARDUPILOTMEGA_TESTSUITE_H +#define ARDUPILOTMEGA_TESTSUITE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef MAVLINK_TEST_ALL +#define MAVLINK_TEST_ALL +static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); +static void mavlink_test_ardupilotmega(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_common(system_id, component_id, last_msg); + mavlink_test_ardupilotmega(system_id, component_id, last_msg); +} +#endif + +#include "../common/testsuite.h" + + +static void mavlink_test_sensor_offsets(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_sensor_offsets_t packet_in = { + 17235, + 17339, + 17443, + 59.0, + 963497984, + 963498192, + 143.0, + 171.0, + 199.0, + 227.0, + 255.0, + 283.0, + }; + mavlink_sensor_offsets_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.mag_ofs_x = packet_in.mag_ofs_x; + packet1.mag_ofs_y = packet_in.mag_ofs_y; + packet1.mag_ofs_z = packet_in.mag_ofs_z; + packet1.mag_declination = packet_in.mag_declination; + packet1.raw_press = packet_in.raw_press; + packet1.raw_temp = packet_in.raw_temp; + packet1.gyro_cal_x = packet_in.gyro_cal_x; + packet1.gyro_cal_y = packet_in.gyro_cal_y; + packet1.gyro_cal_z = packet_in.gyro_cal_z; + packet1.accel_cal_x = packet_in.accel_cal_x; + packet1.accel_cal_y = packet_in.accel_cal_y; + packet1.accel_cal_z = packet_in.accel_cal_z; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_sensor_offsets_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_sensor_offsets_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_sensor_offsets_pack(system_id, component_id, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z ); + mavlink_msg_sensor_offsets_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_sensor_offsets_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z ); + mavlink_msg_sensor_offsets_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; imsgid = MAVLINK_MSG_ID_ACTION; @@ -79,14 +79,14 @@ static inline uint16_t mavlink_msg_action_pack_chan(uint8_t system_id, uint8_t c _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, action); - memcpy(_MAV_PAYLOAD(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); #else mavlink_action_t packet; packet.target = target; packet.target_component = target_component; packet.action = action; - memcpy(_MAV_PAYLOAD(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); #endif msg->msgid = MAVLINK_MSG_ID_ACTION; diff --git a/mavlink/include/v0.9/common/mavlink_msg_action_ack.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_action_ack.h similarity index 95% rename from mavlink/include/v0.9/common/mavlink_msg_action_ack.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_action_ack.h index b7fb3256db1f0e64dd089707dd02fb795b1927e6..a87b35b5999f3116459f6ef344bcd49e9f284cd6 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_action_ack.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_action_ack.h @@ -40,13 +40,13 @@ static inline uint16_t mavlink_msg_action_ack_pack(uint8_t system_id, uint8_t co _mav_put_uint8_t(buf, 0, action); _mav_put_uint8_t(buf, 1, result); - memcpy(_MAV_PAYLOAD(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); #else mavlink_action_ack_t packet; packet.action = action; packet.result = result; - memcpy(_MAV_PAYLOAD(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); #endif msg->msgid = MAVLINK_MSG_ID_ACTION_ACK; @@ -72,13 +72,13 @@ static inline uint16_t mavlink_msg_action_ack_pack_chan(uint8_t system_id, uint8 _mav_put_uint8_t(buf, 0, action); _mav_put_uint8_t(buf, 1, result); - memcpy(_MAV_PAYLOAD(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); #else mavlink_action_ack_t packet; packet.action = action; packet.result = result; - memcpy(_MAV_PAYLOAD(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); #endif msg->msgid = MAVLINK_MSG_ID_ACTION_ACK; diff --git a/mavlink/include/v0.9/common/mavlink_msg_attitude.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_attitude.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_attitude.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_attitude.h index d3e3cb3dc274592b9a51a4d0b581e862c413c4d5..188f1eb0ff0ead3cc7b749c4a01bab59d2f5a3b9 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_attitude.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_attitude.h @@ -60,7 +60,7 @@ static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t comp _mav_put_float(buf, 24, pitchspeed); _mav_put_float(buf, 28, yawspeed); - memcpy(_MAV_PAYLOAD(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); #else mavlink_attitude_t packet; packet.usec = usec; @@ -71,7 +71,7 @@ static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t comp packet.pitchspeed = pitchspeed; packet.yawspeed = yawspeed; - memcpy(_MAV_PAYLOAD(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); #endif msg->msgid = MAVLINK_MSG_ID_ATTITUDE; @@ -107,7 +107,7 @@ static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t _mav_put_float(buf, 24, pitchspeed); _mav_put_float(buf, 28, yawspeed); - memcpy(_MAV_PAYLOAD(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); #else mavlink_attitude_t packet; packet.usec = usec; @@ -118,7 +118,7 @@ static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t packet.pitchspeed = pitchspeed; packet.yawspeed = yawspeed; - memcpy(_MAV_PAYLOAD(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); #endif msg->msgid = MAVLINK_MSG_ID_ATTITUDE; diff --git a/mavlink/include/v0.9/common/mavlink_msg_auth_key.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_auth_key.h similarity index 94% rename from mavlink/include/v0.9/common/mavlink_msg_auth_key.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_auth_key.h index c563fb7828b9c433a7a0838a0a1a3aa82626fa3a..c451444eacf9c305c00a823c7ea64c291866889f 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_auth_key.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_auth_key.h @@ -36,12 +36,12 @@ static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t comp char buf[32]; _mav_put_char_array(buf, 0, key, 32); - memcpy(_MAV_PAYLOAD(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); #else mavlink_auth_key_t packet; mav_array_memcpy(packet.key, key, sizeof(char)*32); - memcpy(_MAV_PAYLOAD(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); #endif msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; @@ -65,12 +65,12 @@ static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t char buf[32]; _mav_put_char_array(buf, 0, key, 32); - memcpy(_MAV_PAYLOAD(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); #else mavlink_auth_key_t packet; mav_array_memcpy(packet.key, key, sizeof(char)*32); - memcpy(_MAV_PAYLOAD(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); #endif msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; diff --git a/mavlink/include/v0.9/common/mavlink_msg_boot.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_boot.h similarity index 94% rename from mavlink/include/v0.9/common/mavlink_msg_boot.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_boot.h index 7541cabef69febdfc9e183d83e29a01717d9e86b..570949bd568670061f912eca2c30125f122860df 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_boot.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_boot.h @@ -36,12 +36,12 @@ static inline uint16_t mavlink_msg_boot_pack(uint8_t system_id, uint8_t componen char buf[4]; _mav_put_uint32_t(buf, 0, version); - memcpy(_MAV_PAYLOAD(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); #else mavlink_boot_t packet; packet.version = version; - memcpy(_MAV_PAYLOAD(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); #endif msg->msgid = MAVLINK_MSG_ID_BOOT; @@ -65,12 +65,12 @@ static inline uint16_t mavlink_msg_boot_pack_chan(uint8_t system_id, uint8_t com char buf[4]; _mav_put_uint32_t(buf, 0, version); - memcpy(_MAV_PAYLOAD(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); #else mavlink_boot_t packet; packet.version = version; - memcpy(_MAV_PAYLOAD(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); #endif msg->msgid = MAVLINK_MSG_ID_BOOT; diff --git a/mavlink/include/v0.9/common/mavlink_msg_change_operator_control.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_change_operator_control.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_change_operator_control.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_change_operator_control.h index 6292849bd064217308973ef288660e2ce7db2511..8fad932ea8d0beb944f3701e1702225eb8f66348 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_change_operator_control.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_change_operator_control.h @@ -47,14 +47,14 @@ static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_i _mav_put_uint8_t(buf, 1, control_request); _mav_put_uint8_t(buf, 2, version); _mav_put_char_array(buf, 3, passkey, 25); - memcpy(_MAV_PAYLOAD(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); #else mavlink_change_operator_control_t packet; packet.target_system = target_system; packet.control_request = control_request; packet.version = version; mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); - memcpy(_MAV_PAYLOAD(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); #endif msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; @@ -83,14 +83,14 @@ static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t sys _mav_put_uint8_t(buf, 1, control_request); _mav_put_uint8_t(buf, 2, version); _mav_put_char_array(buf, 3, passkey, 25); - memcpy(_MAV_PAYLOAD(msg), buf, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); #else mavlink_change_operator_control_t packet; packet.target_system = target_system; packet.control_request = control_request; packet.version = version; mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); - memcpy(_MAV_PAYLOAD(msg), &packet, 28); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); #endif msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; diff --git a/mavlink/include/v0.9/common/mavlink_msg_change_operator_control_ack.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_change_operator_control_ack.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_change_operator_control_ack.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_change_operator_control_ack.h index a24c6f5a06071301cca3ecae6e41ccce9850bf80..e9e195bbb9b2f91c6d17d72e89056baa6556d979 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_change_operator_control_ack.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_change_operator_control_ack.h @@ -44,14 +44,14 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t syst _mav_put_uint8_t(buf, 1, control_request); _mav_put_uint8_t(buf, 2, ack); - memcpy(_MAV_PAYLOAD(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); #else mavlink_change_operator_control_ack_t packet; packet.gcs_system_id = gcs_system_id; packet.control_request = control_request; packet.ack = ack; - memcpy(_MAV_PAYLOAD(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); #endif msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; @@ -79,14 +79,14 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t _mav_put_uint8_t(buf, 1, control_request); _mav_put_uint8_t(buf, 2, ack); - memcpy(_MAV_PAYLOAD(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); #else mavlink_change_operator_control_ack_t packet; packet.gcs_system_id = gcs_system_id; packet.control_request = control_request; packet.ack = ack; - memcpy(_MAV_PAYLOAD(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); #endif msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; diff --git a/mavlink/include/v0.9/common/mavlink_msg_command.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_command.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_command.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_command.h index a7221fa444a303b9c09ee4ce46da52425c480724..b5d44f8b2b47192304b498a9cbe0ecf2ab84ae0d 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_command.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_command.h @@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_command_pack(uint8_t system_id, uint8_t compo _mav_put_float(buf, 12, param3); _mav_put_float(buf, 16, param4); - memcpy(_MAV_PAYLOAD(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); #else mavlink_command_t packet; packet.target_system = target_system; @@ -76,7 +76,7 @@ static inline uint16_t mavlink_msg_command_pack(uint8_t system_id, uint8_t compo packet.param3 = param3; packet.param4 = param4; - memcpy(_MAV_PAYLOAD(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); #endif msg->msgid = MAVLINK_MSG_ID_COMMAND; @@ -114,7 +114,7 @@ static inline uint16_t mavlink_msg_command_pack_chan(uint8_t system_id, uint8_t _mav_put_float(buf, 12, param3); _mav_put_float(buf, 16, param4); - memcpy(_MAV_PAYLOAD(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); #else mavlink_command_t packet; packet.target_system = target_system; @@ -126,7 +126,7 @@ static inline uint16_t mavlink_msg_command_pack_chan(uint8_t system_id, uint8_t packet.param3 = param3; packet.param4 = param4; - memcpy(_MAV_PAYLOAD(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); #endif msg->msgid = MAVLINK_MSG_ID_COMMAND; diff --git a/mavlink/include/v0.9/common/mavlink_msg_command_ack.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_command_ack.h similarity index 96% rename from mavlink/include/v0.9/common/mavlink_msg_command_ack.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_command_ack.h index 7fc8c86232d40256f8b59cbb54933a0d4ca36a9d..ee4c89dcfa9bd16871a77c368f8b3476d1145d05 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_command_ack.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_command_ack.h @@ -40,13 +40,13 @@ static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t c _mav_put_float(buf, 0, command); _mav_put_float(buf, 4, result); - memcpy(_MAV_PAYLOAD(msg), buf, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); #else mavlink_command_ack_t packet; packet.command = command; packet.result = result; - memcpy(_MAV_PAYLOAD(msg), &packet, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); #endif msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; @@ -72,13 +72,13 @@ static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint _mav_put_float(buf, 0, command); _mav_put_float(buf, 4, result); - memcpy(_MAV_PAYLOAD(msg), buf, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); #else mavlink_command_ack_t packet; packet.command = command; packet.result = result; - memcpy(_MAV_PAYLOAD(msg), &packet, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); #endif msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; diff --git a/mavlink/include/v0.9/common/mavlink_msg_control_status.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_control_status.h similarity index 98% rename from mavlink/include/v0.9/common/mavlink_msg_control_status.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_control_status.h index 617cf5ba98446f6d35037d724b1abde3326e9606..ebc1568cc138e660818cd62b7ae18aae7fcedd44 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_control_status.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_control_status.h @@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_control_status_pack(uint8_t system_id, uint8_ _mav_put_uint8_t(buf, 6, control_pos_z); _mav_put_uint8_t(buf, 7, control_pos_yaw); - memcpy(_MAV_PAYLOAD(msg), buf, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); #else mavlink_control_status_t packet; packet.position_fix = position_fix; @@ -76,7 +76,7 @@ static inline uint16_t mavlink_msg_control_status_pack(uint8_t system_id, uint8_ packet.control_pos_z = control_pos_z; packet.control_pos_yaw = control_pos_yaw; - memcpy(_MAV_PAYLOAD(msg), &packet, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); #endif msg->msgid = MAVLINK_MSG_ID_CONTROL_STATUS; @@ -114,7 +114,7 @@ static inline uint16_t mavlink_msg_control_status_pack_chan(uint8_t system_id, u _mav_put_uint8_t(buf, 6, control_pos_z); _mav_put_uint8_t(buf, 7, control_pos_yaw); - memcpy(_MAV_PAYLOAD(msg), buf, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); #else mavlink_control_status_t packet; packet.position_fix = position_fix; @@ -126,7 +126,7 @@ static inline uint16_t mavlink_msg_control_status_pack_chan(uint8_t system_id, u packet.control_pos_z = control_pos_z; packet.control_pos_yaw = control_pos_yaw; - memcpy(_MAV_PAYLOAD(msg), &packet, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); #endif msg->msgid = MAVLINK_MSG_ID_CONTROL_STATUS; diff --git a/mavlink/include/v0.9/common/mavlink_msg_debug.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_debug.h similarity index 95% rename from mavlink/include/v0.9/common/mavlink_msg_debug.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_debug.h index 1f0788a3a47aeba79311d596cdfaf3a0e3db63f3..5a0fbdd710ee7564ba8e46b527a05d9bf9f52606 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_debug.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_debug.h @@ -40,13 +40,13 @@ static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t compone _mav_put_uint8_t(buf, 0, ind); _mav_put_float(buf, 1, value); - memcpy(_MAV_PAYLOAD(msg), buf, 5); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5); #else mavlink_debug_t packet; packet.ind = ind; packet.value = value; - memcpy(_MAV_PAYLOAD(msg), &packet, 5); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5); #endif msg->msgid = MAVLINK_MSG_ID_DEBUG; @@ -72,13 +72,13 @@ static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t co _mav_put_uint8_t(buf, 0, ind); _mav_put_float(buf, 1, value); - memcpy(_MAV_PAYLOAD(msg), buf, 5); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5); #else mavlink_debug_t packet; packet.ind = ind; packet.value = value; - memcpy(_MAV_PAYLOAD(msg), &packet, 5); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5); #endif msg->msgid = MAVLINK_MSG_ID_DEBUG; diff --git a/mavlink/include/v0.9/common/mavlink_msg_debug_vect.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_debug_vect.h similarity index 96% rename from mavlink/include/v0.9/common/mavlink_msg_debug_vect.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_debug_vect.h index 5a1a070997820a59a33e33f86ef31efee6f6647a..51895f3bad3557df630ea5c52e335e49c937f75a 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_debug_vect.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_debug_vect.h @@ -51,7 +51,7 @@ static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t co _mav_put_float(buf, 22, y); _mav_put_float(buf, 26, z); _mav_put_char_array(buf, 0, name, 10); - memcpy(_MAV_PAYLOAD(msg), buf, 30); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30); #else mavlink_debug_vect_t packet; packet.usec = usec; @@ -59,7 +59,7 @@ static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t co packet.y = y; packet.z = z; mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD(msg), &packet, 30); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30); #endif msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; @@ -90,7 +90,7 @@ static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8 _mav_put_float(buf, 22, y); _mav_put_float(buf, 26, z); _mav_put_char_array(buf, 0, name, 10); - memcpy(_MAV_PAYLOAD(msg), buf, 30); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30); #else mavlink_debug_vect_t packet; packet.usec = usec; @@ -98,7 +98,7 @@ static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8 packet.y = y; packet.z = z; mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD(msg), &packet, 30); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30); #endif msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; diff --git a/mavlink/include/v0.9/common/mavlink_msg_global_position.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_global_position.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_global_position.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_global_position.h index d281646a56cc08086eec7f7c3e9fc02e4d35a64a..5e0b9fe81014fedc470b4066574b8fb20bf8e79a 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_global_position.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_global_position.h @@ -60,7 +60,7 @@ static inline uint16_t mavlink_msg_global_position_pack(uint8_t system_id, uint8 _mav_put_float(buf, 24, vy); _mav_put_float(buf, 28, vz); - memcpy(_MAV_PAYLOAD(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); #else mavlink_global_position_t packet; packet.usec = usec; @@ -71,7 +71,7 @@ static inline uint16_t mavlink_msg_global_position_pack(uint8_t system_id, uint8 packet.vy = vy; packet.vz = vz; - memcpy(_MAV_PAYLOAD(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); #endif msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION; @@ -107,7 +107,7 @@ static inline uint16_t mavlink_msg_global_position_pack_chan(uint8_t system_id, _mav_put_float(buf, 24, vy); _mav_put_float(buf, 28, vz); - memcpy(_MAV_PAYLOAD(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); #else mavlink_global_position_t packet; packet.usec = usec; @@ -118,7 +118,7 @@ static inline uint16_t mavlink_msg_global_position_pack_chan(uint8_t system_id, packet.vy = vy; packet.vz = vz; - memcpy(_MAV_PAYLOAD(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); #endif msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION; diff --git a/mavlink/include/v0.9/common/mavlink_msg_global_position_int.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_global_position_int.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_global_position_int.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_global_position_int.h index fa984daadf8da725bd8bacec515d4403afa3996b..859a500499960e9a38b1d01597329eec7b803a13 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_global_position_int.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_global_position_int.h @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u _mav_put_int16_t(buf, 14, vy); _mav_put_int16_t(buf, 16, vz); - memcpy(_MAV_PAYLOAD(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); #else mavlink_global_position_int_t packet; packet.lat = lat; @@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u packet.vy = vy; packet.vz = vz; - memcpy(_MAV_PAYLOAD(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); #endif msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; @@ -100,7 +100,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_ _mav_put_int16_t(buf, 14, vy); _mav_put_int16_t(buf, 16, vz); - memcpy(_MAV_PAYLOAD(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); #else mavlink_global_position_int_t packet; packet.lat = lat; @@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_ packet.vy = vy; packet.vz = vz; - memcpy(_MAV_PAYLOAD(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); #endif msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; diff --git a/mavlink/include/v0.9/common/mavlink_msg_gps_local_origin_set.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_gps_local_origin_set.h similarity index 96% rename from mavlink/include/v0.9/common/mavlink_msg_gps_local_origin_set.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_gps_local_origin_set.h index 0e011483bd2c2dd01c0e19a4a32444cceb7d22c1..5faec2812c75c52b16b2eb0e1ff13a308b5bb9f3 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_gps_local_origin_set.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_gps_local_origin_set.h @@ -44,14 +44,14 @@ static inline uint16_t mavlink_msg_gps_local_origin_set_pack(uint8_t system_id, _mav_put_int32_t(buf, 4, longitude); _mav_put_int32_t(buf, 8, altitude); - memcpy(_MAV_PAYLOAD(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); #else mavlink_gps_local_origin_set_t packet; packet.latitude = latitude; packet.longitude = longitude; packet.altitude = altitude; - memcpy(_MAV_PAYLOAD(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); #endif msg->msgid = MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET; @@ -79,14 +79,14 @@ static inline uint16_t mavlink_msg_gps_local_origin_set_pack_chan(uint8_t system _mav_put_int32_t(buf, 4, longitude); _mav_put_int32_t(buf, 8, altitude); - memcpy(_MAV_PAYLOAD(msg), buf, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); #else mavlink_gps_local_origin_set_t packet; packet.latitude = latitude; packet.longitude = longitude; packet.altitude = altitude; - memcpy(_MAV_PAYLOAD(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); #endif msg->msgid = MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET; diff --git a/mavlink/include/v0.9/common/mavlink_msg_gps_raw.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_gps_raw.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_gps_raw.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_gps_raw.h index e2e0051498f23812e8b7794a1e56fe6d15648ca9..255cb27befbcd3a78a9c90b702a9345ab592f9fa 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_gps_raw.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_gps_raw.h @@ -68,7 +68,7 @@ static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t compo _mav_put_float(buf, 29, v); _mav_put_float(buf, 33, hdg); - memcpy(_MAV_PAYLOAD(msg), buf, 37); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 37); #else mavlink_gps_raw_t packet; packet.usec = usec; @@ -81,7 +81,7 @@ static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t compo packet.v = v; packet.hdg = hdg; - memcpy(_MAV_PAYLOAD(msg), &packet, 37); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 37); #endif msg->msgid = MAVLINK_MSG_ID_GPS_RAW; @@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_gps_raw_pack_chan(uint8_t system_id, uint8_t _mav_put_float(buf, 29, v); _mav_put_float(buf, 33, hdg); - memcpy(_MAV_PAYLOAD(msg), buf, 37); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 37); #else mavlink_gps_raw_t packet; packet.usec = usec; @@ -134,7 +134,7 @@ static inline uint16_t mavlink_msg_gps_raw_pack_chan(uint8_t system_id, uint8_t packet.v = v; packet.hdg = hdg; - memcpy(_MAV_PAYLOAD(msg), &packet, 37); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 37); #endif msg->msgid = MAVLINK_MSG_ID_GPS_RAW; diff --git a/mavlink/include/v0.9/common/mavlink_msg_gps_raw_int.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_gps_raw_int.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_gps_raw_int.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_gps_raw_int.h index 5f5b595601c4b3786bcce7d5d7f527e39a511785..f1e7a05e5d0a61ac6561b837d99caa15ecd6ce39 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_gps_raw_int.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_gps_raw_int.h @@ -68,7 +68,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c _mav_put_float(buf, 29, v); _mav_put_float(buf, 33, hdg); - memcpy(_MAV_PAYLOAD(msg), buf, 37); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 37); #else mavlink_gps_raw_int_t packet; packet.usec = usec; @@ -81,7 +81,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c packet.v = v; packet.hdg = hdg; - memcpy(_MAV_PAYLOAD(msg), &packet, 37); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 37); #endif msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT; @@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint _mav_put_float(buf, 29, v); _mav_put_float(buf, 33, hdg); - memcpy(_MAV_PAYLOAD(msg), buf, 37); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 37); #else mavlink_gps_raw_int_t packet; packet.usec = usec; @@ -134,7 +134,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint packet.v = v; packet.hdg = hdg; - memcpy(_MAV_PAYLOAD(msg), &packet, 37); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 37); #endif msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT; diff --git a/mavlink/include/v0.9/common/mavlink_msg_gps_set_global_origin.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_gps_set_global_origin.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_gps_set_global_origin.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_gps_set_global_origin.h index 664f78164675cf62f680e0d1120f352ebf9c03d9..cdd1f242a7ec917e1073443b9ff321885b9d9dcd 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_gps_set_global_origin.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_gps_set_global_origin.h @@ -52,7 +52,7 @@ static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id, _mav_put_int32_t(buf, 6, longitude); _mav_put_int32_t(buf, 10, altitude); - memcpy(_MAV_PAYLOAD(msg), buf, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); #else mavlink_gps_set_global_origin_t packet; packet.target_system = target_system; @@ -61,7 +61,7 @@ static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id, packet.longitude = longitude; packet.altitude = altitude; - memcpy(_MAV_PAYLOAD(msg), &packet, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); #endif msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN; @@ -93,7 +93,7 @@ static inline uint16_t mavlink_msg_gps_set_global_origin_pack_chan(uint8_t syste _mav_put_int32_t(buf, 6, longitude); _mav_put_int32_t(buf, 10, altitude); - memcpy(_MAV_PAYLOAD(msg), buf, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); #else mavlink_gps_set_global_origin_t packet; packet.target_system = target_system; @@ -102,7 +102,7 @@ static inline uint16_t mavlink_msg_gps_set_global_origin_pack_chan(uint8_t syste packet.longitude = longitude; packet.altitude = altitude; - memcpy(_MAV_PAYLOAD(msg), &packet, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); #endif msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN; diff --git a/mavlink/include/v0.9/common/mavlink_msg_gps_status.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_gps_status.h similarity index 98% rename from mavlink/include/v0.9/common/mavlink_msg_gps_status.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_gps_status.h index c0ed8c1a78a025fb6865d5d8fd5a33c0c0b6e445..e13ffe38295ffd4eeb63f53733c7fc970f54a58e 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_gps_status.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_gps_status.h @@ -59,7 +59,7 @@ static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t co _mav_put_int8_t_array(buf, 41, satellite_elevation, 20); _mav_put_int8_t_array(buf, 61, satellite_azimuth, 20); _mav_put_int8_t_array(buf, 81, satellite_snr, 20); - memcpy(_MAV_PAYLOAD(msg), buf, 101); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 101); #else mavlink_gps_status_t packet; packet.satellites_visible = satellites_visible; @@ -68,7 +68,7 @@ static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t co mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(int8_t)*20); mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(int8_t)*20); mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(int8_t)*20); - memcpy(_MAV_PAYLOAD(msg), &packet, 101); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 101); #endif msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; @@ -101,7 +101,7 @@ static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8 _mav_put_int8_t_array(buf, 41, satellite_elevation, 20); _mav_put_int8_t_array(buf, 61, satellite_azimuth, 20); _mav_put_int8_t_array(buf, 81, satellite_snr, 20); - memcpy(_MAV_PAYLOAD(msg), buf, 101); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 101); #else mavlink_gps_status_t packet; packet.satellites_visible = satellites_visible; @@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8 mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(int8_t)*20); mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(int8_t)*20); mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(int8_t)*20); - memcpy(_MAV_PAYLOAD(msg), &packet, 101); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 101); #endif msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; diff --git a/mavlink/include/v0.9/minimal/mavlink_msg_heartbeat.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_heartbeat.h similarity index 96% rename from mavlink/include/v0.9/minimal/mavlink_msg_heartbeat.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_heartbeat.h index 86bf637b1b439cdb77079fa657b21426be213889..aad90d29f3dd7f2b6970ad4cc9b724c257b33bfd 100644 --- a/mavlink/include/v0.9/minimal/mavlink_msg_heartbeat.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_heartbeat.h @@ -43,14 +43,14 @@ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t com _mav_put_uint8_t(buf, 1, autopilot); _mav_put_uint8_t(buf, 2, 2); - memcpy(_MAV_PAYLOAD(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); #else mavlink_heartbeat_t packet; packet.type = type; packet.autopilot = autopilot; packet.mavlink_version = 2; - memcpy(_MAV_PAYLOAD(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); #endif msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; @@ -77,14 +77,14 @@ static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_ _mav_put_uint8_t(buf, 1, autopilot); _mav_put_uint8_t(buf, 2, 2); - memcpy(_MAV_PAYLOAD(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); #else mavlink_heartbeat_t packet; packet.type = type; packet.autopilot = autopilot; packet.mavlink_version = 2; - memcpy(_MAV_PAYLOAD(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); #endif msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; diff --git a/mavlink/include/v0.9/common/mavlink_msg_hil_controls.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_hil_controls.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_hil_controls.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_hil_controls.h index 302b23d41c04fcb8ed8bce55bd4041a02462d90f..231c6f216be3e41ae6ce87e732525a221becf4e4 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_hil_controls.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_hil_controls.h @@ -60,7 +60,7 @@ static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t _mav_put_uint8_t(buf, 24, mode); _mav_put_uint8_t(buf, 25, nav_mode); - memcpy(_MAV_PAYLOAD(msg), buf, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); #else mavlink_hil_controls_t packet; packet.time_us = time_us; @@ -71,7 +71,7 @@ static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t packet.mode = mode; packet.nav_mode = nav_mode; - memcpy(_MAV_PAYLOAD(msg), &packet, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); #endif msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS; @@ -107,7 +107,7 @@ static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uin _mav_put_uint8_t(buf, 24, mode); _mav_put_uint8_t(buf, 25, nav_mode); - memcpy(_MAV_PAYLOAD(msg), buf, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); #else mavlink_hil_controls_t packet; packet.time_us = time_us; @@ -118,7 +118,7 @@ static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uin packet.mode = mode; packet.nav_mode = nav_mode; - memcpy(_MAV_PAYLOAD(msg), &packet, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); #endif msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS; diff --git a/mavlink/include/v0.9/common/mavlink_msg_hil_state.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_hil_state.h similarity index 98% rename from mavlink/include/v0.9/common/mavlink_msg_hil_state.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_hil_state.h index 53c3a8efeb7b5d8519fa8706fe550cbc7aa37215..6692c22580fa8dfc4d1b6daff4646518fdd7e35a 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_hil_state.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_hil_state.h @@ -96,7 +96,7 @@ static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t com _mav_put_int16_t(buf, 52, yacc); _mav_put_int16_t(buf, 54, zacc); - memcpy(_MAV_PAYLOAD(msg), buf, 56); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 56); #else mavlink_hil_state_t packet; packet.usec = usec; @@ -116,7 +116,7 @@ static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t com packet.yacc = yacc; packet.zacc = zacc; - memcpy(_MAV_PAYLOAD(msg), &packet, 56); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 56); #endif msg->msgid = MAVLINK_MSG_ID_HIL_STATE; @@ -170,7 +170,7 @@ static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_ _mav_put_int16_t(buf, 52, yacc); _mav_put_int16_t(buf, 54, zacc); - memcpy(_MAV_PAYLOAD(msg), buf, 56); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 56); #else mavlink_hil_state_t packet; packet.usec = usec; @@ -190,7 +190,7 @@ static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_ packet.yacc = yacc; packet.zacc = zacc; - memcpy(_MAV_PAYLOAD(msg), &packet, 56); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 56); #endif msg->msgid = MAVLINK_MSG_ID_HIL_STATE; diff --git a/mavlink/include/v0.9/common/mavlink_msg_local_position.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_local_position.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_local_position.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_local_position.h index fca313b8e92cceeca8acfd1484ca5a683ae96f63..121fb3af649ebd7ef72331c1e35bf6bbc268ceaa 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_local_position.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_local_position.h @@ -60,7 +60,7 @@ static inline uint16_t mavlink_msg_local_position_pack(uint8_t system_id, uint8_ _mav_put_float(buf, 24, vy); _mav_put_float(buf, 28, vz); - memcpy(_MAV_PAYLOAD(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); #else mavlink_local_position_t packet; packet.usec = usec; @@ -71,7 +71,7 @@ static inline uint16_t mavlink_msg_local_position_pack(uint8_t system_id, uint8_ packet.vy = vy; packet.vz = vz; - memcpy(_MAV_PAYLOAD(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); #endif msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION; @@ -107,7 +107,7 @@ static inline uint16_t mavlink_msg_local_position_pack_chan(uint8_t system_id, u _mav_put_float(buf, 24, vy); _mav_put_float(buf, 28, vz); - memcpy(_MAV_PAYLOAD(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); #else mavlink_local_position_t packet; packet.usec = usec; @@ -118,7 +118,7 @@ static inline uint16_t mavlink_msg_local_position_pack_chan(uint8_t system_id, u packet.vy = vy; packet.vz = vz; - memcpy(_MAV_PAYLOAD(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); #endif msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION; diff --git a/mavlink/include/v0.9/common/mavlink_msg_local_position_setpoint.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_local_position_setpoint.h similarity index 96% rename from mavlink/include/v0.9/common/mavlink_msg_local_position_setpoint.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_local_position_setpoint.h index 08c8e35eb26a49d3554c591850ad545a7b24ddd5..2e6178d96e9b92505a3da761c89da02e7607ba03 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_local_position_setpoint.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_local_position_setpoint.h @@ -48,7 +48,7 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_i _mav_put_float(buf, 8, z); _mav_put_float(buf, 12, yaw); - memcpy(_MAV_PAYLOAD(msg), buf, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); #else mavlink_local_position_setpoint_t packet; packet.x = x; @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_i packet.z = z; packet.yaw = yaw; - memcpy(_MAV_PAYLOAD(msg), &packet, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); #endif msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; @@ -86,7 +86,7 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t sys _mav_put_float(buf, 8, z); _mav_put_float(buf, 12, yaw); - memcpy(_MAV_PAYLOAD(msg), buf, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); #else mavlink_local_position_setpoint_t packet; packet.x = x; @@ -94,7 +94,7 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t sys packet.z = z; packet.yaw = yaw; - memcpy(_MAV_PAYLOAD(msg), &packet, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); #endif msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; diff --git a/mavlink/include/v0.9/common/mavlink_msg_local_position_setpoint_set.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_local_position_setpoint_set.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_local_position_setpoint_set.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_local_position_setpoint_set.h index de3aee949813dabd21c148b4a70f106b4c330370..e676c28329685f8d816ceed884ba6da98f776bbb 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_local_position_setpoint_set.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_local_position_setpoint_set.h @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_local_position_setpoint_set_pack(uint8_t syst _mav_put_float(buf, 10, z); _mav_put_float(buf, 14, yaw); - memcpy(_MAV_PAYLOAD(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); #else mavlink_local_position_setpoint_set_t packet; packet.target_system = target_system; @@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_local_position_setpoint_set_pack(uint8_t syst packet.z = z; packet.yaw = yaw; - memcpy(_MAV_PAYLOAD(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); #endif msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET; @@ -100,7 +100,7 @@ static inline uint16_t mavlink_msg_local_position_setpoint_set_pack_chan(uint8_t _mav_put_float(buf, 10, z); _mav_put_float(buf, 14, yaw); - memcpy(_MAV_PAYLOAD(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); #else mavlink_local_position_setpoint_set_t packet; packet.target_system = target_system; @@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_local_position_setpoint_set_pack_chan(uint8_t packet.z = z; packet.yaw = yaw; - memcpy(_MAV_PAYLOAD(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); #endif msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET; diff --git a/mavlink/include/v0.9/common/mavlink_msg_manual_control.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_manual_control.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_manual_control.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_manual_control.h index 09db3d9216f3cca07e5e9401e60906ed88750094..26b70ce4aecca0d3459b13eb981820ed90ba45d2 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_manual_control.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_manual_control.h @@ -68,7 +68,7 @@ static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_ _mav_put_uint8_t(buf, 19, yaw_manual); _mav_put_uint8_t(buf, 20, thrust_manual); - memcpy(_MAV_PAYLOAD(msg), buf, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21); #else mavlink_manual_control_t packet; packet.target = target; @@ -81,7 +81,7 @@ static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_ packet.yaw_manual = yaw_manual; packet.thrust_manual = thrust_manual; - memcpy(_MAV_PAYLOAD(msg), &packet, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21); #endif msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL; @@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, u _mav_put_uint8_t(buf, 19, yaw_manual); _mav_put_uint8_t(buf, 20, thrust_manual); - memcpy(_MAV_PAYLOAD(msg), buf, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21); #else mavlink_manual_control_t packet; packet.target = target; @@ -134,7 +134,7 @@ static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, u packet.yaw_manual = yaw_manual; packet.thrust_manual = thrust_manual; - memcpy(_MAV_PAYLOAD(msg), &packet, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21); #endif msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL; diff --git a/mavlink/include/v0.9/common/mavlink_msg_named_value_float.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_named_value_float.h similarity index 95% rename from mavlink/include/v0.9/common/mavlink_msg_named_value_float.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_named_value_float.h index 7b41755d21a9014854af77b90847740f117fd45e..5cf76e372e5f059d9364f7ca875fc32612a950a9 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_named_value_float.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_named_value_float.h @@ -39,12 +39,12 @@ static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uin char buf[14]; _mav_put_float(buf, 10, value); _mav_put_char_array(buf, 0, name, 10); - memcpy(_MAV_PAYLOAD(msg), buf, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); #else mavlink_named_value_float_t packet; packet.value = value; mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD(msg), &packet, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); #endif msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; @@ -69,12 +69,12 @@ static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id char buf[14]; _mav_put_float(buf, 10, value); _mav_put_char_array(buf, 0, name, 10); - memcpy(_MAV_PAYLOAD(msg), buf, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); #else mavlink_named_value_float_t packet; packet.value = value; mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD(msg), &packet, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); #endif msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; diff --git a/mavlink/include/v0.9/common/mavlink_msg_named_value_int.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_named_value_int.h similarity index 95% rename from mavlink/include/v0.9/common/mavlink_msg_named_value_int.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_named_value_int.h index a484e6e1f119ebabbc106f3ab2ace9f473b4512b..93f0911aa85191ac1c9d8a10a61f894128081515 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_named_value_int.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_named_value_int.h @@ -39,12 +39,12 @@ static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8 char buf[14]; _mav_put_int32_t(buf, 10, value); _mav_put_char_array(buf, 0, name, 10); - memcpy(_MAV_PAYLOAD(msg), buf, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); #else mavlink_named_value_int_t packet; packet.value = value; mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD(msg), &packet, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); #endif msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT; @@ -69,12 +69,12 @@ static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id, char buf[14]; _mav_put_int32_t(buf, 10, value); _mav_put_char_array(buf, 0, name, 10); - memcpy(_MAV_PAYLOAD(msg), buf, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); #else mavlink_named_value_int_t packet; packet.value = value; mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD(msg), &packet, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); #endif msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT; diff --git a/mavlink/include/v0.9/common/mavlink_msg_nav_controller_output.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_nav_controller_output.h similarity index 98% rename from mavlink/include/v0.9/common/mavlink_msg_nav_controller_output.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_nav_controller_output.h index 8322c8fabbc6339e0238de8fd45b2c9279d11941..64a4a7fb4ef34a40d3c172728dbff30a082bb116 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_nav_controller_output.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_nav_controller_output.h @@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, _mav_put_float(buf, 18, aspd_error); _mav_put_float(buf, 22, xtrack_error); - memcpy(_MAV_PAYLOAD(msg), buf, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); #else mavlink_nav_controller_output_t packet; packet.nav_roll = nav_roll; @@ -76,7 +76,7 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, packet.aspd_error = aspd_error; packet.xtrack_error = xtrack_error; - memcpy(_MAV_PAYLOAD(msg), &packet, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); #endif msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; @@ -114,7 +114,7 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t syste _mav_put_float(buf, 18, aspd_error); _mav_put_float(buf, 22, xtrack_error); - memcpy(_MAV_PAYLOAD(msg), buf, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); #else mavlink_nav_controller_output_t packet; packet.nav_roll = nav_roll; @@ -126,7 +126,7 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t syste packet.aspd_error = aspd_error; packet.xtrack_error = xtrack_error; - memcpy(_MAV_PAYLOAD(msg), &packet, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); #endif msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; diff --git a/mavlink/include/v0.9/common/mavlink_msg_object_detection_event.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_object_detection_event.h similarity index 98% rename from mavlink/include/v0.9/common/mavlink_msg_object_detection_event.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_object_detection_event.h index fc707cb7397b9bb0abc01022164daf8676e03e59..617eb50d4443c87e7d8203816dbfaf66d76df8d5 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_object_detection_event.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_object_detection_event.h @@ -59,7 +59,7 @@ static inline uint16_t mavlink_msg_object_detection_event_pack(uint8_t system_id _mav_put_float(buf, 28, bearing); _mav_put_float(buf, 32, distance); _mav_put_char_array(buf, 7, name, 20); - memcpy(_MAV_PAYLOAD(msg), buf, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); #else mavlink_object_detection_event_t packet; packet.time = time; @@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_object_detection_event_pack(uint8_t system_id packet.bearing = bearing; packet.distance = distance; mav_array_memcpy(packet.name, name, sizeof(char)*20); - memcpy(_MAV_PAYLOAD(msg), &packet, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); #endif msg->msgid = MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT; @@ -104,7 +104,7 @@ static inline uint16_t mavlink_msg_object_detection_event_pack_chan(uint8_t syst _mav_put_float(buf, 28, bearing); _mav_put_float(buf, 32, distance); _mav_put_char_array(buf, 7, name, 20); - memcpy(_MAV_PAYLOAD(msg), buf, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); #else mavlink_object_detection_event_t packet; packet.time = time; @@ -114,7 +114,7 @@ static inline uint16_t mavlink_msg_object_detection_event_pack_chan(uint8_t syst packet.bearing = bearing; packet.distance = distance; mav_array_memcpy(packet.name, name, sizeof(char)*20); - memcpy(_MAV_PAYLOAD(msg), &packet, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); #endif msg->msgid = MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT; diff --git a/mavlink/include/v0.9/common/mavlink_msg_optical_flow.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_optical_flow.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_optical_flow.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_optical_flow.h index a4bfb18a7ca3208bb89689ae2b11e6f53b4cfae0..33067cc89188de491b5f37486112e707573aa132 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_optical_flow.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_optical_flow.h @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t _mav_put_uint8_t(buf, 13, quality); _mav_put_float(buf, 14, ground_distance); - memcpy(_MAV_PAYLOAD(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); #else mavlink_optical_flow_t packet; packet.time = time; @@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t packet.quality = quality; packet.ground_distance = ground_distance; - memcpy(_MAV_PAYLOAD(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); #endif msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW; @@ -100,7 +100,7 @@ static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uin _mav_put_uint8_t(buf, 13, quality); _mav_put_float(buf, 14, ground_distance); - memcpy(_MAV_PAYLOAD(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); #else mavlink_optical_flow_t packet; packet.time = time; @@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uin packet.quality = quality; packet.ground_distance = ground_distance; - memcpy(_MAV_PAYLOAD(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); #endif msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW; diff --git a/mavlink/include/v0.9/common/mavlink_msg_param_request_list.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_param_request_list.h similarity index 96% rename from mavlink/include/v0.9/common/mavlink_msg_param_request_list.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_param_request_list.h index 123ac7977878d1fa70beeb30d22202e3c5c1df95..39e35915e11be841cfa8f8ba60586d97e5c26217 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_param_request_list.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_param_request_list.h @@ -40,13 +40,13 @@ static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, ui _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); - memcpy(_MAV_PAYLOAD(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); #else mavlink_param_request_list_t packet; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); #endif msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; @@ -72,13 +72,13 @@ static inline uint16_t mavlink_msg_param_request_list_pack_chan(uint8_t system_i _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); - memcpy(_MAV_PAYLOAD(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); #else mavlink_param_request_list_t packet; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); #endif msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; diff --git a/mavlink/include/v0.9/common/mavlink_msg_param_request_read.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_param_request_read.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_param_request_read.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_param_request_read.h index d84ed5f03203279cf5884d254d415c0ace73e921..c02cb04492d5123d7c992c252cdae699c895b7f5 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_param_request_read.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_param_request_read.h @@ -47,14 +47,14 @@ static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, ui _mav_put_uint8_t(buf, 1, target_component); _mav_put_int16_t(buf, 17, param_index); _mav_put_int8_t_array(buf, 2, param_id, 15); - memcpy(_MAV_PAYLOAD(msg), buf, 19); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 19); #else mavlink_param_request_read_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.param_index = param_index; mav_array_memcpy(packet.param_id, param_id, sizeof(int8_t)*15); - memcpy(_MAV_PAYLOAD(msg), &packet, 19); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 19); #endif msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; @@ -83,14 +83,14 @@ static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_i _mav_put_uint8_t(buf, 1, target_component); _mav_put_int16_t(buf, 17, param_index); _mav_put_int8_t_array(buf, 2, param_id, 15); - memcpy(_MAV_PAYLOAD(msg), buf, 19); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 19); #else mavlink_param_request_read_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.param_index = param_index; mav_array_memcpy(packet.param_id, param_id, sizeof(int8_t)*15); - memcpy(_MAV_PAYLOAD(msg), &packet, 19); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 19); #endif msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; diff --git a/mavlink/include/v0.9/common/mavlink_msg_param_set.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_param_set.h similarity index 96% rename from mavlink/include/v0.9/common/mavlink_msg_param_set.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_param_set.h index 2703b70765f9340797548b18214a879d050d10a0..e6648430f6ba71ec76d34e407028767257af4d6a 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_param_set.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_param_set.h @@ -47,14 +47,14 @@ static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t com _mav_put_uint8_t(buf, 1, target_component); _mav_put_float(buf, 17, param_value); _mav_put_int8_t_array(buf, 2, param_id, 15); - memcpy(_MAV_PAYLOAD(msg), buf, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21); #else mavlink_param_set_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.param_value = param_value; mav_array_memcpy(packet.param_id, param_id, sizeof(int8_t)*15); - memcpy(_MAV_PAYLOAD(msg), &packet, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21); #endif msg->msgid = MAVLINK_MSG_ID_PARAM_SET; @@ -83,14 +83,14 @@ static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_ _mav_put_uint8_t(buf, 1, target_component); _mav_put_float(buf, 17, param_value); _mav_put_int8_t_array(buf, 2, param_id, 15); - memcpy(_MAV_PAYLOAD(msg), buf, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21); #else mavlink_param_set_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.param_value = param_value; mav_array_memcpy(packet.param_id, param_id, sizeof(int8_t)*15); - memcpy(_MAV_PAYLOAD(msg), &packet, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21); #endif msg->msgid = MAVLINK_MSG_ID_PARAM_SET; diff --git a/mavlink/include/v0.9/common/mavlink_msg_param_value.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_param_value.h similarity index 96% rename from mavlink/include/v0.9/common/mavlink_msg_param_value.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_param_value.h index 1ded094763ea8347320dfa88a9c5767e3f13006f..634fbb152777565102867005b838e157c69273b4 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_param_value.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_param_value.h @@ -47,14 +47,14 @@ static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t c _mav_put_uint16_t(buf, 19, param_count); _mav_put_uint16_t(buf, 21, param_index); _mav_put_int8_t_array(buf, 0, param_id, 15); - memcpy(_MAV_PAYLOAD(msg), buf, 23); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 23); #else mavlink_param_value_t packet; packet.param_value = param_value; packet.param_count = param_count; packet.param_index = param_index; mav_array_memcpy(packet.param_id, param_id, sizeof(int8_t)*15); - memcpy(_MAV_PAYLOAD(msg), &packet, 23); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 23); #endif msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; @@ -83,14 +83,14 @@ static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint _mav_put_uint16_t(buf, 19, param_count); _mav_put_uint16_t(buf, 21, param_index); _mav_put_int8_t_array(buf, 0, param_id, 15); - memcpy(_MAV_PAYLOAD(msg), buf, 23); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 23); #else mavlink_param_value_t packet; packet.param_value = param_value; packet.param_count = param_count; packet.param_index = param_index; mav_array_memcpy(packet.param_id, param_id, sizeof(int8_t)*15); - memcpy(_MAV_PAYLOAD(msg), &packet, 23); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 23); #endif msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; diff --git a/mavlink/include/v0.9/common/mavlink_msg_ping.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_ping.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_ping.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_ping.h index c424221380df4fc5ef0b7b7175fcecc7a4ec317a..ad076fd9b5eb3dc29a54ef75d6113396b0eaf1ba 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_ping.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_ping.h @@ -48,7 +48,7 @@ static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t componen _mav_put_uint8_t(buf, 5, target_component); _mav_put_uint64_t(buf, 6, time); - memcpy(_MAV_PAYLOAD(msg), buf, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); #else mavlink_ping_t packet; packet.seq = seq; @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t componen packet.target_component = target_component; packet.time = time; - memcpy(_MAV_PAYLOAD(msg), &packet, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); #endif msg->msgid = MAVLINK_MSG_ID_PING; @@ -86,7 +86,7 @@ static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t com _mav_put_uint8_t(buf, 5, target_component); _mav_put_uint64_t(buf, 6, time); - memcpy(_MAV_PAYLOAD(msg), buf, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); #else mavlink_ping_t packet; packet.seq = seq; @@ -94,7 +94,7 @@ static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t com packet.target_component = target_component; packet.time = time; - memcpy(_MAV_PAYLOAD(msg), &packet, 14); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); #endif msg->msgid = MAVLINK_MSG_ID_PING; diff --git a/mavlink/include/v0.9/common/mavlink_msg_position_target.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_position_target.h similarity index 96% rename from mavlink/include/v0.9/common/mavlink_msg_position_target.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_position_target.h index 4d9cdc48067aa1d7518eb98421db41122350d32a..6cd7719fb27ca4f3943a17cde13da97df2744094 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_position_target.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_position_target.h @@ -48,7 +48,7 @@ static inline uint16_t mavlink_msg_position_target_pack(uint8_t system_id, uint8 _mav_put_float(buf, 8, z); _mav_put_float(buf, 12, yaw); - memcpy(_MAV_PAYLOAD(msg), buf, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); #else mavlink_position_target_t packet; packet.x = x; @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_position_target_pack(uint8_t system_id, uint8 packet.z = z; packet.yaw = yaw; - memcpy(_MAV_PAYLOAD(msg), &packet, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); #endif msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET; @@ -86,7 +86,7 @@ static inline uint16_t mavlink_msg_position_target_pack_chan(uint8_t system_id, _mav_put_float(buf, 8, z); _mav_put_float(buf, 12, yaw); - memcpy(_MAV_PAYLOAD(msg), buf, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); #else mavlink_position_target_t packet; packet.x = x; @@ -94,7 +94,7 @@ static inline uint16_t mavlink_msg_position_target_pack_chan(uint8_t system_id, packet.z = z; packet.yaw = yaw; - memcpy(_MAV_PAYLOAD(msg), &packet, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); #endif msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET; diff --git a/mavlink/include/v0.9/common/mavlink_msg_raw_imu.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_raw_imu.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_raw_imu.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_raw_imu.h index a3a3500fde74490beb8985a1c774ea2b7deca812..c60945ae9fbd867177f1812427eb48773c0bd924 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_raw_imu.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_raw_imu.h @@ -72,7 +72,7 @@ static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t compo _mav_put_int16_t(buf, 22, ymag); _mav_put_int16_t(buf, 24, zmag); - memcpy(_MAV_PAYLOAD(msg), buf, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); #else mavlink_raw_imu_t packet; packet.usec = usec; @@ -86,7 +86,7 @@ static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t compo packet.ymag = ymag; packet.zmag = zmag; - memcpy(_MAV_PAYLOAD(msg), &packet, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); #endif msg->msgid = MAVLINK_MSG_ID_RAW_IMU; @@ -128,7 +128,7 @@ static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t _mav_put_int16_t(buf, 22, ymag); _mav_put_int16_t(buf, 24, zmag); - memcpy(_MAV_PAYLOAD(msg), buf, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); #else mavlink_raw_imu_t packet; packet.usec = usec; @@ -142,7 +142,7 @@ static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t packet.ymag = ymag; packet.zmag = zmag; - memcpy(_MAV_PAYLOAD(msg), &packet, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); #endif msg->msgid = MAVLINK_MSG_ID_RAW_IMU; diff --git a/mavlink/include/v0.9/common/mavlink_msg_raw_pressure.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_raw_pressure.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_raw_pressure.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_raw_pressure.h index b56d3e622e547fd22f4c3211206edcd93eec5777..b493b7e9887c63bc4d32016aea8e59ac8295a4e2 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_raw_pressure.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_raw_pressure.h @@ -52,7 +52,7 @@ static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t _mav_put_int16_t(buf, 12, press_diff2); _mav_put_int16_t(buf, 14, temperature); - memcpy(_MAV_PAYLOAD(msg), buf, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); #else mavlink_raw_pressure_t packet; packet.usec = usec; @@ -61,7 +61,7 @@ static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t packet.press_diff2 = press_diff2; packet.temperature = temperature; - memcpy(_MAV_PAYLOAD(msg), &packet, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); #endif msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; @@ -93,7 +93,7 @@ static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uin _mav_put_int16_t(buf, 12, press_diff2); _mav_put_int16_t(buf, 14, temperature); - memcpy(_MAV_PAYLOAD(msg), buf, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); #else mavlink_raw_pressure_t packet; packet.usec = usec; @@ -102,7 +102,7 @@ static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uin packet.press_diff2 = press_diff2; packet.temperature = temperature; - memcpy(_MAV_PAYLOAD(msg), &packet, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); #endif msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; diff --git a/mavlink/include/v0.9/common/mavlink_msg_rc_channels_override.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_rc_channels_override.h similarity index 98% rename from mavlink/include/v0.9/common/mavlink_msg_rc_channels_override.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_rc_channels_override.h index d163158f7f97807dff1ae9c377f2f36a65fe59dd..30e5a8f98e9e182c739354aee520d6be72049fc5 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_rc_channels_override.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_rc_channels_override.h @@ -72,7 +72,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, _mav_put_uint16_t(buf, 14, chan7_raw); _mav_put_uint16_t(buf, 16, chan8_raw); - memcpy(_MAV_PAYLOAD(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); #else mavlink_rc_channels_override_t packet; packet.target_system = target_system; @@ -86,7 +86,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, packet.chan7_raw = chan7_raw; packet.chan8_raw = chan8_raw; - memcpy(_MAV_PAYLOAD(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); #endif msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE; @@ -128,7 +128,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system _mav_put_uint16_t(buf, 14, chan7_raw); _mav_put_uint16_t(buf, 16, chan8_raw); - memcpy(_MAV_PAYLOAD(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); #else mavlink_rc_channels_override_t packet; packet.target_system = target_system; @@ -142,7 +142,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system packet.chan7_raw = chan7_raw; packet.chan8_raw = chan8_raw; - memcpy(_MAV_PAYLOAD(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); #endif msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE; diff --git a/mavlink/include/v0.9/common/mavlink_msg_rc_channels_raw.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_rc_channels_raw.h similarity index 98% rename from mavlink/include/v0.9/common/mavlink_msg_rc_channels_raw.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_rc_channels_raw.h index 6df3485082aac610d2b89a3301fd924b4bebfc80..855f7cced300b663d8a8b292e4253290160c0437 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_rc_channels_raw.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_rc_channels_raw.h @@ -68,7 +68,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8 _mav_put_uint16_t(buf, 14, chan8_raw); _mav_put_uint8_t(buf, 16, rssi); - memcpy(_MAV_PAYLOAD(msg), buf, 17); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17); #else mavlink_rc_channels_raw_t packet; packet.chan1_raw = chan1_raw; @@ -81,7 +81,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8 packet.chan8_raw = chan8_raw; packet.rssi = rssi; - memcpy(_MAV_PAYLOAD(msg), &packet, 17); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17); #endif msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; @@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, _mav_put_uint16_t(buf, 14, chan8_raw); _mav_put_uint8_t(buf, 16, rssi); - memcpy(_MAV_PAYLOAD(msg), buf, 17); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17); #else mavlink_rc_channels_raw_t packet; packet.chan1_raw = chan1_raw; @@ -134,7 +134,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, packet.chan8_raw = chan8_raw; packet.rssi = rssi; - memcpy(_MAV_PAYLOAD(msg), &packet, 17); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17); #endif msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; diff --git a/mavlink/include/v0.9/common/mavlink_msg_rc_channels_scaled.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_rc_channels_scaled.h similarity index 98% rename from mavlink/include/v0.9/common/mavlink_msg_rc_channels_scaled.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_rc_channels_scaled.h index b178ad1731f18e909af5344045f46f968e0d14cd..49df14a7ac0a48d25dd70967904e00a05eb22719 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_rc_channels_scaled.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_rc_channels_scaled.h @@ -68,7 +68,7 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, ui _mav_put_int16_t(buf, 14, chan8_scaled); _mav_put_uint8_t(buf, 16, rssi); - memcpy(_MAV_PAYLOAD(msg), buf, 17); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17); #else mavlink_rc_channels_scaled_t packet; packet.chan1_scaled = chan1_scaled; @@ -81,7 +81,7 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, ui packet.chan8_scaled = chan8_scaled; packet.rssi = rssi; - memcpy(_MAV_PAYLOAD(msg), &packet, 17); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17); #endif msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; @@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_i _mav_put_int16_t(buf, 14, chan8_scaled); _mav_put_uint8_t(buf, 16, rssi); - memcpy(_MAV_PAYLOAD(msg), buf, 17); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17); #else mavlink_rc_channels_scaled_t packet; packet.chan1_scaled = chan1_scaled; @@ -134,7 +134,7 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_i packet.chan8_scaled = chan8_scaled; packet.rssi = rssi; - memcpy(_MAV_PAYLOAD(msg), &packet, 17); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17); #endif msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; diff --git a/mavlink/include/v0.9/common/mavlink_msg_request_data_stream.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_request_data_stream.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_request_data_stream.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_request_data_stream.h index 895897738cad4a87edee111f596a5694408c62c1..e80473aa11f9a8c96060b36d3b98cf2427bd52e2 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_request_data_stream.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_request_data_stream.h @@ -52,7 +52,7 @@ static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, u _mav_put_uint16_t(buf, 3, req_message_rate); _mav_put_uint8_t(buf, 5, start_stop); - memcpy(_MAV_PAYLOAD(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); #else mavlink_request_data_stream_t packet; packet.target_system = target_system; @@ -61,7 +61,7 @@ static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, u packet.req_message_rate = req_message_rate; packet.start_stop = start_stop; - memcpy(_MAV_PAYLOAD(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); #endif msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM; @@ -93,7 +93,7 @@ static inline uint16_t mavlink_msg_request_data_stream_pack_chan(uint8_t system_ _mav_put_uint16_t(buf, 3, req_message_rate); _mav_put_uint8_t(buf, 5, start_stop); - memcpy(_MAV_PAYLOAD(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); #else mavlink_request_data_stream_t packet; packet.target_system = target_system; @@ -102,7 +102,7 @@ static inline uint16_t mavlink_msg_request_data_stream_pack_chan(uint8_t system_ packet.req_message_rate = req_message_rate; packet.start_stop = start_stop; - memcpy(_MAV_PAYLOAD(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); #endif msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM; diff --git a/mavlink/include/v0.9/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h index 4d0a87e2fda4ebffbe59de87dd525dce8f682f9f..b344f3aa27c983ddc498039170f1c1325b53c7e6 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h @@ -52,7 +52,7 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(uin _mav_put_float(buf, 16, yaw_speed); _mav_put_float(buf, 20, thrust); - memcpy(_MAV_PAYLOAD(msg), buf, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24); #else mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet; packet.time_us = time_us; @@ -61,7 +61,7 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(uin packet.yaw_speed = yaw_speed; packet.thrust = thrust; - memcpy(_MAV_PAYLOAD(msg), &packet, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24); #endif msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT; @@ -93,7 +93,7 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_cha _mav_put_float(buf, 16, yaw_speed); _mav_put_float(buf, 20, thrust); - memcpy(_MAV_PAYLOAD(msg), buf, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24); #else mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet; packet.time_us = time_us; @@ -102,7 +102,7 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_cha packet.yaw_speed = yaw_speed; packet.thrust = thrust; - memcpy(_MAV_PAYLOAD(msg), &packet, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24); #endif msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT; diff --git a/mavlink/include/v0.9/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h index 7de8441ab0e03bd1324027935824aefcf2f9fa29..16155f134324abeebedc8f0e6c7628da2e8bf5ff 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h @@ -52,7 +52,7 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(uint8_t s _mav_put_float(buf, 16, yaw); _mav_put_float(buf, 20, thrust); - memcpy(_MAV_PAYLOAD(msg), buf, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24); #else mavlink_roll_pitch_yaw_thrust_setpoint_t packet; packet.time_us = time_us; @@ -61,7 +61,7 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(uint8_t s packet.yaw = yaw; packet.thrust = thrust; - memcpy(_MAV_PAYLOAD(msg), &packet, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24); #endif msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT; @@ -93,7 +93,7 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack_chan(uint _mav_put_float(buf, 16, yaw); _mav_put_float(buf, 20, thrust); - memcpy(_MAV_PAYLOAD(msg), buf, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24); #else mavlink_roll_pitch_yaw_thrust_setpoint_t packet; packet.time_us = time_us; @@ -102,7 +102,7 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack_chan(uint packet.yaw = yaw; packet.thrust = thrust; - memcpy(_MAV_PAYLOAD(msg), &packet, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24); #endif msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT; diff --git a/mavlink/include/v0.9/common/mavlink_msg_safety_allowed_area.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_safety_allowed_area.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_safety_allowed_area.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_safety_allowed_area.h index d76c204f7a151c203765911c0df99b3c44e65774..07b91fd0edbc750c775184fd0ae2350632632594 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_safety_allowed_area.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_safety_allowed_area.h @@ -60,7 +60,7 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, u _mav_put_float(buf, 17, p2y); _mav_put_float(buf, 21, p2z); - memcpy(_MAV_PAYLOAD(msg), buf, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25); #else mavlink_safety_allowed_area_t packet; packet.frame = frame; @@ -71,7 +71,7 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, u packet.p2y = p2y; packet.p2z = p2z; - memcpy(_MAV_PAYLOAD(msg), &packet, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25); #endif msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; @@ -107,7 +107,7 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_ _mav_put_float(buf, 17, p2y); _mav_put_float(buf, 21, p2z); - memcpy(_MAV_PAYLOAD(msg), buf, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25); #else mavlink_safety_allowed_area_t packet; packet.frame = frame; @@ -118,7 +118,7 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_ packet.p2y = p2y; packet.p2z = p2z; - memcpy(_MAV_PAYLOAD(msg), &packet, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25); #endif msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; diff --git a/mavlink/include/v0.9/common/mavlink_msg_safety_set_allowed_area.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_safety_set_allowed_area.h similarity index 98% rename from mavlink/include/v0.9/common/mavlink_msg_safety_set_allowed_area.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_safety_set_allowed_area.h index 8afdf6f13318085dccffa100177a149ae0fc89cd..3c122227a6335dc1cc7123e32e9a1040d6488708 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_safety_set_allowed_area.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_safety_set_allowed_area.h @@ -68,7 +68,7 @@ static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_i _mav_put_float(buf, 19, p2y); _mav_put_float(buf, 23, p2z); - memcpy(_MAV_PAYLOAD(msg), buf, 27); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 27); #else mavlink_safety_set_allowed_area_t packet; packet.target_system = target_system; @@ -81,7 +81,7 @@ static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_i packet.p2y = p2y; packet.p2z = p2z; - memcpy(_MAV_PAYLOAD(msg), &packet, 27); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 27); #endif msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA; @@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_safety_set_allowed_area_pack_chan(uint8_t sys _mav_put_float(buf, 19, p2y); _mav_put_float(buf, 23, p2z); - memcpy(_MAV_PAYLOAD(msg), buf, 27); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 27); #else mavlink_safety_set_allowed_area_t packet; packet.target_system = target_system; @@ -134,7 +134,7 @@ static inline uint16_t mavlink_msg_safety_set_allowed_area_pack_chan(uint8_t sys packet.p2y = p2y; packet.p2z = p2z; - memcpy(_MAV_PAYLOAD(msg), &packet, 27); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 27); #endif msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA; diff --git a/mavlink/include/v0.9/common/mavlink_msg_scaled_imu.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_scaled_imu.h similarity index 98% rename from mavlink/include/v0.9/common/mavlink_msg_scaled_imu.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_scaled_imu.h index 7bec81d9d5c7e341ed972a2f6257ef596491f716..4315dac27566b0f7db869ed65da3aca5949f5f71 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_scaled_imu.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_scaled_imu.h @@ -72,7 +72,7 @@ static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t co _mav_put_int16_t(buf, 22, ymag); _mav_put_int16_t(buf, 24, zmag); - memcpy(_MAV_PAYLOAD(msg), buf, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); #else mavlink_scaled_imu_t packet; packet.usec = usec; @@ -86,7 +86,7 @@ static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t co packet.ymag = ymag; packet.zmag = zmag; - memcpy(_MAV_PAYLOAD(msg), &packet, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); #endif msg->msgid = MAVLINK_MSG_ID_SCALED_IMU; @@ -128,7 +128,7 @@ static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8 _mav_put_int16_t(buf, 22, ymag); _mav_put_int16_t(buf, 24, zmag); - memcpy(_MAV_PAYLOAD(msg), buf, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); #else mavlink_scaled_imu_t packet; packet.usec = usec; @@ -142,7 +142,7 @@ static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8 packet.ymag = ymag; packet.zmag = zmag; - memcpy(_MAV_PAYLOAD(msg), &packet, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); #endif msg->msgid = MAVLINK_MSG_ID_SCALED_IMU; diff --git a/mavlink/include/v0.9/common/mavlink_msg_scaled_pressure.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_scaled_pressure.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_scaled_pressure.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_scaled_pressure.h index 287c9a95b7b2ce45d43ef7c1c41e0c224826af0c..579f7f4ee350b4930b2cf94347f3601ca847b594 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_scaled_pressure.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_scaled_pressure.h @@ -48,7 +48,7 @@ static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8 _mav_put_float(buf, 12, press_diff); _mav_put_int16_t(buf, 16, temperature); - memcpy(_MAV_PAYLOAD(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); #else mavlink_scaled_pressure_t packet; packet.usec = usec; @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8 packet.press_diff = press_diff; packet.temperature = temperature; - memcpy(_MAV_PAYLOAD(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); #endif msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE; @@ -86,7 +86,7 @@ static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, _mav_put_float(buf, 12, press_diff); _mav_put_int16_t(buf, 16, temperature); - memcpy(_MAV_PAYLOAD(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); #else mavlink_scaled_pressure_t packet; packet.usec = usec; @@ -94,7 +94,7 @@ static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, packet.press_diff = press_diff; packet.temperature = temperature; - memcpy(_MAV_PAYLOAD(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); #endif msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE; diff --git a/mavlink/include/v0.9/common/mavlink_msg_servo_output_raw.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_servo_output_raw.h similarity index 98% rename from mavlink/include/v0.9/common/mavlink_msg_servo_output_raw.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_servo_output_raw.h index 3c2b52e906452aefb3095170b08b48cd3b95e497..b5be3318cc10de48a0484f8458b3a2d21c7af0a0 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_servo_output_raw.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_servo_output_raw.h @@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint _mav_put_uint16_t(buf, 12, servo7_raw); _mav_put_uint16_t(buf, 14, servo8_raw); - memcpy(_MAV_PAYLOAD(msg), buf, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); #else mavlink_servo_output_raw_t packet; packet.servo1_raw = servo1_raw; @@ -76,7 +76,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint packet.servo7_raw = servo7_raw; packet.servo8_raw = servo8_raw; - memcpy(_MAV_PAYLOAD(msg), &packet, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); #endif msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; @@ -114,7 +114,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, _mav_put_uint16_t(buf, 12, servo7_raw); _mav_put_uint16_t(buf, 14, servo8_raw); - memcpy(_MAV_PAYLOAD(msg), buf, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); #else mavlink_servo_output_raw_t packet; packet.servo1_raw = servo1_raw; @@ -126,7 +126,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, packet.servo7_raw = servo7_raw; packet.servo8_raw = servo8_raw; - memcpy(_MAV_PAYLOAD(msg), &packet, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); #endif msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; diff --git a/mavlink/include/v0.9/common/mavlink_msg_set_altitude.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_set_altitude.h similarity index 95% rename from mavlink/include/v0.9/common/mavlink_msg_set_altitude.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_set_altitude.h index 14398bc53e2ab1c47a73aaf5da7eafb7fc0b3a01..72cc5e7b0cb01cc271e42aa1e940e0a32d839422 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_set_altitude.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_set_altitude.h @@ -40,13 +40,13 @@ static inline uint16_t mavlink_msg_set_altitude_pack(uint8_t system_id, uint8_t _mav_put_uint8_t(buf, 0, target); _mav_put_uint32_t(buf, 1, mode); - memcpy(_MAV_PAYLOAD(msg), buf, 5); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5); #else mavlink_set_altitude_t packet; packet.target = target; packet.mode = mode; - memcpy(_MAV_PAYLOAD(msg), &packet, 5); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5); #endif msg->msgid = MAVLINK_MSG_ID_SET_ALTITUDE; @@ -72,13 +72,13 @@ static inline uint16_t mavlink_msg_set_altitude_pack_chan(uint8_t system_id, uin _mav_put_uint8_t(buf, 0, target); _mav_put_uint32_t(buf, 1, mode); - memcpy(_MAV_PAYLOAD(msg), buf, 5); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5); #else mavlink_set_altitude_t packet; packet.target = target; packet.mode = mode; - memcpy(_MAV_PAYLOAD(msg), &packet, 5); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5); #endif msg->msgid = MAVLINK_MSG_ID_SET_ALTITUDE; diff --git a/mavlink/include/v0.9/common/mavlink_msg_set_mode.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_set_mode.h similarity index 95% rename from mavlink/include/v0.9/common/mavlink_msg_set_mode.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_set_mode.h index 6630aea486317cfce13044a1117d2dc8cc49bfa3..8a3f20593dcbfdd9354688808ec8ceb9bf0c4cf5 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_set_mode.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_set_mode.h @@ -40,13 +40,13 @@ static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t comp _mav_put_uint8_t(buf, 0, target); _mav_put_uint8_t(buf, 1, mode); - memcpy(_MAV_PAYLOAD(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); #else mavlink_set_mode_t packet; packet.target = target; packet.mode = mode; - memcpy(_MAV_PAYLOAD(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); #endif msg->msgid = MAVLINK_MSG_ID_SET_MODE; @@ -72,13 +72,13 @@ static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t _mav_put_uint8_t(buf, 0, target); _mav_put_uint8_t(buf, 1, mode); - memcpy(_MAV_PAYLOAD(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); #else mavlink_set_mode_t packet; packet.target = target; packet.mode = mode; - memcpy(_MAV_PAYLOAD(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); #endif msg->msgid = MAVLINK_MSG_ID_SET_MODE; diff --git a/mavlink/include/v0.9/common/mavlink_msg_set_nav_mode.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_set_nav_mode.h similarity index 95% rename from mavlink/include/v0.9/common/mavlink_msg_set_nav_mode.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_set_nav_mode.h index fafb6ec7e5434cb910eb4a448751104fed4ca24b..02efa26b1988680cac543ac41260c7703f0acbfd 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_set_nav_mode.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_set_nav_mode.h @@ -40,13 +40,13 @@ static inline uint16_t mavlink_msg_set_nav_mode_pack(uint8_t system_id, uint8_t _mav_put_uint8_t(buf, 0, target); _mav_put_uint8_t(buf, 1, nav_mode); - memcpy(_MAV_PAYLOAD(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); #else mavlink_set_nav_mode_t packet; packet.target = target; packet.nav_mode = nav_mode; - memcpy(_MAV_PAYLOAD(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); #endif msg->msgid = MAVLINK_MSG_ID_SET_NAV_MODE; @@ -72,13 +72,13 @@ static inline uint16_t mavlink_msg_set_nav_mode_pack_chan(uint8_t system_id, uin _mav_put_uint8_t(buf, 0, target); _mav_put_uint8_t(buf, 1, nav_mode); - memcpy(_MAV_PAYLOAD(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); #else mavlink_set_nav_mode_t packet; packet.target = target; packet.nav_mode = nav_mode; - memcpy(_MAV_PAYLOAD(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); #endif msg->msgid = MAVLINK_MSG_ID_SET_NAV_MODE; diff --git a/mavlink/include/v0.9/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h index d666d0cca67efb5f79a2fe2b67af4c0f724ecd5a..6a9c01215bb0752c017ca655310d941b45a654d1 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(uint8_t _mav_put_float(buf, 10, yaw_speed); _mav_put_float(buf, 14, thrust); - memcpy(_MAV_PAYLOAD(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); #else mavlink_set_roll_pitch_yaw_speed_thrust_t packet; packet.target_system = target_system; @@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(uint8_t packet.yaw_speed = yaw_speed; packet.thrust = thrust; - memcpy(_MAV_PAYLOAD(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); #endif msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST; @@ -100,7 +100,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack_chan(uin _mav_put_float(buf, 10, yaw_speed); _mav_put_float(buf, 14, thrust); - memcpy(_MAV_PAYLOAD(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); #else mavlink_set_roll_pitch_yaw_speed_thrust_t packet; packet.target_system = target_system; @@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack_chan(uin packet.yaw_speed = yaw_speed; packet.thrust = thrust; - memcpy(_MAV_PAYLOAD(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); #endif msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST; diff --git a/mavlink/include/v0.9/common/mavlink_msg_set_roll_pitch_yaw_thrust.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_set_roll_pitch_yaw_thrust.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_set_roll_pitch_yaw_thrust.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_set_roll_pitch_yaw_thrust.h index ad9425158e1da894b8d837cf478773525dd0fcdb..dad4f657dd671974050f9d934ea4c09847a976b3 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_set_roll_pitch_yaw_thrust.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_set_roll_pitch_yaw_thrust.h @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack(uint8_t system _mav_put_float(buf, 10, yaw); _mav_put_float(buf, 14, thrust); - memcpy(_MAV_PAYLOAD(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); #else mavlink_set_roll_pitch_yaw_thrust_t packet; packet.target_system = target_system; @@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack(uint8_t system packet.yaw = yaw; packet.thrust = thrust; - memcpy(_MAV_PAYLOAD(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); #endif msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST; @@ -100,7 +100,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack_chan(uint8_t s _mav_put_float(buf, 10, yaw); _mav_put_float(buf, 14, thrust); - memcpy(_MAV_PAYLOAD(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); #else mavlink_set_roll_pitch_yaw_thrust_t packet; packet.target_system = target_system; @@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack_chan(uint8_t s packet.yaw = yaw; packet.thrust = thrust; - memcpy(_MAV_PAYLOAD(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); #endif msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST; diff --git a/mavlink/include/v0.9/common/mavlink_msg_state_correction.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_state_correction.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_state_correction.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_state_correction.h index 9c9f6d9b8964ba0f85971dfe5dc9c130ea38133d..ddd785a2ac4609c1a25ccde3115ac32ebdaaaff4 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_state_correction.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_state_correction.h @@ -68,7 +68,7 @@ static inline uint16_t mavlink_msg_state_correction_pack(uint8_t system_id, uint _mav_put_float(buf, 28, vyErr); _mav_put_float(buf, 32, vzErr); - memcpy(_MAV_PAYLOAD(msg), buf, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); #else mavlink_state_correction_t packet; packet.xErr = xErr; @@ -81,7 +81,7 @@ static inline uint16_t mavlink_msg_state_correction_pack(uint8_t system_id, uint packet.vyErr = vyErr; packet.vzErr = vzErr; - memcpy(_MAV_PAYLOAD(msg), &packet, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); #endif msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION; @@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_state_correction_pack_chan(uint8_t system_id, _mav_put_float(buf, 28, vyErr); _mav_put_float(buf, 32, vzErr); - memcpy(_MAV_PAYLOAD(msg), buf, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); #else mavlink_state_correction_t packet; packet.xErr = xErr; @@ -134,7 +134,7 @@ static inline uint16_t mavlink_msg_state_correction_pack_chan(uint8_t system_id, packet.vyErr = vyErr; packet.vzErr = vzErr; - memcpy(_MAV_PAYLOAD(msg), &packet, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); #endif msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION; diff --git a/mavlink/include/v0.9/common/mavlink_msg_statustext.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_statustext.h similarity index 95% rename from mavlink/include/v0.9/common/mavlink_msg_statustext.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_statustext.h index da6cd7a18c675b0e619f14388370adc954aa0e1f..c65f629e991d317273ab95b832e1730cd1f08f45 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_statustext.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_statustext.h @@ -39,12 +39,12 @@ static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t co char buf[51]; _mav_put_uint8_t(buf, 0, severity); _mav_put_int8_t_array(buf, 1, text, 50); - memcpy(_MAV_PAYLOAD(msg), buf, 51); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 51); #else mavlink_statustext_t packet; packet.severity = severity; mav_array_memcpy(packet.text, text, sizeof(int8_t)*50); - memcpy(_MAV_PAYLOAD(msg), &packet, 51); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 51); #endif msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; @@ -69,12 +69,12 @@ static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8 char buf[51]; _mav_put_uint8_t(buf, 0, severity); _mav_put_int8_t_array(buf, 1, text, 50); - memcpy(_MAV_PAYLOAD(msg), buf, 51); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 51); #else mavlink_statustext_t packet; packet.severity = severity; mav_array_memcpy(packet.text, text, sizeof(int8_t)*50); - memcpy(_MAV_PAYLOAD(msg), &packet, 51); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 51); #endif msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; diff --git a/mavlink/include/v0.9/common/mavlink_msg_sys_status.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_sys_status.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_sys_status.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_sys_status.h index 9add0d069fa9416988faf4aac20b4f98693b729f..1217ea60e9cb282a8dc821d1759b8005a0d8a095 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_sys_status.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_sys_status.h @@ -60,7 +60,7 @@ static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t co _mav_put_uint16_t(buf, 7, battery_remaining); _mav_put_uint16_t(buf, 9, packet_drop); - memcpy(_MAV_PAYLOAD(msg), buf, 11); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 11); #else mavlink_sys_status_t packet; packet.mode = mode; @@ -71,7 +71,7 @@ static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t co packet.battery_remaining = battery_remaining; packet.packet_drop = packet_drop; - memcpy(_MAV_PAYLOAD(msg), &packet, 11); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 11); #endif msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; @@ -107,7 +107,7 @@ static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8 _mav_put_uint16_t(buf, 7, battery_remaining); _mav_put_uint16_t(buf, 9, packet_drop); - memcpy(_MAV_PAYLOAD(msg), buf, 11); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 11); #else mavlink_sys_status_t packet; packet.mode = mode; @@ -118,7 +118,7 @@ static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8 packet.battery_remaining = battery_remaining; packet.packet_drop = packet_drop; - memcpy(_MAV_PAYLOAD(msg), &packet, 11); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 11); #endif msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; diff --git a/mavlink/include/v0.9/common/mavlink_msg_system_time.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_system_time.h similarity index 95% rename from mavlink/include/v0.9/common/mavlink_msg_system_time.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_system_time.h index cf2b1f6fe9462bb655540d95f38f6cc4a1ceaefc..362586a70d7523d7704bf83320dd5696e294b72b 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_system_time.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_system_time.h @@ -36,12 +36,12 @@ static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t c char buf[8]; _mav_put_uint64_t(buf, 0, time_usec); - memcpy(_MAV_PAYLOAD(msg), buf, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); #else mavlink_system_time_t packet; packet.time_usec = time_usec; - memcpy(_MAV_PAYLOAD(msg), &packet, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); #endif msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; @@ -65,12 +65,12 @@ static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint char buf[8]; _mav_put_uint64_t(buf, 0, time_usec); - memcpy(_MAV_PAYLOAD(msg), buf, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); #else mavlink_system_time_t packet; packet.time_usec = time_usec; - memcpy(_MAV_PAYLOAD(msg), &packet, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); #endif msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; diff --git a/mavlink/include/v0.9/common/mavlink_msg_system_time_utc.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_system_time_utc.h similarity index 95% rename from mavlink/include/v0.9/common/mavlink_msg_system_time_utc.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_system_time_utc.h index 70ebf56389d41fe6d98122b4f0caaa300bb152f6..5688435d53bcecf00640f4fec74622357a2c6962 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_system_time_utc.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_system_time_utc.h @@ -40,13 +40,13 @@ static inline uint16_t mavlink_msg_system_time_utc_pack(uint8_t system_id, uint8 _mav_put_uint32_t(buf, 0, utc_date); _mav_put_uint32_t(buf, 4, utc_time); - memcpy(_MAV_PAYLOAD(msg), buf, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); #else mavlink_system_time_utc_t packet; packet.utc_date = utc_date; packet.utc_time = utc_time; - memcpy(_MAV_PAYLOAD(msg), &packet, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); #endif msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME_UTC; @@ -72,13 +72,13 @@ static inline uint16_t mavlink_msg_system_time_utc_pack_chan(uint8_t system_id, _mav_put_uint32_t(buf, 0, utc_date); _mav_put_uint32_t(buf, 4, utc_time); - memcpy(_MAV_PAYLOAD(msg), buf, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); #else mavlink_system_time_utc_t packet; packet.utc_date = utc_date; packet.utc_time = utc_time; - memcpy(_MAV_PAYLOAD(msg), &packet, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); #endif msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME_UTC; diff --git a/mavlink/include/v0.9/common/mavlink_msg_vfr_hud.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_vfr_hud.h similarity index 97% rename from mavlink/include/v0.9/common/mavlink_msg_vfr_hud.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_vfr_hud.h index 705d8d4db0a1789cf66bc3c1337d94ec50bde843..0f92de775e9fe459853d4c48df51861d861ff75d 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_vfr_hud.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_vfr_hud.h @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t compo _mav_put_float(buf, 12, alt); _mav_put_float(buf, 16, climb); - memcpy(_MAV_PAYLOAD(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); #else mavlink_vfr_hud_t packet; packet.airspeed = airspeed; @@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t compo packet.alt = alt; packet.climb = climb; - memcpy(_MAV_PAYLOAD(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); #endif msg->msgid = MAVLINK_MSG_ID_VFR_HUD; @@ -100,7 +100,7 @@ static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t _mav_put_float(buf, 12, alt); _mav_put_float(buf, 16, climb); - memcpy(_MAV_PAYLOAD(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); #else mavlink_vfr_hud_t packet; packet.airspeed = airspeed; @@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t packet.alt = alt; packet.climb = climb; - memcpy(_MAV_PAYLOAD(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); #endif msg->msgid = MAVLINK_MSG_ID_VFR_HUD; diff --git a/mavlink/include/v0.9/common/mavlink_msg_waypoint.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint.h similarity index 98% rename from mavlink/include/v0.9/common/mavlink_msg_waypoint.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint.h index 27e89de1f7de68f09dc167b0f2819670a935c5bb..d9b21e3c94909ced74fbf4702409facb8b2763f1 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_waypoint.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint.h @@ -88,7 +88,7 @@ static inline uint16_t mavlink_msg_waypoint_pack(uint8_t system_id, uint8_t comp _mav_put_float(buf, 28, y); _mav_put_float(buf, 32, z); - memcpy(_MAV_PAYLOAD(msg), buf, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); #else mavlink_waypoint_t packet; packet.target_system = target_system; @@ -106,7 +106,7 @@ static inline uint16_t mavlink_msg_waypoint_pack(uint8_t system_id, uint8_t comp packet.y = y; packet.z = z; - memcpy(_MAV_PAYLOAD(msg), &packet, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); #endif msg->msgid = MAVLINK_MSG_ID_WAYPOINT; @@ -156,7 +156,7 @@ static inline uint16_t mavlink_msg_waypoint_pack_chan(uint8_t system_id, uint8_t _mav_put_float(buf, 28, y); _mav_put_float(buf, 32, z); - memcpy(_MAV_PAYLOAD(msg), buf, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); #else mavlink_waypoint_t packet; packet.target_system = target_system; @@ -174,7 +174,7 @@ static inline uint16_t mavlink_msg_waypoint_pack_chan(uint8_t system_id, uint8_t packet.y = y; packet.z = z; - memcpy(_MAV_PAYLOAD(msg), &packet, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); #endif msg->msgid = MAVLINK_MSG_ID_WAYPOINT; diff --git a/mavlink/include/v0.9/common/mavlink_msg_waypoint_ack.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_ack.h similarity index 96% rename from mavlink/include/v0.9/common/mavlink_msg_waypoint_ack.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_ack.h index 2b36087189f0b0cd2ae98ac834ecbb6e3c53cd51..ddba2adf4cae24c711498a1e84917fca49076708 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_waypoint_ack.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_ack.h @@ -44,14 +44,14 @@ static inline uint16_t mavlink_msg_waypoint_ack_pack(uint8_t system_id, uint8_t _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, type); - memcpy(_MAV_PAYLOAD(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); #else mavlink_waypoint_ack_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.type = type; - memcpy(_MAV_PAYLOAD(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); #endif msg->msgid = MAVLINK_MSG_ID_WAYPOINT_ACK; @@ -79,14 +79,14 @@ static inline uint16_t mavlink_msg_waypoint_ack_pack_chan(uint8_t system_id, uin _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint8_t(buf, 2, type); - memcpy(_MAV_PAYLOAD(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); #else mavlink_waypoint_ack_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.type = type; - memcpy(_MAV_PAYLOAD(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); #endif msg->msgid = MAVLINK_MSG_ID_WAYPOINT_ACK; diff --git a/mavlink/include/v0.9/common/mavlink_msg_waypoint_clear_all.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_clear_all.h similarity index 96% rename from mavlink/include/v0.9/common/mavlink_msg_waypoint_clear_all.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_clear_all.h index bca8dcc1f4b25a9b857093a0cabe0f8d10cff5c8..8eab44b2676752ab9706096a07b54c3d55938c67 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_waypoint_clear_all.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_clear_all.h @@ -40,13 +40,13 @@ static inline uint16_t mavlink_msg_waypoint_clear_all_pack(uint8_t system_id, ui _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); - memcpy(_MAV_PAYLOAD(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); #else mavlink_waypoint_clear_all_t packet; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); #endif msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL; @@ -72,13 +72,13 @@ static inline uint16_t mavlink_msg_waypoint_clear_all_pack_chan(uint8_t system_i _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); - memcpy(_MAV_PAYLOAD(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); #else mavlink_waypoint_clear_all_t packet; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); #endif msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL; diff --git a/mavlink/include/v0.9/common/mavlink_msg_waypoint_count.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_count.h similarity index 96% rename from mavlink/include/v0.9/common/mavlink_msg_waypoint_count.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_count.h index 73c62f831dd971ecdcf7509bf7ad22e16cfdf1c5..af1dd382b6e44166882219bdb73fcdafec08a8aa 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_waypoint_count.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_count.h @@ -44,14 +44,14 @@ static inline uint16_t mavlink_msg_waypoint_count_pack(uint8_t system_id, uint8_ _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint16_t(buf, 2, count); - memcpy(_MAV_PAYLOAD(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); #else mavlink_waypoint_count_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.count = count; - memcpy(_MAV_PAYLOAD(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); #endif msg->msgid = MAVLINK_MSG_ID_WAYPOINT_COUNT; @@ -79,14 +79,14 @@ static inline uint16_t mavlink_msg_waypoint_count_pack_chan(uint8_t system_id, u _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint16_t(buf, 2, count); - memcpy(_MAV_PAYLOAD(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); #else mavlink_waypoint_count_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.count = count; - memcpy(_MAV_PAYLOAD(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); #endif msg->msgid = MAVLINK_MSG_ID_WAYPOINT_COUNT; diff --git a/mavlink/include/v0.9/common/mavlink_msg_waypoint_current.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_current.h similarity index 94% rename from mavlink/include/v0.9/common/mavlink_msg_waypoint_current.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_current.h index 411b867667c8f7731b96162bc83a0f7f9d0d194d..a7e4557d6e0d105605ff925936360f0644ea228f 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_waypoint_current.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_current.h @@ -36,12 +36,12 @@ static inline uint16_t mavlink_msg_waypoint_current_pack(uint8_t system_id, uint char buf[2]; _mav_put_uint16_t(buf, 0, seq); - memcpy(_MAV_PAYLOAD(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); #else mavlink_waypoint_current_t packet; packet.seq = seq; - memcpy(_MAV_PAYLOAD(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); #endif msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CURRENT; @@ -65,12 +65,12 @@ static inline uint16_t mavlink_msg_waypoint_current_pack_chan(uint8_t system_id, char buf[2]; _mav_put_uint16_t(buf, 0, seq); - memcpy(_MAV_PAYLOAD(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); #else mavlink_waypoint_current_t packet; packet.seq = seq; - memcpy(_MAV_PAYLOAD(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); #endif msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CURRENT; diff --git a/mavlink/include/v0.9/common/mavlink_msg_waypoint_reached.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_reached.h similarity index 94% rename from mavlink/include/v0.9/common/mavlink_msg_waypoint_reached.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_reached.h index 6f291c7095f4b0147bc30f889372bd921f89346f..d28dce1494c9cd56f5591e9bdf13741ea92e64c4 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_waypoint_reached.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_reached.h @@ -36,12 +36,12 @@ static inline uint16_t mavlink_msg_waypoint_reached_pack(uint8_t system_id, uint char buf[2]; _mav_put_uint16_t(buf, 0, seq); - memcpy(_MAV_PAYLOAD(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); #else mavlink_waypoint_reached_t packet; packet.seq = seq; - memcpy(_MAV_PAYLOAD(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); #endif msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REACHED; @@ -65,12 +65,12 @@ static inline uint16_t mavlink_msg_waypoint_reached_pack_chan(uint8_t system_id, char buf[2]; _mav_put_uint16_t(buf, 0, seq); - memcpy(_MAV_PAYLOAD(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); #else mavlink_waypoint_reached_t packet; packet.seq = seq; - memcpy(_MAV_PAYLOAD(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); #endif msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REACHED; diff --git a/mavlink/include/v0.9/common/mavlink_msg_waypoint_request.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_request.h similarity index 96% rename from mavlink/include/v0.9/common/mavlink_msg_waypoint_request.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_request.h index e9d616ab1dd1d7f9686ce628041045711beb20b9..38167c0806907100afe37d8b7f98f31577963a6e 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_waypoint_request.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_request.h @@ -44,14 +44,14 @@ static inline uint16_t mavlink_msg_waypoint_request_pack(uint8_t system_id, uint _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint16_t(buf, 2, seq); - memcpy(_MAV_PAYLOAD(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); #else mavlink_waypoint_request_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.seq = seq; - memcpy(_MAV_PAYLOAD(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); #endif msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST; @@ -79,14 +79,14 @@ static inline uint16_t mavlink_msg_waypoint_request_pack_chan(uint8_t system_id, _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint16_t(buf, 2, seq); - memcpy(_MAV_PAYLOAD(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); #else mavlink_waypoint_request_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.seq = seq; - memcpy(_MAV_PAYLOAD(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); #endif msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST; diff --git a/mavlink/include/v0.9/common/mavlink_msg_waypoint_request_list.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_request_list.h similarity index 96% rename from mavlink/include/v0.9/common/mavlink_msg_waypoint_request_list.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_request_list.h index caeb62037505ae4f46590daec64f70c8cae335c9..ba21fbc82d679a5b4e34036b06ed9cdc9dd7895d 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_waypoint_request_list.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_request_list.h @@ -40,13 +40,13 @@ static inline uint16_t mavlink_msg_waypoint_request_list_pack(uint8_t system_id, _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); - memcpy(_MAV_PAYLOAD(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); #else mavlink_waypoint_request_list_t packet; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); #endif msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST; @@ -72,13 +72,13 @@ static inline uint16_t mavlink_msg_waypoint_request_list_pack_chan(uint8_t syste _mav_put_uint8_t(buf, 0, target_system); _mav_put_uint8_t(buf, 1, target_component); - memcpy(_MAV_PAYLOAD(msg), buf, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); #else mavlink_waypoint_request_list_t packet; packet.target_system = target_system; packet.target_component = target_component; - memcpy(_MAV_PAYLOAD(msg), &packet, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); #endif msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST; diff --git a/mavlink/include/v0.9/common/mavlink_msg_waypoint_set_current.h b/mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_set_current.h similarity index 96% rename from mavlink/include/v0.9/common/mavlink_msg_waypoint_set_current.h rename to mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_set_current.h index 7a9fd614a4369dac0903706c0d2c7a8a69cc6ca3..f1ba68b456ef66173e981ded6a8822c56be9f405 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_waypoint_set_current.h +++ b/mavlink/include/mavlink/v0.9/common/mavlink_msg_waypoint_set_current.h @@ -44,14 +44,14 @@ static inline uint16_t mavlink_msg_waypoint_set_current_pack(uint8_t system_id, _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint16_t(buf, 2, seq); - memcpy(_MAV_PAYLOAD(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); #else mavlink_waypoint_set_current_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.seq = seq; - memcpy(_MAV_PAYLOAD(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); #endif msg->msgid = MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT; @@ -79,14 +79,14 @@ static inline uint16_t mavlink_msg_waypoint_set_current_pack_chan(uint8_t system _mav_put_uint8_t(buf, 1, target_component); _mav_put_uint16_t(buf, 2, seq); - memcpy(_MAV_PAYLOAD(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); #else mavlink_waypoint_set_current_t packet; packet.target_system = target_system; packet.target_component = target_component; packet.seq = seq; - memcpy(_MAV_PAYLOAD(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); #endif msg->msgid = MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT; diff --git a/mavlink/include/v0.9/common/testsuite.h b/mavlink/include/mavlink/v0.9/common/testsuite.h similarity index 100% rename from mavlink/include/v0.9/common/testsuite.h rename to mavlink/include/mavlink/v0.9/common/testsuite.h diff --git a/mavlink/include/v0.9/common/version.h b/mavlink/include/mavlink/v0.9/common/version.h similarity index 84% rename from mavlink/include/v0.9/common/version.h rename to mavlink/include/mavlink/v0.9/common/version.h index a1761418f5666680146d03d8c1cdae4115b847b4..11206e4a034a25e0d958632e30b627b245fc5041 100644 --- a/mavlink/include/v0.9/common/version.h +++ b/mavlink/include/mavlink/v0.9/common/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Mar 1 01:19:41 2012" +#define MAVLINK_BUILD_DATE "Thu Apr 19 19:46:08 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "0.9" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/files/mavlink_generator/generator/C/include_v0.9/mavlink_helpers.h b/mavlink/include/mavlink/v0.9/mavlink_helpers.h similarity index 100% rename from files/mavlink_generator/generator/C/include_v0.9/mavlink_helpers.h rename to mavlink/include/mavlink/v0.9/mavlink_helpers.h diff --git a/files/mavlink_generator/generator/C/include_v0.9/mavlink_types.h b/mavlink/include/mavlink/v0.9/mavlink_types.h similarity index 99% rename from files/mavlink_generator/generator/C/include_v0.9/mavlink_types.h rename to mavlink/include/mavlink/v0.9/mavlink_types.h index 9daeffc63f7347027bffed188c00431744898174..c9c5fc47fb4856c93454fd6d62ad5ba4545d0628 100644 --- a/files/mavlink_generator/generator/C/include_v0.9/mavlink_types.h +++ b/mavlink/include/mavlink/v0.9/mavlink_types.h @@ -140,6 +140,7 @@ enum MAV_COMPONENT MAV_COMP_ID_AIRSLAM, MAV_COMP_ID_MAPPER, MAV_COMP_ID_CAMERA, + MAV_COMP_ID_RADIO = 68, MAV_COMP_ID_IMU = 200, MAV_COMP_ID_IMU_2 = 201, MAV_COMP_ID_IMU_3 = 202, diff --git a/mavlink/include/v0.9/minimal/mavlink.h b/mavlink/include/mavlink/v0.9/minimal/mavlink.h similarity index 100% rename from mavlink/include/v0.9/minimal/mavlink.h rename to mavlink/include/mavlink/v0.9/minimal/mavlink.h diff --git a/mavlink/include/v0.9/common/mavlink_msg_heartbeat.h b/mavlink/include/mavlink/v0.9/minimal/mavlink_msg_heartbeat.h similarity index 96% rename from mavlink/include/v0.9/common/mavlink_msg_heartbeat.h rename to mavlink/include/mavlink/v0.9/minimal/mavlink_msg_heartbeat.h index 86bf637b1b439cdb77079fa657b21426be213889..aad90d29f3dd7f2b6970ad4cc9b724c257b33bfd 100644 --- a/mavlink/include/v0.9/common/mavlink_msg_heartbeat.h +++ b/mavlink/include/mavlink/v0.9/minimal/mavlink_msg_heartbeat.h @@ -43,14 +43,14 @@ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t com _mav_put_uint8_t(buf, 1, autopilot); _mav_put_uint8_t(buf, 2, 2); - memcpy(_MAV_PAYLOAD(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); #else mavlink_heartbeat_t packet; packet.type = type; packet.autopilot = autopilot; packet.mavlink_version = 2; - memcpy(_MAV_PAYLOAD(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); #endif msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; @@ -77,14 +77,14 @@ static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_ _mav_put_uint8_t(buf, 1, autopilot); _mav_put_uint8_t(buf, 2, 2); - memcpy(_MAV_PAYLOAD(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); #else mavlink_heartbeat_t packet; packet.type = type; packet.autopilot = autopilot; packet.mavlink_version = 2; - memcpy(_MAV_PAYLOAD(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); #endif msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; diff --git a/mavlink/include/v1.0/minimal/minimal.h b/mavlink/include/mavlink/v0.9/minimal/minimal.h similarity index 99% rename from mavlink/include/v1.0/minimal/minimal.h rename to mavlink/include/mavlink/v0.9/minimal/minimal.h index 43c6bd3adfed40feacea05e3da7e166a3ec37e5c..5979f806b83db4b95972c51d2ac0705f91ec8ef0 100644 --- a/mavlink/include/v1.0/minimal/minimal.h +++ b/mavlink/include/mavlink/v0.9/minimal/minimal.h @@ -12,11 +12,11 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#define MAVLINK_MESSAGE_LENGTHS {3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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 {50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#define MAVLINK_MESSAGE_CRCS {72, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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 diff --git a/mavlink/include/v0.9/minimal/testsuite.h b/mavlink/include/mavlink/v0.9/minimal/testsuite.h similarity index 100% rename from mavlink/include/v0.9/minimal/testsuite.h rename to mavlink/include/mavlink/v0.9/minimal/testsuite.h diff --git a/mavlink/include/v0.9/minimal/version.h b/mavlink/include/mavlink/v0.9/minimal/version.h similarity index 84% rename from mavlink/include/v0.9/minimal/version.h rename to mavlink/include/mavlink/v0.9/minimal/version.h index 4a62db08b4d0683be8b5df5a8048da72210d805d..bcbe878aaa202584abf07e1e0453af00f493c7dd 100644 --- a/mavlink/include/v0.9/minimal/version.h +++ b/mavlink/include/mavlink/v0.9/minimal/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Mar 1 01:19:39 2012" +#define MAVLINK_BUILD_DATE "Thu Apr 19 19:43:27 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "0.9" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 3 diff --git a/files/mavlink_generator/generator/C/include_v0.9/protocol.h b/mavlink/include/mavlink/v0.9/protocol.h similarity index 100% rename from files/mavlink_generator/generator/C/include_v0.9/protocol.h rename to mavlink/include/mavlink/v0.9/protocol.h diff --git a/mavlink/include/v0.9/slugs/mavlink.h b/mavlink/include/mavlink/v0.9/slugs/mavlink.h similarity index 100% rename from mavlink/include/v0.9/slugs/mavlink.h rename to mavlink/include/mavlink/v0.9/slugs/mavlink.h diff --git a/mavlink/include/v0.9/slugs/mavlink_msg_air_data.h b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_air_data.h similarity index 96% rename from mavlink/include/v0.9/slugs/mavlink_msg_air_data.h rename to mavlink/include/mavlink/v0.9/slugs/mavlink_msg_air_data.h index e093258ac706050397b00732075b0b8366586ba4..a9e3cad36e1c9d6c945d0bc361cef87a6b16b59b 100644 --- a/mavlink/include/v0.9/slugs/mavlink_msg_air_data.h +++ b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_air_data.h @@ -44,14 +44,14 @@ static inline uint16_t mavlink_msg_air_data_pack(uint8_t system_id, uint8_t comp _mav_put_float(buf, 4, staticPressure); _mav_put_uint16_t(buf, 8, temperature); - memcpy(_MAV_PAYLOAD(msg), buf, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 10); #else mavlink_air_data_t packet; packet.dynamicPressure = dynamicPressure; packet.staticPressure = staticPressure; packet.temperature = temperature; - memcpy(_MAV_PAYLOAD(msg), &packet, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 10); #endif msg->msgid = MAVLINK_MSG_ID_AIR_DATA; @@ -79,14 +79,14 @@ static inline uint16_t mavlink_msg_air_data_pack_chan(uint8_t system_id, uint8_t _mav_put_float(buf, 4, staticPressure); _mav_put_uint16_t(buf, 8, temperature); - memcpy(_MAV_PAYLOAD(msg), buf, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 10); #else mavlink_air_data_t packet; packet.dynamicPressure = dynamicPressure; packet.staticPressure = staticPressure; packet.temperature = temperature; - memcpy(_MAV_PAYLOAD(msg), &packet, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 10); #endif msg->msgid = MAVLINK_MSG_ID_AIR_DATA; diff --git a/mavlink/include/v0.9/slugs/mavlink_msg_cpu_load.h b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_cpu_load.h similarity index 96% rename from mavlink/include/v0.9/slugs/mavlink_msg_cpu_load.h rename to mavlink/include/mavlink/v0.9/slugs/mavlink_msg_cpu_load.h index 04e44d19b6b54b41f983216f5659ee51d9b6dd0e..a3bc972f1bd1c3b78cbeb5ea93c91a20b348da51 100644 --- a/mavlink/include/v0.9/slugs/mavlink_msg_cpu_load.h +++ b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_cpu_load.h @@ -44,14 +44,14 @@ static inline uint16_t mavlink_msg_cpu_load_pack(uint8_t system_id, uint8_t comp _mav_put_uint8_t(buf, 1, ctrlLoad); _mav_put_uint16_t(buf, 2, batVolt); - memcpy(_MAV_PAYLOAD(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); #else mavlink_cpu_load_t packet; packet.sensLoad = sensLoad; packet.ctrlLoad = ctrlLoad; packet.batVolt = batVolt; - memcpy(_MAV_PAYLOAD(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); #endif msg->msgid = MAVLINK_MSG_ID_CPU_LOAD; @@ -79,14 +79,14 @@ static inline uint16_t mavlink_msg_cpu_load_pack_chan(uint8_t system_id, uint8_t _mav_put_uint8_t(buf, 1, ctrlLoad); _mav_put_uint16_t(buf, 2, batVolt); - memcpy(_MAV_PAYLOAD(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); #else mavlink_cpu_load_t packet; packet.sensLoad = sensLoad; packet.ctrlLoad = ctrlLoad; packet.batVolt = batVolt; - memcpy(_MAV_PAYLOAD(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); #endif msg->msgid = MAVLINK_MSG_ID_CPU_LOAD; diff --git a/mavlink/include/v0.9/slugs/mavlink_msg_ctrl_srfc_pt.h b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_ctrl_srfc_pt.h similarity index 95% rename from mavlink/include/v0.9/slugs/mavlink_msg_ctrl_srfc_pt.h rename to mavlink/include/mavlink/v0.9/slugs/mavlink_msg_ctrl_srfc_pt.h index c991aea386f54efb8fb5e12c7007cb5f54ea9feb..d6f94e1dac0bec90f77e1bd351e723e234bfa779 100644 --- a/mavlink/include/v0.9/slugs/mavlink_msg_ctrl_srfc_pt.h +++ b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_ctrl_srfc_pt.h @@ -40,13 +40,13 @@ static inline uint16_t mavlink_msg_ctrl_srfc_pt_pack(uint8_t system_id, uint8_t _mav_put_uint8_t(buf, 0, target); _mav_put_uint16_t(buf, 1, bitfieldPt); - memcpy(_MAV_PAYLOAD(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); #else mavlink_ctrl_srfc_pt_t packet; packet.target = target; packet.bitfieldPt = bitfieldPt; - memcpy(_MAV_PAYLOAD(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); #endif msg->msgid = MAVLINK_MSG_ID_CTRL_SRFC_PT; @@ -72,13 +72,13 @@ static inline uint16_t mavlink_msg_ctrl_srfc_pt_pack_chan(uint8_t system_id, uin _mav_put_uint8_t(buf, 0, target); _mav_put_uint16_t(buf, 1, bitfieldPt); - memcpy(_MAV_PAYLOAD(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); #else mavlink_ctrl_srfc_pt_t packet; packet.target = target; packet.bitfieldPt = bitfieldPt; - memcpy(_MAV_PAYLOAD(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); #endif msg->msgid = MAVLINK_MSG_ID_CTRL_SRFC_PT; diff --git a/mavlink/include/v0.9/slugs/mavlink_msg_data_log.h b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_data_log.h similarity index 96% rename from mavlink/include/v0.9/slugs/mavlink_msg_data_log.h rename to mavlink/include/mavlink/v0.9/slugs/mavlink_msg_data_log.h index a375796b7a956acc5b93794273af409534f7f783..19a03e5c683151fd7747832291af2a1f694bc847 100644 --- a/mavlink/include/v0.9/slugs/mavlink_msg_data_log.h +++ b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_data_log.h @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_data_log_pack(uint8_t system_id, uint8_t comp _mav_put_float(buf, 16, fl_5); _mav_put_float(buf, 20, fl_6); - memcpy(_MAV_PAYLOAD(msg), buf, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24); #else mavlink_data_log_t packet; packet.fl_1 = fl_1; @@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_data_log_pack(uint8_t system_id, uint8_t comp packet.fl_5 = fl_5; packet.fl_6 = fl_6; - memcpy(_MAV_PAYLOAD(msg), &packet, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24); #endif msg->msgid = MAVLINK_MSG_ID_DATA_LOG; @@ -100,7 +100,7 @@ static inline uint16_t mavlink_msg_data_log_pack_chan(uint8_t system_id, uint8_t _mav_put_float(buf, 16, fl_5); _mav_put_float(buf, 20, fl_6); - memcpy(_MAV_PAYLOAD(msg), buf, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24); #else mavlink_data_log_t packet; packet.fl_1 = fl_1; @@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_data_log_pack_chan(uint8_t system_id, uint8_t packet.fl_5 = fl_5; packet.fl_6 = fl_6; - memcpy(_MAV_PAYLOAD(msg), &packet, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24); #endif msg->msgid = MAVLINK_MSG_ID_DATA_LOG; diff --git a/mavlink/include/v0.9/slugs/mavlink_msg_diagnostic.h b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_diagnostic.h similarity index 97% rename from mavlink/include/v0.9/slugs/mavlink_msg_diagnostic.h rename to mavlink/include/mavlink/v0.9/slugs/mavlink_msg_diagnostic.h index 4545c72fb9e9ee291f170abdeafef3c12c48c6e0..5cdf890aea79ebd5f1fad80daec9d78a688fdb15 100644 --- a/mavlink/include/v0.9/slugs/mavlink_msg_diagnostic.h +++ b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_diagnostic.h @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_diagnostic_pack(uint8_t system_id, uint8_t co _mav_put_int16_t(buf, 14, diagSh2); _mav_put_int16_t(buf, 16, diagSh3); - memcpy(_MAV_PAYLOAD(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); #else mavlink_diagnostic_t packet; packet.diagFl1 = diagFl1; @@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_diagnostic_pack(uint8_t system_id, uint8_t co packet.diagSh2 = diagSh2; packet.diagSh3 = diagSh3; - memcpy(_MAV_PAYLOAD(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); #endif msg->msgid = MAVLINK_MSG_ID_DIAGNOSTIC; @@ -100,7 +100,7 @@ static inline uint16_t mavlink_msg_diagnostic_pack_chan(uint8_t system_id, uint8 _mav_put_int16_t(buf, 14, diagSh2); _mav_put_int16_t(buf, 16, diagSh3); - memcpy(_MAV_PAYLOAD(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); #else mavlink_diagnostic_t packet; packet.diagFl1 = diagFl1; @@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_diagnostic_pack_chan(uint8_t system_id, uint8 packet.diagSh2 = diagSh2; packet.diagSh3 = diagSh3; - memcpy(_MAV_PAYLOAD(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); #endif msg->msgid = MAVLINK_MSG_ID_DIAGNOSTIC; diff --git a/mavlink/include/v0.9/slugs/mavlink_msg_gps_date_time.h b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_gps_date_time.h similarity index 97% rename from mavlink/include/v0.9/slugs/mavlink_msg_gps_date_time.h rename to mavlink/include/mavlink/v0.9/slugs/mavlink_msg_gps_date_time.h index 81d3595ceba3c043dc4b98c3b55e1255b8c7017c..6104fd7a7bec1ecf514b16f1bc679fe27ae16810 100644 --- a/mavlink/include/v0.9/slugs/mavlink_msg_gps_date_time.h +++ b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_gps_date_time.h @@ -60,7 +60,7 @@ static inline uint16_t mavlink_msg_gps_date_time_pack(uint8_t system_id, uint8_t _mav_put_uint8_t(buf, 5, sec); _mav_put_uint8_t(buf, 6, visSat); - memcpy(_MAV_PAYLOAD(msg), buf, 7); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 7); #else mavlink_gps_date_time_t packet; packet.year = year; @@ -71,7 +71,7 @@ static inline uint16_t mavlink_msg_gps_date_time_pack(uint8_t system_id, uint8_t packet.sec = sec; packet.visSat = visSat; - memcpy(_MAV_PAYLOAD(msg), &packet, 7); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 7); #endif msg->msgid = MAVLINK_MSG_ID_GPS_DATE_TIME; @@ -107,7 +107,7 @@ static inline uint16_t mavlink_msg_gps_date_time_pack_chan(uint8_t system_id, ui _mav_put_uint8_t(buf, 5, sec); _mav_put_uint8_t(buf, 6, visSat); - memcpy(_MAV_PAYLOAD(msg), buf, 7); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 7); #else mavlink_gps_date_time_t packet; packet.year = year; @@ -118,7 +118,7 @@ static inline uint16_t mavlink_msg_gps_date_time_pack_chan(uint8_t system_id, ui packet.sec = sec; packet.visSat = visSat; - memcpy(_MAV_PAYLOAD(msg), &packet, 7); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 7); #endif msg->msgid = MAVLINK_MSG_ID_GPS_DATE_TIME; diff --git a/mavlink/include/v0.9/slugs/mavlink_msg_mid_lvl_cmds.h b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_mid_lvl_cmds.h similarity index 96% rename from mavlink/include/v0.9/slugs/mavlink_msg_mid_lvl_cmds.h rename to mavlink/include/mavlink/v0.9/slugs/mavlink_msg_mid_lvl_cmds.h index abb49ab88f79f5efee4bdd21dc953049c697eacc..4ae723b440224ac979fb00e3ef9b5641602898ef 100644 --- a/mavlink/include/v0.9/slugs/mavlink_msg_mid_lvl_cmds.h +++ b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_mid_lvl_cmds.h @@ -48,7 +48,7 @@ static inline uint16_t mavlink_msg_mid_lvl_cmds_pack(uint8_t system_id, uint8_t _mav_put_float(buf, 5, uCommand); _mav_put_float(buf, 9, rCommand); - memcpy(_MAV_PAYLOAD(msg), buf, 13); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13); #else mavlink_mid_lvl_cmds_t packet; packet.target = target; @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_mid_lvl_cmds_pack(uint8_t system_id, uint8_t packet.uCommand = uCommand; packet.rCommand = rCommand; - memcpy(_MAV_PAYLOAD(msg), &packet, 13); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13); #endif msg->msgid = MAVLINK_MSG_ID_MID_LVL_CMDS; @@ -86,7 +86,7 @@ static inline uint16_t mavlink_msg_mid_lvl_cmds_pack_chan(uint8_t system_id, uin _mav_put_float(buf, 5, uCommand); _mav_put_float(buf, 9, rCommand); - memcpy(_MAV_PAYLOAD(msg), buf, 13); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13); #else mavlink_mid_lvl_cmds_t packet; packet.target = target; @@ -94,7 +94,7 @@ static inline uint16_t mavlink_msg_mid_lvl_cmds_pack_chan(uint8_t system_id, uin packet.uCommand = uCommand; packet.rCommand = rCommand; - memcpy(_MAV_PAYLOAD(msg), &packet, 13); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13); #endif msg->msgid = MAVLINK_MSG_ID_MID_LVL_CMDS; diff --git a/mavlink/include/v0.9/slugs/mavlink_msg_sensor_bias.h b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_sensor_bias.h similarity index 97% rename from mavlink/include/v0.9/slugs/mavlink_msg_sensor_bias.h rename to mavlink/include/mavlink/v0.9/slugs/mavlink_msg_sensor_bias.h index 3f10d85a4a53fadb265a371369abda0008b5ce76..7afb96bd64a7d8b357654d77739cb03d8cffbf1d 100644 --- a/mavlink/include/v0.9/slugs/mavlink_msg_sensor_bias.h +++ b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_sensor_bias.h @@ -56,7 +56,7 @@ static inline uint16_t mavlink_msg_sensor_bias_pack(uint8_t system_id, uint8_t c _mav_put_float(buf, 16, gyBias); _mav_put_float(buf, 20, gzBias); - memcpy(_MAV_PAYLOAD(msg), buf, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24); #else mavlink_sensor_bias_t packet; packet.axBias = axBias; @@ -66,7 +66,7 @@ static inline uint16_t mavlink_msg_sensor_bias_pack(uint8_t system_id, uint8_t c packet.gyBias = gyBias; packet.gzBias = gzBias; - memcpy(_MAV_PAYLOAD(msg), &packet, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24); #endif msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS; @@ -100,7 +100,7 @@ static inline uint16_t mavlink_msg_sensor_bias_pack_chan(uint8_t system_id, uint _mav_put_float(buf, 16, gyBias); _mav_put_float(buf, 20, gzBias); - memcpy(_MAV_PAYLOAD(msg), buf, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24); #else mavlink_sensor_bias_t packet; packet.axBias = axBias; @@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_sensor_bias_pack_chan(uint8_t system_id, uint packet.gyBias = gyBias; packet.gzBias = gzBias; - memcpy(_MAV_PAYLOAD(msg), &packet, 24); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24); #endif msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS; diff --git a/mavlink/include/v0.9/slugs/mavlink_msg_slugs_action.h b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_slugs_action.h similarity index 96% rename from mavlink/include/v0.9/slugs/mavlink_msg_slugs_action.h rename to mavlink/include/mavlink/v0.9/slugs/mavlink_msg_slugs_action.h index a7f825f33866fb280e7af9c6479cf0a9d39cd461..da56b98b5ab737f647907e94ade3619607949f2c 100644 --- a/mavlink/include/v0.9/slugs/mavlink_msg_slugs_action.h +++ b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_slugs_action.h @@ -44,14 +44,14 @@ static inline uint16_t mavlink_msg_slugs_action_pack(uint8_t system_id, uint8_t _mav_put_uint8_t(buf, 1, actionId); _mav_put_uint16_t(buf, 2, actionVal); - memcpy(_MAV_PAYLOAD(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); #else mavlink_slugs_action_t packet; packet.target = target; packet.actionId = actionId; packet.actionVal = actionVal; - memcpy(_MAV_PAYLOAD(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); #endif msg->msgid = MAVLINK_MSG_ID_SLUGS_ACTION; @@ -79,14 +79,14 @@ static inline uint16_t mavlink_msg_slugs_action_pack_chan(uint8_t system_id, uin _mav_put_uint8_t(buf, 1, actionId); _mav_put_uint16_t(buf, 2, actionVal); - memcpy(_MAV_PAYLOAD(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); #else mavlink_slugs_action_t packet; packet.target = target; packet.actionId = actionId; packet.actionVal = actionVal; - memcpy(_MAV_PAYLOAD(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); #endif msg->msgid = MAVLINK_MSG_ID_SLUGS_ACTION; diff --git a/mavlink/include/v0.9/slugs/mavlink_msg_slugs_navigation.h b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_slugs_navigation.h similarity index 98% rename from mavlink/include/v0.9/slugs/mavlink_msg_slugs_navigation.h rename to mavlink/include/mavlink/v0.9/slugs/mavlink_msg_slugs_navigation.h index a5804bccf60cc128d78a9b3612f147ad4349d91d..b81bde72ffcdee9997bc0dc9316dd34e40fb3ffa 100644 --- a/mavlink/include/v0.9/slugs/mavlink_msg_slugs_navigation.h +++ b/mavlink/include/mavlink/v0.9/slugs/mavlink_msg_slugs_navigation.h @@ -68,7 +68,7 @@ static inline uint16_t mavlink_msg_slugs_navigation_pack(uint8_t system_id, uint _mav_put_uint8_t(buf, 28, fromWP); _mav_put_uint8_t(buf, 29, toWP); - memcpy(_MAV_PAYLOAD(msg), buf, 30); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30); #else mavlink_slugs_navigation_t packet; packet.u_m = u_m; @@ -81,7 +81,7 @@ static inline uint16_t mavlink_msg_slugs_navigation_pack(uint8_t system_id, uint packet.fromWP = fromWP; packet.toWP = toWP; - memcpy(_MAV_PAYLOAD(msg), &packet, 30); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30); #endif msg->msgid = MAVLINK_MSG_ID_SLUGS_NAVIGATION; @@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_slugs_navigation_pack_chan(uint8_t system_id, _mav_put_uint8_t(buf, 28, fromWP); _mav_put_uint8_t(buf, 29, toWP); - memcpy(_MAV_PAYLOAD(msg), buf, 30); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30); #else mavlink_slugs_navigation_t packet; packet.u_m = u_m; @@ -134,7 +134,7 @@ static inline uint16_t mavlink_msg_slugs_navigation_pack_chan(uint8_t system_id, packet.fromWP = fromWP; packet.toWP = toWP; - memcpy(_MAV_PAYLOAD(msg), &packet, 30); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30); #endif msg->msgid = MAVLINK_MSG_ID_SLUGS_NAVIGATION; diff --git a/mavlink/include/mavlink/v0.9/slugs/slugs.h b/mavlink/include/mavlink/v0.9/slugs/slugs.h new file mode 100644 index 0000000000000000000000000000000000000000..27f4e10beea6db131106b0860c7358ca4a7abece --- /dev/null +++ b/mavlink/include/mavlink/v0.9/slugs/slugs.h @@ -0,0 +1,62 @@ +/** @file + * @brief MAVLink comm protocol generated from slugs.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef SLUGS_H +#define SLUGS_H + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 4, 10, 24, 18, 0, 0, 30, 24, 0, 7, 13, 3, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 150, 232, 168, 2, 0, 0, 120, 167, 0, 16, 2, 52, 0, 202, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_BOOT, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACTION_ACK, MAVLINK_MESSAGE_INFO_ACTION, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_SET_NAV_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_LOCAL_POSITION, MAVLINK_MESSAGE_INFO_GPS_RAW, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_WAYPOINT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST, MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT, MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL, MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED, MAVLINK_MESSAGE_INFO_WAYPOINT_ACK, MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_CONTROL_STATUS, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_POSITION_TARGET, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_SET_ALTITUDE, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CPU_LOAD, MAVLINK_MESSAGE_INFO_AIR_DATA, MAVLINK_MESSAGE_INFO_SENSOR_BIAS, MAVLINK_MESSAGE_INFO_DIAGNOSTIC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SLUGS_NAVIGATION, MAVLINK_MESSAGE_INFO_DATA_LOG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_GPS_DATE_TIME, MAVLINK_MESSAGE_INFO_MID_LVL_CMDS, MAVLINK_MESSAGE_INFO_CTRL_SRFC_PT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SLUGS_ACTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_SLUGS + +#include "../common/common.h" + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +// ENUM DEFINITIONS + + + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_cpu_load.h" +#include "./mavlink_msg_air_data.h" +#include "./mavlink_msg_sensor_bias.h" +#include "./mavlink_msg_diagnostic.h" +#include "./mavlink_msg_slugs_navigation.h" +#include "./mavlink_msg_data_log.h" +#include "./mavlink_msg_gps_date_time.h" +#include "./mavlink_msg_mid_lvl_cmds.h" +#include "./mavlink_msg_ctrl_srfc_pt.h" +#include "./mavlink_msg_slugs_action.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // SLUGS_H diff --git a/mavlink/include/v0.9/slugs/testsuite.h b/mavlink/include/mavlink/v0.9/slugs/testsuite.h similarity index 100% rename from mavlink/include/v0.9/slugs/testsuite.h rename to mavlink/include/mavlink/v0.9/slugs/testsuite.h diff --git a/mavlink/include/v0.9/slugs/version.h b/mavlink/include/mavlink/v0.9/slugs/version.h similarity index 84% rename from mavlink/include/v0.9/slugs/version.h rename to mavlink/include/mavlink/v0.9/slugs/version.h index 81857a87a332014b72e7b195336e7b97fb314e05..20c5607b2d43f10738b7f8e11abb913fa6bf4559 100644 --- a/mavlink/include/v0.9/slugs/version.h +++ b/mavlink/include/mavlink/v0.9/slugs/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Mar 1 01:19:40 2012" +#define MAVLINK_BUILD_DATE "Thu Apr 19 19:44:32 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "0.9" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/mavlink/include/v0.9/pixhawk/mavlink.h b/mavlink/include/mavlink/v0.9/test/mavlink.h similarity index 84% rename from mavlink/include/v0.9/pixhawk/mavlink.h rename to mavlink/include/mavlink/v0.9/test/mavlink.h index 81c47524bffc817086f8ba04e4b6710fecf180d3..5b91bfe2d27c24e5406f883138bcaa0878dd16ba 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink.h +++ b/mavlink/include/mavlink/v0.9/test/mavlink.h @@ -1,5 +1,5 @@ /** @file - * @brief MAVLink comm protocol built from pixhawk.xml + * @brief MAVLink comm protocol built from test.xml * @see http://pixhawk.ethz.ch/software/mavlink */ #ifndef MAVLINK_H @@ -22,6 +22,6 @@ #endif #include "version.h" -#include "pixhawk.h" +#include "test.h" #endif // MAVLINK_H diff --git a/mavlink/include/mavlink/v0.9/test/mavlink_msg_test_types.h b/mavlink/include/mavlink/v0.9/test/mavlink_msg_test_types.h new file mode 100644 index 0000000000000000000000000000000000000000..fb8c5ee1f8c10a99778a323be1e8d55ff1eced69 --- /dev/null +++ b/mavlink/include/mavlink/v0.9/test/mavlink_msg_test_types.h @@ -0,0 +1,610 @@ +// MESSAGE TEST_TYPES PACKING + +#define MAVLINK_MSG_ID_TEST_TYPES 0 + +typedef struct __mavlink_test_types_t +{ + char c; ///< char + char s[10]; ///< string + uint8_t u8; ///< uint8_t + uint16_t u16; ///< uint16_t + uint32_t u32; ///< uint32_t + uint64_t u64; ///< uint64_t + int8_t s8; ///< int8_t + int16_t s16; ///< int16_t + int32_t s32; ///< int32_t + int64_t s64; ///< int64_t + float f; ///< float + double d; ///< double + uint8_t u8_array[3]; ///< uint8_t_array + uint16_t u16_array[3]; ///< uint16_t_array + uint32_t u32_array[3]; ///< uint32_t_array + uint64_t u64_array[3]; ///< uint64_t_array + int8_t s8_array[3]; ///< int8_t_array + int16_t s16_array[3]; ///< int16_t_array + int32_t s32_array[3]; ///< int32_t_array + int64_t s64_array[3]; ///< int64_t_array + float f_array[3]; ///< float_array + double d_array[3]; ///< double_array +} mavlink_test_types_t; + +#define MAVLINK_MSG_ID_TEST_TYPES_LEN 179 +#define MAVLINK_MSG_ID_0_LEN 179 + +#define MAVLINK_MSG_TEST_TYPES_FIELD_S_LEN 10 +#define MAVLINK_MSG_TEST_TYPES_FIELD_U8_ARRAY_LEN 3 +#define MAVLINK_MSG_TEST_TYPES_FIELD_U16_ARRAY_LEN 3 +#define MAVLINK_MSG_TEST_TYPES_FIELD_U32_ARRAY_LEN 3 +#define MAVLINK_MSG_TEST_TYPES_FIELD_U64_ARRAY_LEN 3 +#define MAVLINK_MSG_TEST_TYPES_FIELD_S8_ARRAY_LEN 3 +#define MAVLINK_MSG_TEST_TYPES_FIELD_S16_ARRAY_LEN 3 +#define MAVLINK_MSG_TEST_TYPES_FIELD_S32_ARRAY_LEN 3 +#define MAVLINK_MSG_TEST_TYPES_FIELD_S64_ARRAY_LEN 3 +#define MAVLINK_MSG_TEST_TYPES_FIELD_F_ARRAY_LEN 3 +#define MAVLINK_MSG_TEST_TYPES_FIELD_D_ARRAY_LEN 3 + +#define MAVLINK_MESSAGE_INFO_TEST_TYPES { \ + "TEST_TYPES", \ + 22, \ + { { "c", NULL, MAVLINK_TYPE_CHAR, 0, 0, offsetof(mavlink_test_types_t, c) }, \ + { "s", NULL, MAVLINK_TYPE_CHAR, 10, 1, offsetof(mavlink_test_types_t, s) }, \ + { "u8", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_test_types_t, u8) }, \ + { "u16", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_test_types_t, u16) }, \ + { "u32", "0x%08x", MAVLINK_TYPE_UINT32_T, 0, 14, offsetof(mavlink_test_types_t, u32) }, \ + { "u64", NULL, MAVLINK_TYPE_UINT64_T, 0, 18, offsetof(mavlink_test_types_t, u64) }, \ + { "s8", NULL, MAVLINK_TYPE_INT8_T, 0, 26, offsetof(mavlink_test_types_t, s8) }, \ + { "s16", NULL, MAVLINK_TYPE_INT16_T, 0, 27, offsetof(mavlink_test_types_t, s16) }, \ + { "s32", NULL, MAVLINK_TYPE_INT32_T, 0, 29, offsetof(mavlink_test_types_t, s32) }, \ + { "s64", NULL, MAVLINK_TYPE_INT64_T, 0, 33, offsetof(mavlink_test_types_t, s64) }, \ + { "f", NULL, MAVLINK_TYPE_FLOAT, 0, 41, offsetof(mavlink_test_types_t, f) }, \ + { "d", NULL, MAVLINK_TYPE_DOUBLE, 0, 45, offsetof(mavlink_test_types_t, d) }, \ + { "u8_array", NULL, MAVLINK_TYPE_UINT8_T, 3, 53, offsetof(mavlink_test_types_t, u8_array) }, \ + { "u16_array", NULL, MAVLINK_TYPE_UINT16_T, 3, 56, offsetof(mavlink_test_types_t, u16_array) }, \ + { "u32_array", NULL, MAVLINK_TYPE_UINT32_T, 3, 62, offsetof(mavlink_test_types_t, u32_array) }, \ + { "u64_array", NULL, MAVLINK_TYPE_UINT64_T, 3, 74, offsetof(mavlink_test_types_t, u64_array) }, \ + { "s8_array", NULL, MAVLINK_TYPE_INT8_T, 3, 98, offsetof(mavlink_test_types_t, s8_array) }, \ + { "s16_array", NULL, MAVLINK_TYPE_INT16_T, 3, 101, offsetof(mavlink_test_types_t, s16_array) }, \ + { "s32_array", NULL, MAVLINK_TYPE_INT32_T, 3, 107, offsetof(mavlink_test_types_t, s32_array) }, \ + { "s64_array", NULL, MAVLINK_TYPE_INT64_T, 3, 119, offsetof(mavlink_test_types_t, s64_array) }, \ + { "f_array", NULL, MAVLINK_TYPE_FLOAT, 3, 143, offsetof(mavlink_test_types_t, f_array) }, \ + { "d_array", NULL, MAVLINK_TYPE_DOUBLE, 3, 155, offsetof(mavlink_test_types_t, d_array) }, \ + } \ +} + + +/** + * @brief Pack a test_types message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param c char + * @param s string + * @param u8 uint8_t + * @param u16 uint16_t + * @param u32 uint32_t + * @param u64 uint64_t + * @param s8 int8_t + * @param s16 int16_t + * @param s32 int32_t + * @param s64 int64_t + * @param f float + * @param d double + * @param u8_array uint8_t_array + * @param u16_array uint16_t_array + * @param u32_array uint32_t_array + * @param u64_array uint64_t_array + * @param s8_array int8_t_array + * @param s16_array int16_t_array + * @param s32_array int32_t_array + * @param s64_array int64_t_array + * @param f_array float_array + * @param d_array double_array + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_test_types_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[179]; + _mav_put_char(buf, 0, c); + _mav_put_uint8_t(buf, 11, u8); + _mav_put_uint16_t(buf, 12, u16); + _mav_put_uint32_t(buf, 14, u32); + _mav_put_uint64_t(buf, 18, u64); + _mav_put_int8_t(buf, 26, s8); + _mav_put_int16_t(buf, 27, s16); + _mav_put_int32_t(buf, 29, s32); + _mav_put_int64_t(buf, 33, s64); + _mav_put_float(buf, 41, f); + _mav_put_double(buf, 45, d); + _mav_put_char_array(buf, 1, s, 10); + _mav_put_uint8_t_array(buf, 53, u8_array, 3); + _mav_put_uint16_t_array(buf, 56, u16_array, 3); + _mav_put_uint32_t_array(buf, 62, u32_array, 3); + _mav_put_uint64_t_array(buf, 74, u64_array, 3); + _mav_put_int8_t_array(buf, 98, s8_array, 3); + _mav_put_int16_t_array(buf, 101, s16_array, 3); + _mav_put_int32_t_array(buf, 107, s32_array, 3); + _mav_put_int64_t_array(buf, 119, s64_array, 3); + _mav_put_float_array(buf, 143, f_array, 3); + _mav_put_double_array(buf, 155, d_array, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 179); +#else + mavlink_test_types_t packet; + packet.c = c; + packet.u8 = u8; + packet.u16 = u16; + packet.u32 = u32; + packet.u64 = u64; + packet.s8 = s8; + packet.s16 = s16; + packet.s32 = s32; + packet.s64 = s64; + packet.f = f; + packet.d = d; + mav_array_memcpy(packet.s, s, sizeof(char)*10); + mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); + mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); + mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); + mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); + mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); + mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); + mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); + mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); + mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3); + mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 179); +#endif + + msg->msgid = MAVLINK_MSG_ID_TEST_TYPES; + return mavlink_finalize_message(msg, system_id, component_id, 179); +} + +/** + * @brief Pack a test_types message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param c char + * @param s string + * @param u8 uint8_t + * @param u16 uint16_t + * @param u32 uint32_t + * @param u64 uint64_t + * @param s8 int8_t + * @param s16 int16_t + * @param s32 int32_t + * @param s64 int64_t + * @param f float + * @param d double + * @param u8_array uint8_t_array + * @param u16_array uint16_t_array + * @param u32_array uint32_t_array + * @param u64_array uint64_t_array + * @param s8_array int8_t_array + * @param s16_array int16_t_array + * @param s32_array int32_t_array + * @param s64_array int64_t_array + * @param f_array float_array + * @param d_array double_array + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_test_types_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + char c,const char *s,uint8_t u8,uint16_t u16,uint32_t u32,uint64_t u64,int8_t s8,int16_t s16,int32_t s32,int64_t s64,float f,double d,const uint8_t *u8_array,const uint16_t *u16_array,const uint32_t *u32_array,const uint64_t *u64_array,const int8_t *s8_array,const int16_t *s16_array,const int32_t *s32_array,const int64_t *s64_array,const float *f_array,const double *d_array) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[179]; + _mav_put_char(buf, 0, c); + _mav_put_uint8_t(buf, 11, u8); + _mav_put_uint16_t(buf, 12, u16); + _mav_put_uint32_t(buf, 14, u32); + _mav_put_uint64_t(buf, 18, u64); + _mav_put_int8_t(buf, 26, s8); + _mav_put_int16_t(buf, 27, s16); + _mav_put_int32_t(buf, 29, s32); + _mav_put_int64_t(buf, 33, s64); + _mav_put_float(buf, 41, f); + _mav_put_double(buf, 45, d); + _mav_put_char_array(buf, 1, s, 10); + _mav_put_uint8_t_array(buf, 53, u8_array, 3); + _mav_put_uint16_t_array(buf, 56, u16_array, 3); + _mav_put_uint32_t_array(buf, 62, u32_array, 3); + _mav_put_uint64_t_array(buf, 74, u64_array, 3); + _mav_put_int8_t_array(buf, 98, s8_array, 3); + _mav_put_int16_t_array(buf, 101, s16_array, 3); + _mav_put_int32_t_array(buf, 107, s32_array, 3); + _mav_put_int64_t_array(buf, 119, s64_array, 3); + _mav_put_float_array(buf, 143, f_array, 3); + _mav_put_double_array(buf, 155, d_array, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 179); +#else + mavlink_test_types_t packet; + packet.c = c; + packet.u8 = u8; + packet.u16 = u16; + packet.u32 = u32; + packet.u64 = u64; + packet.s8 = s8; + packet.s16 = s16; + packet.s32 = s32; + packet.s64 = s64; + packet.f = f; + packet.d = d; + mav_array_memcpy(packet.s, s, sizeof(char)*10); + mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); + mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); + mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); + mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); + mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); + mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); + mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); + mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); + mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3); + mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 179); +#endif + + msg->msgid = MAVLINK_MSG_ID_TEST_TYPES; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 179); +} + +/** + * @brief Encode a test_types struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param test_types C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_test_types_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_test_types_t* test_types) +{ + return mavlink_msg_test_types_pack(system_id, component_id, msg, test_types->c, test_types->s, test_types->u8, test_types->u16, test_types->u32, test_types->u64, test_types->s8, test_types->s16, test_types->s32, test_types->s64, test_types->f, test_types->d, test_types->u8_array, test_types->u16_array, test_types->u32_array, test_types->u64_array, test_types->s8_array, test_types->s16_array, test_types->s32_array, test_types->s64_array, test_types->f_array, test_types->d_array); +} + +/** + * @brief Send a test_types message + * @param chan MAVLink channel to send the message + * + * @param c char + * @param s string + * @param u8 uint8_t + * @param u16 uint16_t + * @param u32 uint32_t + * @param u64 uint64_t + * @param s8 int8_t + * @param s16 int16_t + * @param s32 int32_t + * @param s64 int64_t + * @param f float + * @param d double + * @param u8_array uint8_t_array + * @param u16_array uint16_t_array + * @param u32_array uint32_t_array + * @param u64_array uint64_t_array + * @param s8_array int8_t_array + * @param s16_array int16_t_array + * @param s32_array int32_t_array + * @param s64_array int64_t_array + * @param f_array float_array + * @param d_array double_array + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_test_types_send(mavlink_channel_t chan, char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[179]; + _mav_put_char(buf, 0, c); + _mav_put_uint8_t(buf, 11, u8); + _mav_put_uint16_t(buf, 12, u16); + _mav_put_uint32_t(buf, 14, u32); + _mav_put_uint64_t(buf, 18, u64); + _mav_put_int8_t(buf, 26, s8); + _mav_put_int16_t(buf, 27, s16); + _mav_put_int32_t(buf, 29, s32); + _mav_put_int64_t(buf, 33, s64); + _mav_put_float(buf, 41, f); + _mav_put_double(buf, 45, d); + _mav_put_char_array(buf, 1, s, 10); + _mav_put_uint8_t_array(buf, 53, u8_array, 3); + _mav_put_uint16_t_array(buf, 56, u16_array, 3); + _mav_put_uint32_t_array(buf, 62, u32_array, 3); + _mav_put_uint64_t_array(buf, 74, u64_array, 3); + _mav_put_int8_t_array(buf, 98, s8_array, 3); + _mav_put_int16_t_array(buf, 101, s16_array, 3); + _mav_put_int32_t_array(buf, 107, s32_array, 3); + _mav_put_int64_t_array(buf, 119, s64_array, 3); + _mav_put_float_array(buf, 143, f_array, 3); + _mav_put_double_array(buf, 155, d_array, 3); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, buf, 179); +#else + mavlink_test_types_t packet; + packet.c = c; + packet.u8 = u8; + packet.u16 = u16; + packet.u32 = u32; + packet.u64 = u64; + packet.s8 = s8; + packet.s16 = s16; + packet.s32 = s32; + packet.s64 = s64; + packet.f = f; + packet.d = d; + mav_array_memcpy(packet.s, s, sizeof(char)*10); + mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); + mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); + mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); + mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); + mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); + mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); + mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); + mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); + mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3); + mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, (const char *)&packet, 179); +#endif +} + +#endif + +// MESSAGE TEST_TYPES UNPACKING + + +/** + * @brief Get field c from test_types message + * + * @return char + */ +static inline char mavlink_msg_test_types_get_c(const mavlink_message_t* msg) +{ + return _MAV_RETURN_char(msg, 0); +} + +/** + * @brief Get field s from test_types message + * + * @return string + */ +static inline uint16_t mavlink_msg_test_types_get_s(const mavlink_message_t* msg, char *s) +{ + return _MAV_RETURN_char_array(msg, s, 10, 1); +} + +/** + * @brief Get field u8 from test_types message + * + * @return uint8_t + */ +static inline uint8_t mavlink_msg_test_types_get_u8(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 11); +} + +/** + * @brief Get field u16 from test_types message + * + * @return uint16_t + */ +static inline uint16_t mavlink_msg_test_types_get_u16(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field u32 from test_types message + * + * @return uint32_t + */ +static inline uint32_t mavlink_msg_test_types_get_u32(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 14); +} + +/** + * @brief Get field u64 from test_types message + * + * @return uint64_t + */ +static inline uint64_t mavlink_msg_test_types_get_u64(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 18); +} + +/** + * @brief Get field s8 from test_types message + * + * @return int8_t + */ +static inline int8_t mavlink_msg_test_types_get_s8(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 26); +} + +/** + * @brief Get field s16 from test_types message + * + * @return int16_t + */ +static inline int16_t mavlink_msg_test_types_get_s16(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 27); +} + +/** + * @brief Get field s32 from test_types message + * + * @return int32_t + */ +static inline int32_t mavlink_msg_test_types_get_s32(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 29); +} + +/** + * @brief Get field s64 from test_types message + * + * @return int64_t + */ +static inline int64_t mavlink_msg_test_types_get_s64(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int64_t(msg, 33); +} + +/** + * @brief Get field f from test_types message + * + * @return float + */ +static inline float mavlink_msg_test_types_get_f(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 41); +} + +/** + * @brief Get field d from test_types message + * + * @return double + */ +static inline double mavlink_msg_test_types_get_d(const mavlink_message_t* msg) +{ + return _MAV_RETURN_double(msg, 45); +} + +/** + * @brief Get field u8_array from test_types message + * + * @return uint8_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u8_array(const mavlink_message_t* msg, uint8_t *u8_array) +{ + return _MAV_RETURN_uint8_t_array(msg, u8_array, 3, 53); +} + +/** + * @brief Get field u16_array from test_types message + * + * @return uint16_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u16_array(const mavlink_message_t* msg, uint16_t *u16_array) +{ + return _MAV_RETURN_uint16_t_array(msg, u16_array, 3, 56); +} + +/** + * @brief Get field u32_array from test_types message + * + * @return uint32_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u32_array(const mavlink_message_t* msg, uint32_t *u32_array) +{ + return _MAV_RETURN_uint32_t_array(msg, u32_array, 3, 62); +} + +/** + * @brief Get field u64_array from test_types message + * + * @return uint64_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u64_array(const mavlink_message_t* msg, uint64_t *u64_array) +{ + return _MAV_RETURN_uint64_t_array(msg, u64_array, 3, 74); +} + +/** + * @brief Get field s8_array from test_types message + * + * @return int8_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s8_array(const mavlink_message_t* msg, int8_t *s8_array) +{ + return _MAV_RETURN_int8_t_array(msg, s8_array, 3, 98); +} + +/** + * @brief Get field s16_array from test_types message + * + * @return int16_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s16_array(const mavlink_message_t* msg, int16_t *s16_array) +{ + return _MAV_RETURN_int16_t_array(msg, s16_array, 3, 101); +} + +/** + * @brief Get field s32_array from test_types message + * + * @return int32_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s32_array(const mavlink_message_t* msg, int32_t *s32_array) +{ + return _MAV_RETURN_int32_t_array(msg, s32_array, 3, 107); +} + +/** + * @brief Get field s64_array from test_types message + * + * @return int64_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s64_array(const mavlink_message_t* msg, int64_t *s64_array) +{ + return _MAV_RETURN_int64_t_array(msg, s64_array, 3, 119); +} + +/** + * @brief Get field f_array from test_types message + * + * @return float_array + */ +static inline uint16_t mavlink_msg_test_types_get_f_array(const mavlink_message_t* msg, float *f_array) +{ + return _MAV_RETURN_float_array(msg, f_array, 3, 143); +} + +/** + * @brief Get field d_array from test_types message + * + * @return double_array + */ +static inline uint16_t mavlink_msg_test_types_get_d_array(const mavlink_message_t* msg, double *d_array) +{ + return _MAV_RETURN_double_array(msg, d_array, 3, 155); +} + +/** + * @brief Decode a test_types message into a struct + * + * @param msg The message to decode + * @param test_types C-struct to decode the message contents into + */ +static inline void mavlink_msg_test_types_decode(const mavlink_message_t* msg, mavlink_test_types_t* test_types) +{ +#if MAVLINK_NEED_BYTE_SWAP + test_types->c = mavlink_msg_test_types_get_c(msg); + mavlink_msg_test_types_get_s(msg, test_types->s); + test_types->u8 = mavlink_msg_test_types_get_u8(msg); + test_types->u16 = mavlink_msg_test_types_get_u16(msg); + test_types->u32 = mavlink_msg_test_types_get_u32(msg); + test_types->u64 = mavlink_msg_test_types_get_u64(msg); + test_types->s8 = mavlink_msg_test_types_get_s8(msg); + test_types->s16 = mavlink_msg_test_types_get_s16(msg); + test_types->s32 = mavlink_msg_test_types_get_s32(msg); + test_types->s64 = mavlink_msg_test_types_get_s64(msg); + test_types->f = mavlink_msg_test_types_get_f(msg); + test_types->d = mavlink_msg_test_types_get_d(msg); + mavlink_msg_test_types_get_u8_array(msg, test_types->u8_array); + mavlink_msg_test_types_get_u16_array(msg, test_types->u16_array); + mavlink_msg_test_types_get_u32_array(msg, test_types->u32_array); + mavlink_msg_test_types_get_u64_array(msg, test_types->u64_array); + mavlink_msg_test_types_get_s8_array(msg, test_types->s8_array); + mavlink_msg_test_types_get_s16_array(msg, test_types->s16_array); + mavlink_msg_test_types_get_s32_array(msg, test_types->s32_array); + mavlink_msg_test_types_get_s64_array(msg, test_types->s64_array); + mavlink_msg_test_types_get_f_array(msg, test_types->f_array); + mavlink_msg_test_types_get_d_array(msg, test_types->d_array); +#else + memcpy(test_types, _MAV_PAYLOAD(msg), 179); +#endif +} diff --git a/mavlink/include/mavlink/v0.9/test/test.h b/mavlink/include/mavlink/v0.9/test/test.h new file mode 100644 index 0000000000000000000000000000000000000000..cfcf4753e7bff9d51a91bea14be9abd2ddeb0e04 --- /dev/null +++ b/mavlink/include/mavlink/v0.9/test/test.h @@ -0,0 +1,53 @@ +/** @file + * @brief MAVLink comm protocol generated from test.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef TEST_H +#define TEST_H + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {179, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {91, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_TEST_TYPES, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#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/include/mavlink/v0.9/test/testsuite.h b/mavlink/include/mavlink/v0.9/test/testsuite.h new file mode 100644 index 0000000000000000000000000000000000000000..9b0fc041b5894282569366511ad950445874bbde --- /dev/null +++ b/mavlink/include/mavlink/v0.9/test/testsuite.h @@ -0,0 +1,120 @@ +/** @file + * @brief MAVLink comm protocol testsuite generated from test.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef TEST_TESTSUITE_H +#define TEST_TESTSUITE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef MAVLINK_TEST_ALL +#define MAVLINK_TEST_ALL + +static void mavlink_test_test(uint8_t, uint8_t, mavlink_message_t *last_msg); + +static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + + mavlink_test_test(system_id, component_id, last_msg); +} +#endif + + + + +static void mavlink_test_test_types(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_test_types_t packet_in = { + 'A', + "BCDEFGHIJ", + 230, + 17859, + 963498192, + 93372036854776941ULL, + 211, + 18639, + 963498972, + 93372036854777886LL, + 304.0, + 438.0, + { 228, 229, 230 }, + { 20147, 20148, 20149 }, + { 963500688, 963500689, 963500690 }, + { 93372036854780469, 93372036854780470, 93372036854780471 }, + { 171, 172, 173 }, + { 22487, 22488, 22489 }, + { 963503028, 963503029, 963503030 }, + { 93372036854783304, 93372036854783305, 93372036854783306 }, + { 1018.0, 1019.0, 1020.0 }, + { 1208.0, 1209.0, 1210.0 }, + }; + mavlink_test_types_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.c = packet_in.c; + packet1.u8 = packet_in.u8; + packet1.u16 = packet_in.u16; + packet1.u32 = packet_in.u32; + packet1.u64 = packet_in.u64; + packet1.s8 = packet_in.s8; + packet1.s16 = packet_in.s16; + packet1.s32 = packet_in.s32; + packet1.s64 = packet_in.s64; + packet1.f = packet_in.f; + packet1.d = packet_in.d; + + mav_array_memcpy(packet1.s, packet_in.s, sizeof(char)*10); + mav_array_memcpy(packet1.u8_array, packet_in.u8_array, sizeof(uint8_t)*3); + mav_array_memcpy(packet1.u16_array, packet_in.u16_array, sizeof(uint16_t)*3); + mav_array_memcpy(packet1.u32_array, packet_in.u32_array, sizeof(uint32_t)*3); + mav_array_memcpy(packet1.u64_array, packet_in.u64_array, sizeof(uint64_t)*3); + mav_array_memcpy(packet1.s8_array, packet_in.s8_array, sizeof(int8_t)*3); + mav_array_memcpy(packet1.s16_array, packet_in.s16_array, sizeof(int16_t)*3); + mav_array_memcpy(packet1.s32_array, packet_in.s32_array, sizeof(int32_t)*3); + mav_array_memcpy(packet1.s64_array, packet_in.s64_array, sizeof(int64_t)*3); + mav_array_memcpy(packet1.f_array, packet_in.f_array, sizeof(float)*3); + mav_array_memcpy(packet1.d_array, packet_in.d_array, sizeof(double)*3); + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_test_types_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_test_types_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_test_types_pack(system_id, component_id, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array ); + mavlink_msg_test_types_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_test_types_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array ); + mavlink_msg_test_types_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; imsgid = MAVLINK_MSG_ID_NAV_FILTER_BIAS; @@ -107,7 +107,7 @@ static inline uint16_t mavlink_msg_nav_filter_bias_pack_chan(uint8_t system_id, _mav_put_float(buf, 24, gyro_1); _mav_put_float(buf, 28, gyro_2); - memcpy(_MAV_PAYLOAD(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); #else mavlink_nav_filter_bias_t packet; packet.usec = usec; @@ -118,7 +118,7 @@ static inline uint16_t mavlink_msg_nav_filter_bias_pack_chan(uint8_t system_id, packet.gyro_1 = gyro_1; packet.gyro_2 = gyro_2; - memcpy(_MAV_PAYLOAD(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); #endif msg->msgid = MAVLINK_MSG_ID_NAV_FILTER_BIAS; diff --git a/mavlink/include/v0.9/ualberta/mavlink_msg_radio_calibration.h b/mavlink/include/mavlink/v0.9/ualberta/mavlink_msg_radio_calibration.h similarity index 97% rename from mavlink/include/v0.9/ualberta/mavlink_msg_radio_calibration.h rename to mavlink/include/mavlink/v0.9/ualberta/mavlink_msg_radio_calibration.h index 42b36e749855eb7ccb5b848f119bfb68f30bd491..3feb7c8a593d190b37c1f0bd84d03fa6a4ae17ee 100644 --- a/mavlink/include/v0.9/ualberta/mavlink_msg_radio_calibration.h +++ b/mavlink/include/mavlink/v0.9/ualberta/mavlink_msg_radio_calibration.h @@ -61,7 +61,7 @@ static inline uint16_t mavlink_msg_radio_calibration_pack(uint8_t system_id, uin _mav_put_uint16_t_array(buf, 18, gyro, 2); _mav_put_uint16_t_array(buf, 22, pitch, 5); _mav_put_uint16_t_array(buf, 32, throttle, 5); - memcpy(_MAV_PAYLOAD(msg), buf, 42); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42); #else mavlink_radio_calibration_t packet; @@ -71,7 +71,7 @@ static inline uint16_t mavlink_msg_radio_calibration_pack(uint8_t system_id, uin mav_array_memcpy(packet.gyro, gyro, sizeof(uint16_t)*2); mav_array_memcpy(packet.pitch, pitch, sizeof(uint16_t)*5); mav_array_memcpy(packet.throttle, throttle, sizeof(uint16_t)*5); - memcpy(_MAV_PAYLOAD(msg), &packet, 42); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42); #endif msg->msgid = MAVLINK_MSG_ID_RADIO_CALIBRATION; @@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_radio_calibration_pack_chan(uint8_t system_id _mav_put_uint16_t_array(buf, 18, gyro, 2); _mav_put_uint16_t_array(buf, 22, pitch, 5); _mav_put_uint16_t_array(buf, 32, throttle, 5); - memcpy(_MAV_PAYLOAD(msg), buf, 42); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42); #else mavlink_radio_calibration_t packet; @@ -115,7 +115,7 @@ static inline uint16_t mavlink_msg_radio_calibration_pack_chan(uint8_t system_id mav_array_memcpy(packet.gyro, gyro, sizeof(uint16_t)*2); mav_array_memcpy(packet.pitch, pitch, sizeof(uint16_t)*5); mav_array_memcpy(packet.throttle, throttle, sizeof(uint16_t)*5); - memcpy(_MAV_PAYLOAD(msg), &packet, 42); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42); #endif msg->msgid = MAVLINK_MSG_ID_RADIO_CALIBRATION; diff --git a/mavlink/include/v0.9/ualberta/mavlink_msg_ualberta_sys_status.h b/mavlink/include/mavlink/v0.9/ualberta/mavlink_msg_ualberta_sys_status.h similarity index 96% rename from mavlink/include/v0.9/ualberta/mavlink_msg_ualberta_sys_status.h rename to mavlink/include/mavlink/v0.9/ualberta/mavlink_msg_ualberta_sys_status.h index fb0a106600850ade52bb9b65f5fbc0469387f171..511ca6b0dbf841ac2216582f6623da92c2adc955 100644 --- a/mavlink/include/v0.9/ualberta/mavlink_msg_ualberta_sys_status.h +++ b/mavlink/include/mavlink/v0.9/ualberta/mavlink_msg_ualberta_sys_status.h @@ -44,14 +44,14 @@ static inline uint16_t mavlink_msg_ualberta_sys_status_pack(uint8_t system_id, u _mav_put_uint8_t(buf, 1, nav_mode); _mav_put_uint8_t(buf, 2, pilot); - memcpy(_MAV_PAYLOAD(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); #else mavlink_ualberta_sys_status_t packet; packet.mode = mode; packet.nav_mode = nav_mode; packet.pilot = pilot; - memcpy(_MAV_PAYLOAD(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); #endif msg->msgid = MAVLINK_MSG_ID_UALBERTA_SYS_STATUS; @@ -79,14 +79,14 @@ static inline uint16_t mavlink_msg_ualberta_sys_status_pack_chan(uint8_t system_ _mav_put_uint8_t(buf, 1, nav_mode); _mav_put_uint8_t(buf, 2, pilot); - memcpy(_MAV_PAYLOAD(msg), buf, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); #else mavlink_ualberta_sys_status_t packet; packet.mode = mode; packet.nav_mode = nav_mode; packet.pilot = pilot; - memcpy(_MAV_PAYLOAD(msg), &packet, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); #endif msg->msgid = MAVLINK_MSG_ID_UALBERTA_SYS_STATUS; diff --git a/mavlink/include/v0.9/ualberta/testsuite.h b/mavlink/include/mavlink/v0.9/ualberta/testsuite.h similarity index 100% rename from mavlink/include/v0.9/ualberta/testsuite.h rename to mavlink/include/mavlink/v0.9/ualberta/testsuite.h diff --git a/mavlink/include/mavlink/v0.9/ualberta/ualberta.h b/mavlink/include/mavlink/v0.9/ualberta/ualberta.h new file mode 100644 index 0000000000000000000000000000000000000000..02b4484788bb915ef6fdbf633a3ef90003ea14b7 --- /dev/null +++ b/mavlink/include/mavlink/v0.9/ualberta/ualberta.h @@ -0,0 +1,93 @@ +/** @file + * @brief MAVLink comm protocol generated from ualberta.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef UALBERTA_H +#define UALBERTA_H + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 32, 42, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 34, 71, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_BOOT, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACTION_ACK, MAVLINK_MESSAGE_INFO_ACTION, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_SET_NAV_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_LOCAL_POSITION, MAVLINK_MESSAGE_INFO_GPS_RAW, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_WAYPOINT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST, MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT, MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL, MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED, MAVLINK_MESSAGE_INFO_WAYPOINT_ACK, MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_CONTROL_STATUS, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_POSITION_TARGET, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_SET_ALTITUDE, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_NAV_FILTER_BIAS, MAVLINK_MESSAGE_INFO_RADIO_CALIBRATION, MAVLINK_MESSAGE_INFO_UALBERTA_SYS_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_UALBERTA + +#include "../common/common.h" + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +// ENUM DEFINITIONS + + +/** @brief Available autopilot modes for ualberta uav */ +#ifndef HAVE_ENUM_UALBERTA_AUTOPILOT_MODE +#define HAVE_ENUM_UALBERTA_AUTOPILOT_MODE +enum UALBERTA_AUTOPILOT_MODE +{ + MODE_MANUAL_DIRECT=1, /* | */ + MODE_MANUAL_SCALED=2, /* | */ + MODE_AUTO_PID_ATT=3, /* | */ + MODE_AUTO_PID_VEL=4, /* | */ + MODE_AUTO_PID_POS=5, /* | */ + UALBERTA_AUTOPILOT_MODE_ENUM_END=6, /* | */ +}; +#endif + +/** @brief Navigation filter mode */ +#ifndef HAVE_ENUM_UALBERTA_NAV_MODE +#define HAVE_ENUM_UALBERTA_NAV_MODE +enum UALBERTA_NAV_MODE +{ + NAV_AHRS_INIT=1, /* | */ + NAV_AHRS=2, /* | */ + NAV_INS_GPS_INIT=3, /* | */ + NAV_INS_GPS=4, /* | */ + UALBERTA_NAV_MODE_ENUM_END=5, /* | */ +}; +#endif + +/** @brief Mode currently commanded by pilot */ +#ifndef HAVE_ENUM_UALBERTA_PILOT_MODE +#define HAVE_ENUM_UALBERTA_PILOT_MODE +enum UALBERTA_PILOT_MODE +{ + PILOT_MANUAL=1, /* | */ + PILOT_AUTO=2, /* | */ + PILOT_ROTO=3, /* | */ + UALBERTA_PILOT_MODE_ENUM_END=4, /* | */ +}; +#endif + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_nav_filter_bias.h" +#include "./mavlink_msg_radio_calibration.h" +#include "./mavlink_msg_ualberta_sys_status.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // UALBERTA_H diff --git a/mavlink/include/v0.9/ualberta/version.h b/mavlink/include/mavlink/v0.9/ualberta/version.h similarity index 84% rename from mavlink/include/v0.9/ualberta/version.h rename to mavlink/include/mavlink/v0.9/ualberta/version.h index 889625072adf665a624fb384e347c3f6e4df5f1c..4e0086a3efae3e20107618aad43135ed7dd5f590 100644 --- a/mavlink/include/v0.9/ualberta/version.h +++ b/mavlink/include/mavlink/v0.9/ualberta/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Mar 1 01:19:41 2012" +#define MAVLINK_BUILD_DATE "Thu Apr 19 19:44:39 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "0.9" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h b/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h new file mode 100644 index 0000000000000000000000000000000000000000..b499671026b95a785867266cecd3513fefc04efd --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h @@ -0,0 +1,149 @@ +/** @file + * @brief MAVLink comm protocol generated from ardupilotmega.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef ARDUPILOTMEGA_H +#define ARDUPILOTMEGA_H + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 54, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 200, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 205, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_DCM, MAVLINK_MESSAGE_INFO_SIMSTATE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_ARDUPILOTMEGA + +#include "../common/common.h" + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +// ENUM DEFINITIONS + + +/** @brief Enumeration of possible mount operation modes */ +#ifndef HAVE_ENUM_MAV_MOUNT_MODE +#define HAVE_ENUM_MAV_MOUNT_MODE +enum MAV_MOUNT_MODE +{ + MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization | */ + MAV_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM. | */ + MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */ + MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */ + MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */ + MAV_MOUNT_MODE_ENUM_END=5, /* | */ +}; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_CMD +#define HAVE_ENUM_MAV_CMD +enum MAV_CMD +{ + MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ + MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ + MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ + MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ + MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */ + MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ + MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */ + MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */ + MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */ + MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ + MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ + MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ + MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ + MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ + MAV_CMD_ENUM_END=401, /* | */ +}; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_FENCE_ACTION +#define HAVE_ENUM_FENCE_ACTION +enum FENCE_ACTION +{ + FENCE_ACTION_NONE=0, /* Disable fenced mode | */ + FENCE_ACTION_GUIDED=1, /* Switched to guided mode to return point (fence point 0) | */ + FENCE_ACTION_ENUM_END=2, /* | */ +}; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_FENCE_BREACH +#define HAVE_ENUM_FENCE_BREACH +enum FENCE_BREACH +{ + FENCE_BREACH_NONE=0, /* No last fence breach | */ + FENCE_BREACH_MINALT=1, /* Breached minimum altitude | */ + FENCE_BREACH_MAXALT=2, /* Breached minimum altitude | */ + FENCE_BREACH_BOUNDARY=3, /* Breached fence boundary | */ + FENCE_BREACH_ENUM_END=4, /* | */ +}; +#endif + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_sensor_offsets.h" +#include "./mavlink_msg_set_mag_offsets.h" +#include "./mavlink_msg_meminfo.h" +#include "./mavlink_msg_ap_adc.h" +#include "./mavlink_msg_digicam_configure.h" +#include "./mavlink_msg_digicam_control.h" +#include "./mavlink_msg_mount_configure.h" +#include "./mavlink_msg_mount_control.h" +#include "./mavlink_msg_mount_status.h" +#include "./mavlink_msg_fence_point.h" +#include "./mavlink_msg_fence_fetch_point.h" +#include "./mavlink_msg_fence_status.h" +#include "./mavlink_msg_dcm.h" +#include "./mavlink_msg_simstate.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // ARDUPILOTMEGA_H diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink.h new file mode 100644 index 0000000000000000000000000000000000000000..551938f0440328a76fd05b2dfccc8eaf8efe5781 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink.h @@ -0,0 +1,27 @@ +/** @file + * @brief MAVLink comm protocol built from ardupilotmega.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 "ardupilotmega.h" + +#endif // MAVLINK_H diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h new file mode 100644 index 0000000000000000000000000000000000000000..ea640c4fb0b33ed817578a0c0fa05b612c546c04 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h @@ -0,0 +1,254 @@ +// MESSAGE AP_ADC PACKING + +#define MAVLINK_MSG_ID_AP_ADC 153 + +typedef struct __mavlink_ap_adc_t +{ + uint16_t adc1; ///< ADC output 1 + uint16_t adc2; ///< ADC output 2 + uint16_t adc3; ///< ADC output 3 + uint16_t adc4; ///< ADC output 4 + uint16_t adc5; ///< ADC output 5 + uint16_t adc6; ///< ADC output 6 +} mavlink_ap_adc_t; + +#define MAVLINK_MSG_ID_AP_ADC_LEN 12 +#define MAVLINK_MSG_ID_153_LEN 12 + + + +#define MAVLINK_MESSAGE_INFO_AP_ADC { \ + "AP_ADC", \ + 6, \ + { { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ap_adc_t, adc1) }, \ + { "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_ap_adc_t, adc2) }, \ + { "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_ap_adc_t, adc3) }, \ + { "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_ap_adc_t, adc4) }, \ + { "adc5", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_ap_adc_t, adc5) }, \ + { "adc6", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_ap_adc_t, adc6) }, \ + } \ +} + + +/** + * @brief Pack a ap_adc 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 adc1 ADC output 1 + * @param adc2 ADC output 2 + * @param adc3 ADC output 3 + * @param adc4 ADC output 4 + * @param adc5 ADC output 5 + * @param adc6 ADC output 6 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_uint16_t(buf, 0, adc1); + _mav_put_uint16_t(buf, 2, adc2); + _mav_put_uint16_t(buf, 4, adc3); + _mav_put_uint16_t(buf, 6, adc4); + _mav_put_uint16_t(buf, 8, adc5); + _mav_put_uint16_t(buf, 10, adc6); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_ap_adc_t packet; + packet.adc1 = adc1; + packet.adc2 = adc2; + packet.adc3 = adc3; + packet.adc4 = adc4; + packet.adc5 = adc5; + packet.adc6 = adc6; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_AP_ADC; + return mavlink_finalize_message(msg, system_id, component_id, 12, 188); +} + +/** + * @brief Pack a ap_adc 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 adc1 ADC output 1 + * @param adc2 ADC output 2 + * @param adc3 ADC output 3 + * @param adc4 ADC output 4 + * @param adc5 ADC output 5 + * @param adc6 ADC output 6 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t adc1,uint16_t adc2,uint16_t adc3,uint16_t adc4,uint16_t adc5,uint16_t adc6) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_uint16_t(buf, 0, adc1); + _mav_put_uint16_t(buf, 2, adc2); + _mav_put_uint16_t(buf, 4, adc3); + _mav_put_uint16_t(buf, 6, adc4); + _mav_put_uint16_t(buf, 8, adc5); + _mav_put_uint16_t(buf, 10, adc6); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_ap_adc_t packet; + packet.adc1 = adc1; + packet.adc2 = adc2; + packet.adc3 = adc3; + packet.adc4 = adc4; + packet.adc5 = adc5; + packet.adc6 = adc6; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_AP_ADC; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 188); +} + +/** + * @brief Encode a ap_adc 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 ap_adc C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_ap_adc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc) +{ + return mavlink_msg_ap_adc_pack(system_id, component_id, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6); +} + +/** + * @brief Send a ap_adc message + * @param chan MAVLink channel to send the message + * + * @param adc1 ADC output 1 + * @param adc2 ADC output 2 + * @param adc3 ADC output 3 + * @param adc4 ADC output 4 + * @param adc5 ADC output 5 + * @param adc6 ADC output 6 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_ap_adc_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_uint16_t(buf, 0, adc1); + _mav_put_uint16_t(buf, 2, adc2); + _mav_put_uint16_t(buf, 4, adc3); + _mav_put_uint16_t(buf, 6, adc4); + _mav_put_uint16_t(buf, 8, adc5); + _mav_put_uint16_t(buf, 10, adc6); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, 12, 188); +#else + mavlink_ap_adc_t packet; + packet.adc1 = adc1; + packet.adc2 = adc2; + packet.adc3 = adc3; + packet.adc4 = adc4; + packet.adc5 = adc5; + packet.adc6 = adc6; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)&packet, 12, 188); +#endif +} + +#endif + +// MESSAGE AP_ADC UNPACKING + + +/** + * @brief Get field adc1 from ap_adc message + * + * @return ADC output 1 + */ +static inline uint16_t mavlink_msg_ap_adc_get_adc1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field adc2 from ap_adc message + * + * @return ADC output 2 + */ +static inline uint16_t mavlink_msg_ap_adc_get_adc2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Get field adc3 from ap_adc message + * + * @return ADC output 3 + */ +static inline uint16_t mavlink_msg_ap_adc_get_adc3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field adc4 from ap_adc message + * + * @return ADC output 4 + */ +static inline uint16_t mavlink_msg_ap_adc_get_adc4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field adc5 from ap_adc message + * + * @return ADC output 5 + */ +static inline uint16_t mavlink_msg_ap_adc_get_adc5(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field adc6 from ap_adc message + * + * @return ADC output 6 + */ +static inline uint16_t mavlink_msg_ap_adc_get_adc6(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Decode a ap_adc message into a struct + * + * @param msg The message to decode + * @param ap_adc C-struct to decode the message contents into + */ +static inline void mavlink_msg_ap_adc_decode(const mavlink_message_t* msg, mavlink_ap_adc_t* ap_adc) +{ +#if MAVLINK_NEED_BYTE_SWAP + ap_adc->adc1 = mavlink_msg_ap_adc_get_adc1(msg); + ap_adc->adc2 = mavlink_msg_ap_adc_get_adc2(msg); + ap_adc->adc3 = mavlink_msg_ap_adc_get_adc3(msg); + ap_adc->adc4 = mavlink_msg_ap_adc_get_adc4(msg); + ap_adc->adc5 = mavlink_msg_ap_adc_get_adc5(msg); + ap_adc->adc6 = mavlink_msg_ap_adc_get_adc6(msg); +#else + memcpy(ap_adc, _MAV_PAYLOAD(msg), 12); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_dcm.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_dcm.h new file mode 100644 index 0000000000000000000000000000000000000000..0197777ff4445d86e3de52af558bb49cbb8cbff7 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_dcm.h @@ -0,0 +1,276 @@ +// MESSAGE DCM PACKING + +#define MAVLINK_MSG_ID_DCM 163 + +typedef struct __mavlink_dcm_t +{ + float omegaIx; ///< X gyro drift estimate rad/s + float omegaIy; ///< Y gyro drift estimate rad/s + float omegaIz; ///< Z gyro drift estimate rad/s + float accel_weight; ///< average accel_weight + float renorm_val; ///< average renormalisation value + float error_rp; ///< average error_roll_pitch value + float error_yaw; ///< average error_yaw value +} mavlink_dcm_t; + +#define MAVLINK_MSG_ID_DCM_LEN 28 +#define MAVLINK_MSG_ID_163_LEN 28 + + + +#define MAVLINK_MESSAGE_INFO_DCM { \ + "DCM", \ + 7, \ + { { "omegaIx", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_dcm_t, omegaIx) }, \ + { "omegaIy", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_dcm_t, omegaIy) }, \ + { "omegaIz", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_dcm_t, omegaIz) }, \ + { "accel_weight", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_dcm_t, accel_weight) }, \ + { "renorm_val", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_dcm_t, renorm_val) }, \ + { "error_rp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_dcm_t, error_rp) }, \ + { "error_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_dcm_t, error_yaw) }, \ + } \ +} + + +/** + * @brief Pack a dcm 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 omegaIx X gyro drift estimate rad/s + * @param omegaIy Y gyro drift estimate rad/s + * @param omegaIz Z gyro drift estimate rad/s + * @param accel_weight average accel_weight + * @param renorm_val average renormalisation value + * @param error_rp average error_roll_pitch value + * @param error_yaw average error_yaw value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_dcm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_float(buf, 0, omegaIx); + _mav_put_float(buf, 4, omegaIy); + _mav_put_float(buf, 8, omegaIz); + _mav_put_float(buf, 12, accel_weight); + _mav_put_float(buf, 16, renorm_val); + _mav_put_float(buf, 20, error_rp); + _mav_put_float(buf, 24, error_yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); +#else + mavlink_dcm_t packet; + packet.omegaIx = omegaIx; + packet.omegaIy = omegaIy; + packet.omegaIz = omegaIz; + packet.accel_weight = accel_weight; + packet.renorm_val = renorm_val; + packet.error_rp = error_rp; + packet.error_yaw = error_yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_DCM; + return mavlink_finalize_message(msg, system_id, component_id, 28, 205); +} + +/** + * @brief Pack a dcm 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 omegaIx X gyro drift estimate rad/s + * @param omegaIy Y gyro drift estimate rad/s + * @param omegaIz Z gyro drift estimate rad/s + * @param accel_weight average accel_weight + * @param renorm_val average renormalisation value + * @param error_rp average error_roll_pitch value + * @param error_yaw average error_yaw value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_dcm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float omegaIx,float omegaIy,float omegaIz,float accel_weight,float renorm_val,float error_rp,float error_yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_float(buf, 0, omegaIx); + _mav_put_float(buf, 4, omegaIy); + _mav_put_float(buf, 8, omegaIz); + _mav_put_float(buf, 12, accel_weight); + _mav_put_float(buf, 16, renorm_val); + _mav_put_float(buf, 20, error_rp); + _mav_put_float(buf, 24, error_yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); +#else + mavlink_dcm_t packet; + packet.omegaIx = omegaIx; + packet.omegaIy = omegaIy; + packet.omegaIz = omegaIz; + packet.accel_weight = accel_weight; + packet.renorm_val = renorm_val; + packet.error_rp = error_rp; + packet.error_yaw = error_yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_DCM; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 205); +} + +/** + * @brief Encode a dcm 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 dcm C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_dcm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_dcm_t* dcm) +{ + return mavlink_msg_dcm_pack(system_id, component_id, msg, dcm->omegaIx, dcm->omegaIy, dcm->omegaIz, dcm->accel_weight, dcm->renorm_val, dcm->error_rp, dcm->error_yaw); +} + +/** + * @brief Send a dcm message + * @param chan MAVLink channel to send the message + * + * @param omegaIx X gyro drift estimate rad/s + * @param omegaIy Y gyro drift estimate rad/s + * @param omegaIz Z gyro drift estimate rad/s + * @param accel_weight average accel_weight + * @param renorm_val average renormalisation value + * @param error_rp average error_roll_pitch value + * @param error_yaw average error_yaw value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_dcm_send(mavlink_channel_t chan, float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_float(buf, 0, omegaIx); + _mav_put_float(buf, 4, omegaIy); + _mav_put_float(buf, 8, omegaIz); + _mav_put_float(buf, 12, accel_weight); + _mav_put_float(buf, 16, renorm_val); + _mav_put_float(buf, 20, error_rp); + _mav_put_float(buf, 24, error_yaw); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DCM, buf, 28, 205); +#else + mavlink_dcm_t packet; + packet.omegaIx = omegaIx; + packet.omegaIy = omegaIy; + packet.omegaIz = omegaIz; + packet.accel_weight = accel_weight; + packet.renorm_val = renorm_val; + packet.error_rp = error_rp; + packet.error_yaw = error_yaw; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DCM, (const char *)&packet, 28, 205); +#endif +} + +#endif + +// MESSAGE DCM UNPACKING + + +/** + * @brief Get field omegaIx from dcm message + * + * @return X gyro drift estimate rad/s + */ +static inline float mavlink_msg_dcm_get_omegaIx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field omegaIy from dcm message + * + * @return Y gyro drift estimate rad/s + */ +static inline float mavlink_msg_dcm_get_omegaIy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field omegaIz from dcm message + * + * @return Z gyro drift estimate rad/s + */ +static inline float mavlink_msg_dcm_get_omegaIz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field accel_weight from dcm message + * + * @return average accel_weight + */ +static inline float mavlink_msg_dcm_get_accel_weight(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field renorm_val from dcm message + * + * @return average renormalisation value + */ +static inline float mavlink_msg_dcm_get_renorm_val(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field error_rp from dcm message + * + * @return average error_roll_pitch value + */ +static inline float mavlink_msg_dcm_get_error_rp(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field error_yaw from dcm message + * + * @return average error_yaw value + */ +static inline float mavlink_msg_dcm_get_error_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a dcm message into a struct + * + * @param msg The message to decode + * @param dcm C-struct to decode the message contents into + */ +static inline void mavlink_msg_dcm_decode(const mavlink_message_t* msg, mavlink_dcm_t* dcm) +{ +#if MAVLINK_NEED_BYTE_SWAP + dcm->omegaIx = mavlink_msg_dcm_get_omegaIx(msg); + dcm->omegaIy = mavlink_msg_dcm_get_omegaIy(msg); + dcm->omegaIz = mavlink_msg_dcm_get_omegaIz(msg); + dcm->accel_weight = mavlink_msg_dcm_get_accel_weight(msg); + dcm->renorm_val = mavlink_msg_dcm_get_renorm_val(msg); + dcm->error_rp = mavlink_msg_dcm_get_error_rp(msg); + dcm->error_yaw = mavlink_msg_dcm_get_error_yaw(msg); +#else + memcpy(dcm, _MAV_PAYLOAD(msg), 28); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h new file mode 100644 index 0000000000000000000000000000000000000000..cc49c50255e67d10698335fc3bb14a2d7104e5b9 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h @@ -0,0 +1,364 @@ +// MESSAGE DIGICAM_CONFIGURE PACKING + +#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE 154 + +typedef struct __mavlink_digicam_configure_t +{ + float extra_value; ///< Correspondent value to given extra_param + uint16_t shutter_speed; ///< Divisor number //e.g. 1000 means 1/1000 (0 means ignore) + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t mode; ///< Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) + uint8_t aperture; ///< F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) + uint8_t iso; ///< ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) + uint8_t exposure_type; ///< Exposure type enumeration from 1 to N (0 means ignore) + uint8_t command_id; ///< Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + uint8_t engine_cut_off; ///< Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) + uint8_t extra_param; ///< Extra parameters enumeration (0 means ignore) +} mavlink_digicam_configure_t; + +#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN 15 +#define MAVLINK_MSG_ID_154_LEN 15 + + + +#define MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE { \ + "DIGICAM_CONFIGURE", \ + 11, \ + { { "extra_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_digicam_configure_t, extra_value) }, \ + { "shutter_speed", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_digicam_configure_t, shutter_speed) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_digicam_configure_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_digicam_configure_t, target_component) }, \ + { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_digicam_configure_t, mode) }, \ + { "aperture", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_digicam_configure_t, aperture) }, \ + { "iso", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_digicam_configure_t, iso) }, \ + { "exposure_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_digicam_configure_t, exposure_type) }, \ + { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_digicam_configure_t, command_id) }, \ + { "engine_cut_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_digicam_configure_t, engine_cut_off) }, \ + { "extra_param", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_digicam_configure_t, extra_param) }, \ + } \ +} + + +/** + * @brief Pack a digicam_configure 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 target_system System ID + * @param target_component Component ID + * @param mode Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) + * @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore) + * @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) + * @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) + * @param exposure_type Exposure type enumeration from 1 to N (0 means ignore) + * @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + * @param engine_cut_off Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) + * @param extra_param Extra parameters enumeration (0 means ignore) + * @param extra_value Correspondent value to given extra_param + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_digicam_configure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[15]; + _mav_put_float(buf, 0, extra_value); + _mav_put_uint16_t(buf, 4, shutter_speed); + _mav_put_uint8_t(buf, 6, target_system); + _mav_put_uint8_t(buf, 7, target_component); + _mav_put_uint8_t(buf, 8, mode); + _mav_put_uint8_t(buf, 9, aperture); + _mav_put_uint8_t(buf, 10, iso); + _mav_put_uint8_t(buf, 11, exposure_type); + _mav_put_uint8_t(buf, 12, command_id); + _mav_put_uint8_t(buf, 13, engine_cut_off); + _mav_put_uint8_t(buf, 14, extra_param); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); +#else + mavlink_digicam_configure_t packet; + packet.extra_value = extra_value; + packet.shutter_speed = shutter_speed; + packet.target_system = target_system; + packet.target_component = target_component; + packet.mode = mode; + packet.aperture = aperture; + packet.iso = iso; + packet.exposure_type = exposure_type; + packet.command_id = command_id; + packet.engine_cut_off = engine_cut_off; + packet.extra_param = extra_param; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); +#endif + + msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE; + return mavlink_finalize_message(msg, system_id, component_id, 15, 84); +} + +/** + * @brief Pack a digicam_configure 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 target_system System ID + * @param target_component Component ID + * @param mode Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) + * @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore) + * @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) + * @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) + * @param exposure_type Exposure type enumeration from 1 to N (0 means ignore) + * @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + * @param engine_cut_off Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) + * @param extra_param Extra parameters enumeration (0 means ignore) + * @param extra_value Correspondent value to given extra_param + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_digicam_configure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t mode,uint16_t shutter_speed,uint8_t aperture,uint8_t iso,uint8_t exposure_type,uint8_t command_id,uint8_t engine_cut_off,uint8_t extra_param,float extra_value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[15]; + _mav_put_float(buf, 0, extra_value); + _mav_put_uint16_t(buf, 4, shutter_speed); + _mav_put_uint8_t(buf, 6, target_system); + _mav_put_uint8_t(buf, 7, target_component); + _mav_put_uint8_t(buf, 8, mode); + _mav_put_uint8_t(buf, 9, aperture); + _mav_put_uint8_t(buf, 10, iso); + _mav_put_uint8_t(buf, 11, exposure_type); + _mav_put_uint8_t(buf, 12, command_id); + _mav_put_uint8_t(buf, 13, engine_cut_off); + _mav_put_uint8_t(buf, 14, extra_param); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); +#else + mavlink_digicam_configure_t packet; + packet.extra_value = extra_value; + packet.shutter_speed = shutter_speed; + packet.target_system = target_system; + packet.target_component = target_component; + packet.mode = mode; + packet.aperture = aperture; + packet.iso = iso; + packet.exposure_type = exposure_type; + packet.command_id = command_id; + packet.engine_cut_off = engine_cut_off; + packet.extra_param = extra_param; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); +#endif + + msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 15, 84); +} + +/** + * @brief Encode a digicam_configure 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 digicam_configure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_digicam_configure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_digicam_configure_t* digicam_configure) +{ + return mavlink_msg_digicam_configure_pack(system_id, component_id, msg, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value); +} + +/** + * @brief Send a digicam_configure message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param mode Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) + * @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore) + * @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) + * @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) + * @param exposure_type Exposure type enumeration from 1 to N (0 means ignore) + * @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + * @param engine_cut_off Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) + * @param extra_param Extra parameters enumeration (0 means ignore) + * @param extra_value Correspondent value to given extra_param + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_digicam_configure_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[15]; + _mav_put_float(buf, 0, extra_value); + _mav_put_uint16_t(buf, 4, shutter_speed); + _mav_put_uint8_t(buf, 6, target_system); + _mav_put_uint8_t(buf, 7, target_component); + _mav_put_uint8_t(buf, 8, mode); + _mav_put_uint8_t(buf, 9, aperture); + _mav_put_uint8_t(buf, 10, iso); + _mav_put_uint8_t(buf, 11, exposure_type); + _mav_put_uint8_t(buf, 12, command_id); + _mav_put_uint8_t(buf, 13, engine_cut_off); + _mav_put_uint8_t(buf, 14, extra_param); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, buf, 15, 84); +#else + mavlink_digicam_configure_t packet; + packet.extra_value = extra_value; + packet.shutter_speed = shutter_speed; + packet.target_system = target_system; + packet.target_component = target_component; + packet.mode = mode; + packet.aperture = aperture; + packet.iso = iso; + packet.exposure_type = exposure_type; + packet.command_id = command_id; + packet.engine_cut_off = engine_cut_off; + packet.extra_param = extra_param; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (const char *)&packet, 15, 84); +#endif +} + +#endif + +// MESSAGE DIGICAM_CONFIGURE UNPACKING + + +/** + * @brief Get field target_system from digicam_configure message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_digicam_configure_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field target_component from digicam_configure message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_digicam_configure_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field mode from digicam_configure message + * + * @return Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) + */ +static inline uint8_t mavlink_msg_digicam_configure_get_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Get field shutter_speed from digicam_configure message + * + * @return Divisor number //e.g. 1000 means 1/1000 (0 means ignore) + */ +static inline uint16_t mavlink_msg_digicam_configure_get_shutter_speed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field aperture from digicam_configure message + * + * @return F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) + */ +static inline uint8_t mavlink_msg_digicam_configure_get_aperture(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 9); +} + +/** + * @brief Get field iso from digicam_configure message + * + * @return ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) + */ +static inline uint8_t mavlink_msg_digicam_configure_get_iso(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 10); +} + +/** + * @brief Get field exposure_type from digicam_configure message + * + * @return Exposure type enumeration from 1 to N (0 means ignore) + */ +static inline uint8_t mavlink_msg_digicam_configure_get_exposure_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 11); +} + +/** + * @brief Get field command_id from digicam_configure message + * + * @return Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + */ +static inline uint8_t mavlink_msg_digicam_configure_get_command_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field engine_cut_off from digicam_configure message + * + * @return Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) + */ +static inline uint8_t mavlink_msg_digicam_configure_get_engine_cut_off(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 13); +} + +/** + * @brief Get field extra_param from digicam_configure message + * + * @return Extra parameters enumeration (0 means ignore) + */ +static inline uint8_t mavlink_msg_digicam_configure_get_extra_param(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 14); +} + +/** + * @brief Get field extra_value from digicam_configure message + * + * @return Correspondent value to given extra_param + */ +static inline float mavlink_msg_digicam_configure_get_extra_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Decode a digicam_configure message into a struct + * + * @param msg The message to decode + * @param digicam_configure C-struct to decode the message contents into + */ +static inline void mavlink_msg_digicam_configure_decode(const mavlink_message_t* msg, mavlink_digicam_configure_t* digicam_configure) +{ +#if MAVLINK_NEED_BYTE_SWAP + digicam_configure->extra_value = mavlink_msg_digicam_configure_get_extra_value(msg); + digicam_configure->shutter_speed = mavlink_msg_digicam_configure_get_shutter_speed(msg); + digicam_configure->target_system = mavlink_msg_digicam_configure_get_target_system(msg); + digicam_configure->target_component = mavlink_msg_digicam_configure_get_target_component(msg); + digicam_configure->mode = mavlink_msg_digicam_configure_get_mode(msg); + digicam_configure->aperture = mavlink_msg_digicam_configure_get_aperture(msg); + digicam_configure->iso = mavlink_msg_digicam_configure_get_iso(msg); + digicam_configure->exposure_type = mavlink_msg_digicam_configure_get_exposure_type(msg); + digicam_configure->command_id = mavlink_msg_digicam_configure_get_command_id(msg); + digicam_configure->engine_cut_off = mavlink_msg_digicam_configure_get_engine_cut_off(msg); + digicam_configure->extra_param = mavlink_msg_digicam_configure_get_extra_param(msg); +#else + memcpy(digicam_configure, _MAV_PAYLOAD(msg), 15); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h new file mode 100644 index 0000000000000000000000000000000000000000..a3b4878c434c3bee55a59ccc964b36f8d59f99ca --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h @@ -0,0 +1,342 @@ +// MESSAGE DIGICAM_CONTROL PACKING + +#define MAVLINK_MSG_ID_DIGICAM_CONTROL 155 + +typedef struct __mavlink_digicam_control_t +{ + float extra_value; ///< Correspondent value to given extra_param + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t session; ///< 0: stop, 1: start or keep it up //Session control e.g. show/hide lens + uint8_t zoom_pos; ///< 1 to N //Zoom's absolute position (0 means ignore) + int8_t zoom_step; ///< -100 to 100 //Zooming step value to offset zoom from the current position + uint8_t focus_lock; ///< 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus + uint8_t shot; ///< 0: ignore, 1: shot or start filming + uint8_t command_id; ///< Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + uint8_t extra_param; ///< Extra parameters enumeration (0 means ignore) +} mavlink_digicam_control_t; + +#define MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN 13 +#define MAVLINK_MSG_ID_155_LEN 13 + + + +#define MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL { \ + "DIGICAM_CONTROL", \ + 10, \ + { { "extra_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_digicam_control_t, extra_value) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_digicam_control_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_digicam_control_t, target_component) }, \ + { "session", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_digicam_control_t, session) }, \ + { "zoom_pos", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_digicam_control_t, zoom_pos) }, \ + { "zoom_step", NULL, MAVLINK_TYPE_INT8_T, 0, 8, offsetof(mavlink_digicam_control_t, zoom_step) }, \ + { "focus_lock", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_digicam_control_t, focus_lock) }, \ + { "shot", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_digicam_control_t, shot) }, \ + { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_digicam_control_t, command_id) }, \ + { "extra_param", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_digicam_control_t, extra_param) }, \ + } \ +} + + +/** + * @brief Pack a digicam_control 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 target_system System ID + * @param target_component Component ID + * @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens + * @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore) + * @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position + * @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus + * @param shot 0: ignore, 1: shot or start filming + * @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + * @param extra_param Extra parameters enumeration (0 means ignore) + * @param extra_value Correspondent value to given extra_param + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_digicam_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[13]; + _mav_put_float(buf, 0, extra_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 6, session); + _mav_put_uint8_t(buf, 7, zoom_pos); + _mav_put_int8_t(buf, 8, zoom_step); + _mav_put_uint8_t(buf, 9, focus_lock); + _mav_put_uint8_t(buf, 10, shot); + _mav_put_uint8_t(buf, 11, command_id); + _mav_put_uint8_t(buf, 12, extra_param); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13); +#else + mavlink_digicam_control_t packet; + packet.extra_value = extra_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.session = session; + packet.zoom_pos = zoom_pos; + packet.zoom_step = zoom_step; + packet.focus_lock = focus_lock; + packet.shot = shot; + packet.command_id = command_id; + packet.extra_param = extra_param; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13); +#endif + + msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL; + return mavlink_finalize_message(msg, system_id, component_id, 13, 22); +} + +/** + * @brief Pack a digicam_control 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 target_system System ID + * @param target_component Component ID + * @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens + * @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore) + * @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position + * @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus + * @param shot 0: ignore, 1: shot or start filming + * @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + * @param extra_param Extra parameters enumeration (0 means ignore) + * @param extra_value Correspondent value to given extra_param + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_digicam_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t session,uint8_t zoom_pos,int8_t zoom_step,uint8_t focus_lock,uint8_t shot,uint8_t command_id,uint8_t extra_param,float extra_value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[13]; + _mav_put_float(buf, 0, extra_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 6, session); + _mav_put_uint8_t(buf, 7, zoom_pos); + _mav_put_int8_t(buf, 8, zoom_step); + _mav_put_uint8_t(buf, 9, focus_lock); + _mav_put_uint8_t(buf, 10, shot); + _mav_put_uint8_t(buf, 11, command_id); + _mav_put_uint8_t(buf, 12, extra_param); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13); +#else + mavlink_digicam_control_t packet; + packet.extra_value = extra_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.session = session; + packet.zoom_pos = zoom_pos; + packet.zoom_step = zoom_step; + packet.focus_lock = focus_lock; + packet.shot = shot; + packet.command_id = command_id; + packet.extra_param = extra_param; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13); +#endif + + msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 13, 22); +} + +/** + * @brief Encode a digicam_control 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 digicam_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_digicam_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_digicam_control_t* digicam_control) +{ + return mavlink_msg_digicam_control_pack(system_id, component_id, msg, digicam_control->target_system, digicam_control->target_component, digicam_control->session, digicam_control->zoom_pos, digicam_control->zoom_step, digicam_control->focus_lock, digicam_control->shot, digicam_control->command_id, digicam_control->extra_param, digicam_control->extra_value); +} + +/** + * @brief Send a digicam_control message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens + * @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore) + * @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position + * @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus + * @param shot 0: ignore, 1: shot or start filming + * @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + * @param extra_param Extra parameters enumeration (0 means ignore) + * @param extra_value Correspondent value to given extra_param + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_digicam_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[13]; + _mav_put_float(buf, 0, extra_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 6, session); + _mav_put_uint8_t(buf, 7, zoom_pos); + _mav_put_int8_t(buf, 8, zoom_step); + _mav_put_uint8_t(buf, 9, focus_lock); + _mav_put_uint8_t(buf, 10, shot); + _mav_put_uint8_t(buf, 11, command_id); + _mav_put_uint8_t(buf, 12, extra_param); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, buf, 13, 22); +#else + mavlink_digicam_control_t packet; + packet.extra_value = extra_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.session = session; + packet.zoom_pos = zoom_pos; + packet.zoom_step = zoom_step; + packet.focus_lock = focus_lock; + packet.shot = shot; + packet.command_id = command_id; + packet.extra_param = extra_param; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, (const char *)&packet, 13, 22); +#endif +} + +#endif + +// MESSAGE DIGICAM_CONTROL UNPACKING + + +/** + * @brief Get field target_system from digicam_control message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_digicam_control_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field target_component from digicam_control message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_digicam_control_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field session from digicam_control message + * + * @return 0: stop, 1: start or keep it up //Session control e.g. show/hide lens + */ +static inline uint8_t mavlink_msg_digicam_control_get_session(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field zoom_pos from digicam_control message + * + * @return 1 to N //Zoom's absolute position (0 means ignore) + */ +static inline uint8_t mavlink_msg_digicam_control_get_zoom_pos(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field zoom_step from digicam_control message + * + * @return -100 to 100 //Zooming step value to offset zoom from the current position + */ +static inline int8_t mavlink_msg_digicam_control_get_zoom_step(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 8); +} + +/** + * @brief Get field focus_lock from digicam_control message + * + * @return 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus + */ +static inline uint8_t mavlink_msg_digicam_control_get_focus_lock(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 9); +} + +/** + * @brief Get field shot from digicam_control message + * + * @return 0: ignore, 1: shot or start filming + */ +static inline uint8_t mavlink_msg_digicam_control_get_shot(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 10); +} + +/** + * @brief Get field command_id from digicam_control message + * + * @return Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + */ +static inline uint8_t mavlink_msg_digicam_control_get_command_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 11); +} + +/** + * @brief Get field extra_param from digicam_control message + * + * @return Extra parameters enumeration (0 means ignore) + */ +static inline uint8_t mavlink_msg_digicam_control_get_extra_param(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field extra_value from digicam_control message + * + * @return Correspondent value to given extra_param + */ +static inline float mavlink_msg_digicam_control_get_extra_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Decode a digicam_control message into a struct + * + * @param msg The message to decode + * @param digicam_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_digicam_control_decode(const mavlink_message_t* msg, mavlink_digicam_control_t* digicam_control) +{ +#if MAVLINK_NEED_BYTE_SWAP + digicam_control->extra_value = mavlink_msg_digicam_control_get_extra_value(msg); + digicam_control->target_system = mavlink_msg_digicam_control_get_target_system(msg); + digicam_control->target_component = mavlink_msg_digicam_control_get_target_component(msg); + digicam_control->session = mavlink_msg_digicam_control_get_session(msg); + digicam_control->zoom_pos = mavlink_msg_digicam_control_get_zoom_pos(msg); + digicam_control->zoom_step = mavlink_msg_digicam_control_get_zoom_step(msg); + digicam_control->focus_lock = mavlink_msg_digicam_control_get_focus_lock(msg); + digicam_control->shot = mavlink_msg_digicam_control_get_shot(msg); + digicam_control->command_id = mavlink_msg_digicam_control_get_command_id(msg); + digicam_control->extra_param = mavlink_msg_digicam_control_get_extra_param(msg); +#else + memcpy(digicam_control, _MAV_PAYLOAD(msg), 13); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h new file mode 100644 index 0000000000000000000000000000000000000000..c1e405b0a5a986bf54635eb15e21204880458f77 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h @@ -0,0 +1,188 @@ +// MESSAGE FENCE_FETCH_POINT PACKING + +#define MAVLINK_MSG_ID_FENCE_FETCH_POINT 161 + +typedef struct __mavlink_fence_fetch_point_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t idx; ///< point index (first point is 1, 0 is for return point) +} mavlink_fence_fetch_point_t; + +#define MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN 3 +#define MAVLINK_MSG_ID_161_LEN 3 + + + +#define MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT { \ + "FENCE_FETCH_POINT", \ + 3, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_fence_fetch_point_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_fence_fetch_point_t, target_component) }, \ + { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_fence_fetch_point_t, idx) }, \ + } \ +} + + +/** + * @brief Pack a fence_fetch_point 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 target_system System ID + * @param target_component Component ID + * @param idx point index (first point is 1, 0 is for return point) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_fence_fetch_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t idx) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, idx); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); +#else + mavlink_fence_fetch_point_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.idx = idx; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT; + return mavlink_finalize_message(msg, system_id, component_id, 3, 68); +} + +/** + * @brief Pack a fence_fetch_point 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 target_system System ID + * @param target_component Component ID + * @param idx point index (first point is 1, 0 is for return point) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_fence_fetch_point_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t idx) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, idx); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); +#else + mavlink_fence_fetch_point_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.idx = idx; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 68); +} + +/** + * @brief Encode a fence_fetch_point 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 fence_fetch_point C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_fence_fetch_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_fetch_point_t* fence_fetch_point) +{ + return mavlink_msg_fence_fetch_point_pack(system_id, component_id, msg, fence_fetch_point->target_system, fence_fetch_point->target_component, fence_fetch_point->idx); +} + +/** + * @brief Send a fence_fetch_point message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param idx point index (first point is 1, 0 is for return point) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_fence_fetch_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, idx); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, buf, 3, 68); +#else + mavlink_fence_fetch_point_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.idx = idx; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, (const char *)&packet, 3, 68); +#endif +} + +#endif + +// MESSAGE FENCE_FETCH_POINT UNPACKING + + +/** + * @brief Get field target_system from fence_fetch_point message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_fence_fetch_point_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from fence_fetch_point message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_fence_fetch_point_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field idx from fence_fetch_point message + * + * @return point index (first point is 1, 0 is for return point) + */ +static inline uint8_t mavlink_msg_fence_fetch_point_get_idx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Decode a fence_fetch_point message into a struct + * + * @param msg The message to decode + * @param fence_fetch_point C-struct to decode the message contents into + */ +static inline void mavlink_msg_fence_fetch_point_decode(const mavlink_message_t* msg, mavlink_fence_fetch_point_t* fence_fetch_point) +{ +#if MAVLINK_NEED_BYTE_SWAP + fence_fetch_point->target_system = mavlink_msg_fence_fetch_point_get_target_system(msg); + fence_fetch_point->target_component = mavlink_msg_fence_fetch_point_get_target_component(msg); + fence_fetch_point->idx = mavlink_msg_fence_fetch_point_get_idx(msg); +#else + memcpy(fence_fetch_point, _MAV_PAYLOAD(msg), 3); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h new file mode 100644 index 0000000000000000000000000000000000000000..b31319c74909effcc71e3f2217ef8f04f5593bd6 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h @@ -0,0 +1,254 @@ +// MESSAGE FENCE_POINT PACKING + +#define MAVLINK_MSG_ID_FENCE_POINT 160 + +typedef struct __mavlink_fence_point_t +{ + float lat; ///< Latitude of point + float lng; ///< Longitude of point + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t idx; ///< point index (first point is 1, 0 is for return point) + uint8_t count; ///< total number of points (for sanity checking) +} mavlink_fence_point_t; + +#define MAVLINK_MSG_ID_FENCE_POINT_LEN 12 +#define MAVLINK_MSG_ID_160_LEN 12 + + + +#define MAVLINK_MESSAGE_INFO_FENCE_POINT { \ + "FENCE_POINT", \ + 6, \ + { { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_fence_point_t, lat) }, \ + { "lng", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_fence_point_t, lng) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fence_point_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fence_point_t, target_component) }, \ + { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fence_point_t, idx) }, \ + { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fence_point_t, count) }, \ + } \ +} + + +/** + * @brief Pack a fence_point 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 target_system System ID + * @param target_component Component ID + * @param idx point index (first point is 1, 0 is for return point) + * @param count total number of points (for sanity checking) + * @param lat Latitude of point + * @param lng Longitude of point + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_float(buf, 0, lat); + _mav_put_float(buf, 4, lng); + _mav_put_uint8_t(buf, 8, target_system); + _mav_put_uint8_t(buf, 9, target_component); + _mav_put_uint8_t(buf, 10, idx); + _mav_put_uint8_t(buf, 11, count); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_fence_point_t packet; + packet.lat = lat; + packet.lng = lng; + packet.target_system = target_system; + packet.target_component = target_component; + packet.idx = idx; + packet.count = count; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_FENCE_POINT; + return mavlink_finalize_message(msg, system_id, component_id, 12, 78); +} + +/** + * @brief Pack a fence_point 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 target_system System ID + * @param target_component Component ID + * @param idx point index (first point is 1, 0 is for return point) + * @param count total number of points (for sanity checking) + * @param lat Latitude of point + * @param lng Longitude of point + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_fence_point_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t idx,uint8_t count,float lat,float lng) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_float(buf, 0, lat); + _mav_put_float(buf, 4, lng); + _mav_put_uint8_t(buf, 8, target_system); + _mav_put_uint8_t(buf, 9, target_component); + _mav_put_uint8_t(buf, 10, idx); + _mav_put_uint8_t(buf, 11, count); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_fence_point_t packet; + packet.lat = lat; + packet.lng = lng; + packet.target_system = target_system; + packet.target_component = target_component; + packet.idx = idx; + packet.count = count; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_FENCE_POINT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 78); +} + +/** + * @brief Encode a fence_point 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 fence_point C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_fence_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_point_t* fence_point) +{ + return mavlink_msg_fence_point_pack(system_id, component_id, msg, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng); +} + +/** + * @brief Send a fence_point message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param idx point index (first point is 1, 0 is for return point) + * @param count total number of points (for sanity checking) + * @param lat Latitude of point + * @param lng Longitude of point + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_fence_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_float(buf, 0, lat); + _mav_put_float(buf, 4, lng); + _mav_put_uint8_t(buf, 8, target_system); + _mav_put_uint8_t(buf, 9, target_component); + _mav_put_uint8_t(buf, 10, idx); + _mav_put_uint8_t(buf, 11, count); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, 12, 78); +#else + mavlink_fence_point_t packet; + packet.lat = lat; + packet.lng = lng; + packet.target_system = target_system; + packet.target_component = target_component; + packet.idx = idx; + packet.count = count; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)&packet, 12, 78); +#endif +} + +#endif + +// MESSAGE FENCE_POINT UNPACKING + + +/** + * @brief Get field target_system from fence_point message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_fence_point_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Get field target_component from fence_point message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_fence_point_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 9); +} + +/** + * @brief Get field idx from fence_point message + * + * @return point index (first point is 1, 0 is for return point) + */ +static inline uint8_t mavlink_msg_fence_point_get_idx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 10); +} + +/** + * @brief Get field count from fence_point message + * + * @return total number of points (for sanity checking) + */ +static inline uint8_t mavlink_msg_fence_point_get_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 11); +} + +/** + * @brief Get field lat from fence_point message + * + * @return Latitude of point + */ +static inline float mavlink_msg_fence_point_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field lng from fence_point message + * + * @return Longitude of point + */ +static inline float mavlink_msg_fence_point_get_lng(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Decode a fence_point message into a struct + * + * @param msg The message to decode + * @param fence_point C-struct to decode the message contents into + */ +static inline void mavlink_msg_fence_point_decode(const mavlink_message_t* msg, mavlink_fence_point_t* fence_point) +{ +#if MAVLINK_NEED_BYTE_SWAP + fence_point->lat = mavlink_msg_fence_point_get_lat(msg); + fence_point->lng = mavlink_msg_fence_point_get_lng(msg); + fence_point->target_system = mavlink_msg_fence_point_get_target_system(msg); + fence_point->target_component = mavlink_msg_fence_point_get_target_component(msg); + fence_point->idx = mavlink_msg_fence_point_get_idx(msg); + fence_point->count = mavlink_msg_fence_point_get_count(msg); +#else + memcpy(fence_point, _MAV_PAYLOAD(msg), 12); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h new file mode 100644 index 0000000000000000000000000000000000000000..ce3e7ee67bb51e7884d30631eb1506328a0040df --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h @@ -0,0 +1,210 @@ +// MESSAGE FENCE_STATUS PACKING + +#define MAVLINK_MSG_ID_FENCE_STATUS 162 + +typedef struct __mavlink_fence_status_t +{ + uint32_t breach_time; ///< time of last breach in milliseconds since boot + uint16_t breach_count; ///< number of fence breaches + uint8_t breach_status; ///< 0 if currently inside fence, 1 if outside + uint8_t breach_type; ///< last breach type (see FENCE_BREACH_* enum) +} mavlink_fence_status_t; + +#define MAVLINK_MSG_ID_FENCE_STATUS_LEN 8 +#define MAVLINK_MSG_ID_162_LEN 8 + + + +#define MAVLINK_MESSAGE_INFO_FENCE_STATUS { \ + "FENCE_STATUS", \ + 4, \ + { { "breach_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_fence_status_t, breach_time) }, \ + { "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_fence_status_t, breach_count) }, \ + { "breach_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_fence_status_t, breach_status) }, \ + { "breach_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_fence_status_t, breach_type) }, \ + } \ +} + + +/** + * @brief Pack a fence_status 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 breach_status 0 if currently inside fence, 1 if outside + * @param breach_count number of fence breaches + * @param breach_type last breach type (see FENCE_BREACH_* enum) + * @param breach_time time of last breach in milliseconds since boot + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[8]; + _mav_put_uint32_t(buf, 0, breach_time); + _mav_put_uint16_t(buf, 4, breach_count); + _mav_put_uint8_t(buf, 6, breach_status); + _mav_put_uint8_t(buf, 7, breach_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); +#else + mavlink_fence_status_t packet; + packet.breach_time = breach_time; + packet.breach_count = breach_count; + packet.breach_status = breach_status; + packet.breach_type = breach_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); +#endif + + msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS; + return mavlink_finalize_message(msg, system_id, component_id, 8, 189); +} + +/** + * @brief Pack a fence_status 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 breach_status 0 if currently inside fence, 1 if outside + * @param breach_count number of fence breaches + * @param breach_type last breach type (see FENCE_BREACH_* enum) + * @param breach_time time of last breach in milliseconds since boot + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t breach_status,uint16_t breach_count,uint8_t breach_type,uint32_t breach_time) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[8]; + _mav_put_uint32_t(buf, 0, breach_time); + _mav_put_uint16_t(buf, 4, breach_count); + _mav_put_uint8_t(buf, 6, breach_status); + _mav_put_uint8_t(buf, 7, breach_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); +#else + mavlink_fence_status_t packet; + packet.breach_time = breach_time; + packet.breach_count = breach_count; + packet.breach_status = breach_status; + packet.breach_type = breach_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); +#endif + + msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8, 189); +} + +/** + * @brief Encode a fence_status 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 fence_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_fence_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status) +{ + return mavlink_msg_fence_status_pack(system_id, component_id, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time); +} + +/** + * @brief Send a fence_status message + * @param chan MAVLink channel to send the message + * + * @param breach_status 0 if currently inside fence, 1 if outside + * @param breach_count number of fence breaches + * @param breach_type last breach type (see FENCE_BREACH_* enum) + * @param breach_time time of last breach in milliseconds since boot + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_fence_status_send(mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[8]; + _mav_put_uint32_t(buf, 0, breach_time); + _mav_put_uint16_t(buf, 4, breach_count); + _mav_put_uint8_t(buf, 6, breach_status); + _mav_put_uint8_t(buf, 7, breach_type); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, 8, 189); +#else + mavlink_fence_status_t packet; + packet.breach_time = breach_time; + packet.breach_count = breach_count; + packet.breach_status = breach_status; + packet.breach_type = breach_type; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)&packet, 8, 189); +#endif +} + +#endif + +// MESSAGE FENCE_STATUS UNPACKING + + +/** + * @brief Get field breach_status from fence_status message + * + * @return 0 if currently inside fence, 1 if outside + */ +static inline uint8_t mavlink_msg_fence_status_get_breach_status(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field breach_count from fence_status message + * + * @return number of fence breaches + */ +static inline uint16_t mavlink_msg_fence_status_get_breach_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field breach_type from fence_status message + * + * @return last breach type (see FENCE_BREACH_* enum) + */ +static inline uint8_t mavlink_msg_fence_status_get_breach_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field breach_time from fence_status message + * + * @return time of last breach in milliseconds since boot + */ +static inline uint32_t mavlink_msg_fence_status_get_breach_time(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Decode a fence_status message into a struct + * + * @param msg The message to decode + * @param fence_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_fence_status_decode(const mavlink_message_t* msg, mavlink_fence_status_t* fence_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + fence_status->breach_time = mavlink_msg_fence_status_get_breach_time(msg); + fence_status->breach_count = mavlink_msg_fence_status_get_breach_count(msg); + fence_status->breach_status = mavlink_msg_fence_status_get_breach_status(msg); + fence_status->breach_type = mavlink_msg_fence_status_get_breach_type(msg); +#else + memcpy(fence_status, _MAV_PAYLOAD(msg), 8); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h new file mode 100644 index 0000000000000000000000000000000000000000..a095a804f3cb5a6a59569f934b0a6d0a4c30f81a --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h @@ -0,0 +1,166 @@ +// MESSAGE MEMINFO PACKING + +#define MAVLINK_MSG_ID_MEMINFO 152 + +typedef struct __mavlink_meminfo_t +{ + uint16_t brkval; ///< heap top + uint16_t freemem; ///< free memory +} mavlink_meminfo_t; + +#define MAVLINK_MSG_ID_MEMINFO_LEN 4 +#define MAVLINK_MSG_ID_152_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_MEMINFO { \ + "MEMINFO", \ + 2, \ + { { "brkval", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_meminfo_t, brkval) }, \ + { "freemem", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_meminfo_t, freemem) }, \ + } \ +} + + +/** + * @brief Pack a meminfo 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 brkval heap top + * @param freemem free memory + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_meminfo_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t brkval, uint16_t freemem) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, brkval); + _mav_put_uint16_t(buf, 2, freemem); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); +#else + mavlink_meminfo_t packet; + packet.brkval = brkval; + packet.freemem = freemem; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_MEMINFO; + return mavlink_finalize_message(msg, system_id, component_id, 4, 208); +} + +/** + * @brief Pack a meminfo 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 brkval heap top + * @param freemem free memory + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_meminfo_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t brkval,uint16_t freemem) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, brkval); + _mav_put_uint16_t(buf, 2, freemem); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); +#else + mavlink_meminfo_t packet; + packet.brkval = brkval; + packet.freemem = freemem; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_MEMINFO; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 208); +} + +/** + * @brief Encode a meminfo 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 meminfo C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_meminfo_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_meminfo_t* meminfo) +{ + return mavlink_msg_meminfo_pack(system_id, component_id, msg, meminfo->brkval, meminfo->freemem); +} + +/** + * @brief Send a meminfo message + * @param chan MAVLink channel to send the message + * + * @param brkval heap top + * @param freemem free memory + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_meminfo_send(mavlink_channel_t chan, uint16_t brkval, uint16_t freemem) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, brkval); + _mav_put_uint16_t(buf, 2, freemem); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, buf, 4, 208); +#else + mavlink_meminfo_t packet; + packet.brkval = brkval; + packet.freemem = freemem; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)&packet, 4, 208); +#endif +} + +#endif + +// MESSAGE MEMINFO UNPACKING + + +/** + * @brief Get field brkval from meminfo message + * + * @return heap top + */ +static inline uint16_t mavlink_msg_meminfo_get_brkval(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field freemem from meminfo message + * + * @return free memory + */ +static inline uint16_t mavlink_msg_meminfo_get_freemem(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Decode a meminfo message into a struct + * + * @param msg The message to decode + * @param meminfo C-struct to decode the message contents into + */ +static inline void mavlink_msg_meminfo_decode(const mavlink_message_t* msg, mavlink_meminfo_t* meminfo) +{ +#if MAVLINK_NEED_BYTE_SWAP + meminfo->brkval = mavlink_msg_meminfo_get_brkval(msg); + meminfo->freemem = mavlink_msg_meminfo_get_freemem(msg); +#else + memcpy(meminfo, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h new file mode 100644 index 0000000000000000000000000000000000000000..051a7183794528cedbc1c29984c3d47dd15b4b8e --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h @@ -0,0 +1,254 @@ +// MESSAGE MOUNT_CONFIGURE PACKING + +#define MAVLINK_MSG_ID_MOUNT_CONFIGURE 156 + +typedef struct __mavlink_mount_configure_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t mount_mode; ///< mount operating mode (see MAV_MOUNT_MODE enum) + uint8_t stab_roll; ///< (1 = yes, 0 = no) + uint8_t stab_pitch; ///< (1 = yes, 0 = no) + uint8_t stab_yaw; ///< (1 = yes, 0 = no) +} mavlink_mount_configure_t; + +#define MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN 6 +#define MAVLINK_MSG_ID_156_LEN 6 + + + +#define MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE { \ + "MOUNT_CONFIGURE", \ + 6, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mount_configure_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mount_configure_t, target_component) }, \ + { "mount_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mount_configure_t, mount_mode) }, \ + { "stab_roll", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mount_configure_t, stab_roll) }, \ + { "stab_pitch", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mount_configure_t, stab_pitch) }, \ + { "stab_yaw", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mount_configure_t, stab_yaw) }, \ + } \ +} + + +/** + * @brief Pack a mount_configure 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 target_system System ID + * @param target_component Component ID + * @param mount_mode mount operating mode (see MAV_MOUNT_MODE enum) + * @param stab_roll (1 = yes, 0 = no) + * @param stab_pitch (1 = yes, 0 = no) + * @param stab_yaw (1 = yes, 0 = no) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mount_configure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, mount_mode); + _mav_put_uint8_t(buf, 3, stab_roll); + _mav_put_uint8_t(buf, 4, stab_pitch); + _mav_put_uint8_t(buf, 5, stab_yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); +#else + mavlink_mount_configure_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.mount_mode = mount_mode; + packet.stab_roll = stab_roll; + packet.stab_pitch = stab_pitch; + packet.stab_yaw = stab_yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); +#endif + + msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE; + return mavlink_finalize_message(msg, system_id, component_id, 6, 19); +} + +/** + * @brief Pack a mount_configure 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 target_system System ID + * @param target_component Component ID + * @param mount_mode mount operating mode (see MAV_MOUNT_MODE enum) + * @param stab_roll (1 = yes, 0 = no) + * @param stab_pitch (1 = yes, 0 = no) + * @param stab_yaw (1 = yes, 0 = no) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mount_configure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t mount_mode,uint8_t stab_roll,uint8_t stab_pitch,uint8_t stab_yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, mount_mode); + _mav_put_uint8_t(buf, 3, stab_roll); + _mav_put_uint8_t(buf, 4, stab_pitch); + _mav_put_uint8_t(buf, 5, stab_yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); +#else + mavlink_mount_configure_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.mount_mode = mount_mode; + packet.stab_roll = stab_roll; + packet.stab_pitch = stab_pitch; + packet.stab_yaw = stab_yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); +#endif + + msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 19); +} + +/** + * @brief Encode a mount_configure 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 mount_configure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mount_configure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_configure_t* mount_configure) +{ + return mavlink_msg_mount_configure_pack(system_id, component_id, msg, mount_configure->target_system, mount_configure->target_component, mount_configure->mount_mode, mount_configure->stab_roll, mount_configure->stab_pitch, mount_configure->stab_yaw); +} + +/** + * @brief Send a mount_configure message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param mount_mode mount operating mode (see MAV_MOUNT_MODE enum) + * @param stab_roll (1 = yes, 0 = no) + * @param stab_pitch (1 = yes, 0 = no) + * @param stab_yaw (1 = yes, 0 = no) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mount_configure_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, mount_mode); + _mav_put_uint8_t(buf, 3, stab_roll); + _mav_put_uint8_t(buf, 4, stab_pitch); + _mav_put_uint8_t(buf, 5, stab_yaw); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, buf, 6, 19); +#else + mavlink_mount_configure_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.mount_mode = mount_mode; + packet.stab_roll = stab_roll; + packet.stab_pitch = stab_pitch; + packet.stab_yaw = stab_yaw; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)&packet, 6, 19); +#endif +} + +#endif + +// MESSAGE MOUNT_CONFIGURE UNPACKING + + +/** + * @brief Get field target_system from mount_configure message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mount_configure_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from mount_configure message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mount_configure_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field mount_mode from mount_configure message + * + * @return mount operating mode (see MAV_MOUNT_MODE enum) + */ +static inline uint8_t mavlink_msg_mount_configure_get_mount_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field stab_roll from mount_configure message + * + * @return (1 = yes, 0 = no) + */ +static inline uint8_t mavlink_msg_mount_configure_get_stab_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field stab_pitch from mount_configure message + * + * @return (1 = yes, 0 = no) + */ +static inline uint8_t mavlink_msg_mount_configure_get_stab_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field stab_yaw from mount_configure message + * + * @return (1 = yes, 0 = no) + */ +static inline uint8_t mavlink_msg_mount_configure_get_stab_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Decode a mount_configure message into a struct + * + * @param msg The message to decode + * @param mount_configure C-struct to decode the message contents into + */ +static inline void mavlink_msg_mount_configure_decode(const mavlink_message_t* msg, mavlink_mount_configure_t* mount_configure) +{ +#if MAVLINK_NEED_BYTE_SWAP + mount_configure->target_system = mavlink_msg_mount_configure_get_target_system(msg); + mount_configure->target_component = mavlink_msg_mount_configure_get_target_component(msg); + mount_configure->mount_mode = mavlink_msg_mount_configure_get_mount_mode(msg); + mount_configure->stab_roll = mavlink_msg_mount_configure_get_stab_roll(msg); + mount_configure->stab_pitch = mavlink_msg_mount_configure_get_stab_pitch(msg); + mount_configure->stab_yaw = mavlink_msg_mount_configure_get_stab_yaw(msg); +#else + memcpy(mount_configure, _MAV_PAYLOAD(msg), 6); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h new file mode 100644 index 0000000000000000000000000000000000000000..a519922997ce10af1eff72308e9423b85749cb51 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h @@ -0,0 +1,254 @@ +// MESSAGE MOUNT_CONTROL PACKING + +#define MAVLINK_MSG_ID_MOUNT_CONTROL 157 + +typedef struct __mavlink_mount_control_t +{ + int32_t input_a; ///< pitch(deg*100) or lat, depending on mount mode + int32_t input_b; ///< roll(deg*100) or lon depending on mount mode + int32_t input_c; ///< yaw(deg*100) or alt (in cm) depending on mount mode + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t save_position; ///< if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) +} mavlink_mount_control_t; + +#define MAVLINK_MSG_ID_MOUNT_CONTROL_LEN 15 +#define MAVLINK_MSG_ID_157_LEN 15 + + + +#define MAVLINK_MESSAGE_INFO_MOUNT_CONTROL { \ + "MOUNT_CONTROL", \ + 6, \ + { { "input_a", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_mount_control_t, input_a) }, \ + { "input_b", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_mount_control_t, input_b) }, \ + { "input_c", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_mount_control_t, input_c) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mount_control_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mount_control_t, target_component) }, \ + { "save_position", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_mount_control_t, save_position) }, \ + } \ +} + + +/** + * @brief Pack a mount_control 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 target_system System ID + * @param target_component Component ID + * @param input_a pitch(deg*100) or lat, depending on mount mode + * @param input_b roll(deg*100) or lon depending on mount mode + * @param input_c yaw(deg*100) or alt (in cm) depending on mount mode + * @param save_position if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mount_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[15]; + _mav_put_int32_t(buf, 0, input_a); + _mav_put_int32_t(buf, 4, input_b); + _mav_put_int32_t(buf, 8, input_c); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + _mav_put_uint8_t(buf, 14, save_position); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); +#else + mavlink_mount_control_t packet; + packet.input_a = input_a; + packet.input_b = input_b; + packet.input_c = input_c; + packet.target_system = target_system; + packet.target_component = target_component; + packet.save_position = save_position; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); +#endif + + msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL; + return mavlink_finalize_message(msg, system_id, component_id, 15, 21); +} + +/** + * @brief Pack a mount_control 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 target_system System ID + * @param target_component Component ID + * @param input_a pitch(deg*100) or lat, depending on mount mode + * @param input_b roll(deg*100) or lon depending on mount mode + * @param input_c yaw(deg*100) or alt (in cm) depending on mount mode + * @param save_position if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mount_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,int32_t input_a,int32_t input_b,int32_t input_c,uint8_t save_position) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[15]; + _mav_put_int32_t(buf, 0, input_a); + _mav_put_int32_t(buf, 4, input_b); + _mav_put_int32_t(buf, 8, input_c); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + _mav_put_uint8_t(buf, 14, save_position); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); +#else + mavlink_mount_control_t packet; + packet.input_a = input_a; + packet.input_b = input_b; + packet.input_c = input_c; + packet.target_system = target_system; + packet.target_component = target_component; + packet.save_position = save_position; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); +#endif + + msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 15, 21); +} + +/** + * @brief Encode a mount_control 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 mount_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mount_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_control_t* mount_control) +{ + return mavlink_msg_mount_control_pack(system_id, component_id, msg, mount_control->target_system, mount_control->target_component, mount_control->input_a, mount_control->input_b, mount_control->input_c, mount_control->save_position); +} + +/** + * @brief Send a mount_control message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param input_a pitch(deg*100) or lat, depending on mount mode + * @param input_b roll(deg*100) or lon depending on mount mode + * @param input_c yaw(deg*100) or alt (in cm) depending on mount mode + * @param save_position if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mount_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[15]; + _mav_put_int32_t(buf, 0, input_a); + _mav_put_int32_t(buf, 4, input_b); + _mav_put_int32_t(buf, 8, input_c); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + _mav_put_uint8_t(buf, 14, save_position); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, buf, 15, 21); +#else + mavlink_mount_control_t packet; + packet.input_a = input_a; + packet.input_b = input_b; + packet.input_c = input_c; + packet.target_system = target_system; + packet.target_component = target_component; + packet.save_position = save_position; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, (const char *)&packet, 15, 21); +#endif +} + +#endif + +// MESSAGE MOUNT_CONTROL UNPACKING + + +/** + * @brief Get field target_system from mount_control message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mount_control_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field target_component from mount_control message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mount_control_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 13); +} + +/** + * @brief Get field input_a from mount_control message + * + * @return pitch(deg*100) or lat, depending on mount mode + */ +static inline int32_t mavlink_msg_mount_control_get_input_a(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field input_b from mount_control message + * + * @return roll(deg*100) or lon depending on mount mode + */ +static inline int32_t mavlink_msg_mount_control_get_input_b(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field input_c from mount_control message + * + * @return yaw(deg*100) or alt (in cm) depending on mount mode + */ +static inline int32_t mavlink_msg_mount_control_get_input_c(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field save_position from mount_control message + * + * @return if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) + */ +static inline uint8_t mavlink_msg_mount_control_get_save_position(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 14); +} + +/** + * @brief Decode a mount_control message into a struct + * + * @param msg The message to decode + * @param mount_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_mount_control_decode(const mavlink_message_t* msg, mavlink_mount_control_t* mount_control) +{ +#if MAVLINK_NEED_BYTE_SWAP + mount_control->input_a = mavlink_msg_mount_control_get_input_a(msg); + mount_control->input_b = mavlink_msg_mount_control_get_input_b(msg); + mount_control->input_c = mavlink_msg_mount_control_get_input_c(msg); + mount_control->target_system = mavlink_msg_mount_control_get_target_system(msg); + mount_control->target_component = mavlink_msg_mount_control_get_target_component(msg); + mount_control->save_position = mavlink_msg_mount_control_get_save_position(msg); +#else + memcpy(mount_control, _MAV_PAYLOAD(msg), 15); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h new file mode 100644 index 0000000000000000000000000000000000000000..edc188ebd49b7c2f90dfade166c557b1d091cd28 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h @@ -0,0 +1,232 @@ +// MESSAGE MOUNT_STATUS PACKING + +#define MAVLINK_MSG_ID_MOUNT_STATUS 158 + +typedef struct __mavlink_mount_status_t +{ + int32_t pointing_a; ///< pitch(deg*100) or lat, depending on mount mode + int32_t pointing_b; ///< roll(deg*100) or lon depending on mount mode + int32_t pointing_c; ///< yaw(deg*100) or alt (in cm) depending on mount mode + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_mount_status_t; + +#define MAVLINK_MSG_ID_MOUNT_STATUS_LEN 14 +#define MAVLINK_MSG_ID_158_LEN 14 + + + +#define MAVLINK_MESSAGE_INFO_MOUNT_STATUS { \ + "MOUNT_STATUS", \ + 5, \ + { { "pointing_a", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_mount_status_t, pointing_a) }, \ + { "pointing_b", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_mount_status_t, pointing_b) }, \ + { "pointing_c", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_mount_status_t, pointing_c) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mount_status_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mount_status_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mount_status 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 target_system System ID + * @param target_component Component ID + * @param pointing_a pitch(deg*100) or lat, depending on mount mode + * @param pointing_b roll(deg*100) or lon depending on mount mode + * @param pointing_c yaw(deg*100) or alt (in cm) depending on mount mode + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mount_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[14]; + _mav_put_int32_t(buf, 0, pointing_a); + _mav_put_int32_t(buf, 4, pointing_b); + _mav_put_int32_t(buf, 8, pointing_c); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); +#else + mavlink_mount_status_t packet; + packet.pointing_a = pointing_a; + packet.pointing_b = pointing_b; + packet.pointing_c = pointing_c; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); +#endif + + msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS; + return mavlink_finalize_message(msg, system_id, component_id, 14, 134); +} + +/** + * @brief Pack a mount_status 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 target_system System ID + * @param target_component Component ID + * @param pointing_a pitch(deg*100) or lat, depending on mount mode + * @param pointing_b roll(deg*100) or lon depending on mount mode + * @param pointing_c yaw(deg*100) or alt (in cm) depending on mount mode + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mount_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,int32_t pointing_a,int32_t pointing_b,int32_t pointing_c) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[14]; + _mav_put_int32_t(buf, 0, pointing_a); + _mav_put_int32_t(buf, 4, pointing_b); + _mav_put_int32_t(buf, 8, pointing_c); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); +#else + mavlink_mount_status_t packet; + packet.pointing_a = pointing_a; + packet.pointing_b = pointing_b; + packet.pointing_c = pointing_c; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); +#endif + + msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 134); +} + +/** + * @brief Encode a mount_status 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 mount_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mount_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_status_t* mount_status) +{ + return mavlink_msg_mount_status_pack(system_id, component_id, msg, mount_status->target_system, mount_status->target_component, mount_status->pointing_a, mount_status->pointing_b, mount_status->pointing_c); +} + +/** + * @brief Send a mount_status message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param pointing_a pitch(deg*100) or lat, depending on mount mode + * @param pointing_b roll(deg*100) or lon depending on mount mode + * @param pointing_c yaw(deg*100) or alt (in cm) depending on mount mode + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mount_status_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[14]; + _mav_put_int32_t(buf, 0, pointing_a); + _mav_put_int32_t(buf, 4, pointing_b); + _mav_put_int32_t(buf, 8, pointing_c); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, buf, 14, 134); +#else + mavlink_mount_status_t packet; + packet.pointing_a = pointing_a; + packet.pointing_b = pointing_b; + packet.pointing_c = pointing_c; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)&packet, 14, 134); +#endif +} + +#endif + +// MESSAGE MOUNT_STATUS UNPACKING + + +/** + * @brief Get field target_system from mount_status message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mount_status_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field target_component from mount_status message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mount_status_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 13); +} + +/** + * @brief Get field pointing_a from mount_status message + * + * @return pitch(deg*100) or lat, depending on mount mode + */ +static inline int32_t mavlink_msg_mount_status_get_pointing_a(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field pointing_b from mount_status message + * + * @return roll(deg*100) or lon depending on mount mode + */ +static inline int32_t mavlink_msg_mount_status_get_pointing_b(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field pointing_c from mount_status message + * + * @return yaw(deg*100) or alt (in cm) depending on mount mode + */ +static inline int32_t mavlink_msg_mount_status_get_pointing_c(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Decode a mount_status message into a struct + * + * @param msg The message to decode + * @param mount_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_mount_status_decode(const mavlink_message_t* msg, mavlink_mount_status_t* mount_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + mount_status->pointing_a = mavlink_msg_mount_status_get_pointing_a(msg); + mount_status->pointing_b = mavlink_msg_mount_status_get_pointing_b(msg); + mount_status->pointing_c = mavlink_msg_mount_status_get_pointing_c(msg); + mount_status->target_system = mavlink_msg_mount_status_get_target_system(msg); + mount_status->target_component = mavlink_msg_mount_status_get_target_component(msg); +#else + memcpy(mount_status, _MAV_PAYLOAD(msg), 14); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h new file mode 100644 index 0000000000000000000000000000000000000000..56fb52d96d2720be8a54932427a559287873edec --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h @@ -0,0 +1,386 @@ +// MESSAGE SENSOR_OFFSETS PACKING + +#define MAVLINK_MSG_ID_SENSOR_OFFSETS 150 + +typedef struct __mavlink_sensor_offsets_t +{ + float mag_declination; ///< magnetic declination (radians) + int32_t raw_press; ///< raw pressure from barometer + int32_t raw_temp; ///< raw temperature from barometer + float gyro_cal_x; ///< gyro X calibration + float gyro_cal_y; ///< gyro Y calibration + float gyro_cal_z; ///< gyro Z calibration + float accel_cal_x; ///< accel X calibration + float accel_cal_y; ///< accel Y calibration + float accel_cal_z; ///< accel Z calibration + int16_t mag_ofs_x; ///< magnetometer X offset + int16_t mag_ofs_y; ///< magnetometer Y offset + int16_t mag_ofs_z; ///< magnetometer Z offset +} mavlink_sensor_offsets_t; + +#define MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN 42 +#define MAVLINK_MSG_ID_150_LEN 42 + + + +#define MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS { \ + "SENSOR_OFFSETS", \ + 12, \ + { { "mag_declination", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_offsets_t, mag_declination) }, \ + { "raw_press", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_sensor_offsets_t, raw_press) }, \ + { "raw_temp", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_sensor_offsets_t, raw_temp) }, \ + { "gyro_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sensor_offsets_t, gyro_cal_x) }, \ + { "gyro_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sensor_offsets_t, gyro_cal_y) }, \ + { "gyro_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sensor_offsets_t, gyro_cal_z) }, \ + { "accel_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sensor_offsets_t, accel_cal_x) }, \ + { "accel_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sensor_offsets_t, accel_cal_y) }, \ + { "accel_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sensor_offsets_t, accel_cal_z) }, \ + { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_sensor_offsets_t, mag_ofs_x) }, \ + { "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_sensor_offsets_t, mag_ofs_y) }, \ + { "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_sensor_offsets_t, mag_ofs_z) }, \ + } \ +} + + +/** + * @brief Pack a sensor_offsets 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 mag_ofs_x magnetometer X offset + * @param mag_ofs_y magnetometer Y offset + * @param mag_ofs_z magnetometer Z offset + * @param mag_declination magnetic declination (radians) + * @param raw_press raw pressure from barometer + * @param raw_temp raw temperature from barometer + * @param gyro_cal_x gyro X calibration + * @param gyro_cal_y gyro Y calibration + * @param gyro_cal_z gyro Z calibration + * @param accel_cal_x accel X calibration + * @param accel_cal_y accel Y calibration + * @param accel_cal_z accel Z calibration + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[42]; + _mav_put_float(buf, 0, mag_declination); + _mav_put_int32_t(buf, 4, raw_press); + _mav_put_int32_t(buf, 8, raw_temp); + _mav_put_float(buf, 12, gyro_cal_x); + _mav_put_float(buf, 16, gyro_cal_y); + _mav_put_float(buf, 20, gyro_cal_z); + _mav_put_float(buf, 24, accel_cal_x); + _mav_put_float(buf, 28, accel_cal_y); + _mav_put_float(buf, 32, accel_cal_z); + _mav_put_int16_t(buf, 36, mag_ofs_x); + _mav_put_int16_t(buf, 38, mag_ofs_y); + _mav_put_int16_t(buf, 40, mag_ofs_z); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42); +#else + mavlink_sensor_offsets_t packet; + packet.mag_declination = mag_declination; + packet.raw_press = raw_press; + packet.raw_temp = raw_temp; + packet.gyro_cal_x = gyro_cal_x; + packet.gyro_cal_y = gyro_cal_y; + packet.gyro_cal_z = gyro_cal_z; + packet.accel_cal_x = accel_cal_x; + packet.accel_cal_y = accel_cal_y; + packet.accel_cal_z = accel_cal_z; + packet.mag_ofs_x = mag_ofs_x; + packet.mag_ofs_y = mag_ofs_y; + packet.mag_ofs_z = mag_ofs_z; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42); +#endif + + msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS; + return mavlink_finalize_message(msg, system_id, component_id, 42, 134); +} + +/** + * @brief Pack a sensor_offsets 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 mag_ofs_x magnetometer X offset + * @param mag_ofs_y magnetometer Y offset + * @param mag_ofs_z magnetometer Z offset + * @param mag_declination magnetic declination (radians) + * @param raw_press raw pressure from barometer + * @param raw_temp raw temperature from barometer + * @param gyro_cal_x gyro X calibration + * @param gyro_cal_y gyro Y calibration + * @param gyro_cal_z gyro Z calibration + * @param accel_cal_x accel X calibration + * @param accel_cal_y accel Y calibration + * @param accel_cal_z accel Z calibration + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z,float mag_declination,int32_t raw_press,int32_t raw_temp,float gyro_cal_x,float gyro_cal_y,float gyro_cal_z,float accel_cal_x,float accel_cal_y,float accel_cal_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[42]; + _mav_put_float(buf, 0, mag_declination); + _mav_put_int32_t(buf, 4, raw_press); + _mav_put_int32_t(buf, 8, raw_temp); + _mav_put_float(buf, 12, gyro_cal_x); + _mav_put_float(buf, 16, gyro_cal_y); + _mav_put_float(buf, 20, gyro_cal_z); + _mav_put_float(buf, 24, accel_cal_x); + _mav_put_float(buf, 28, accel_cal_y); + _mav_put_float(buf, 32, accel_cal_z); + _mav_put_int16_t(buf, 36, mag_ofs_x); + _mav_put_int16_t(buf, 38, mag_ofs_y); + _mav_put_int16_t(buf, 40, mag_ofs_z); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42); +#else + mavlink_sensor_offsets_t packet; + packet.mag_declination = mag_declination; + packet.raw_press = raw_press; + packet.raw_temp = raw_temp; + packet.gyro_cal_x = gyro_cal_x; + packet.gyro_cal_y = gyro_cal_y; + packet.gyro_cal_z = gyro_cal_z; + packet.accel_cal_x = accel_cal_x; + packet.accel_cal_y = accel_cal_y; + packet.accel_cal_z = accel_cal_z; + packet.mag_ofs_x = mag_ofs_x; + packet.mag_ofs_y = mag_ofs_y; + packet.mag_ofs_z = mag_ofs_z; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42); +#endif + + msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 42, 134); +} + +/** + * @brief Encode a sensor_offsets 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 sensor_offsets C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_sensor_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_offsets_t* sensor_offsets) +{ + return mavlink_msg_sensor_offsets_pack(system_id, component_id, msg, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z); +} + +/** + * @brief Send a sensor_offsets message + * @param chan MAVLink channel to send the message + * + * @param mag_ofs_x magnetometer X offset + * @param mag_ofs_y magnetometer Y offset + * @param mag_ofs_z magnetometer Z offset + * @param mag_declination magnetic declination (radians) + * @param raw_press raw pressure from barometer + * @param raw_temp raw temperature from barometer + * @param gyro_cal_x gyro X calibration + * @param gyro_cal_y gyro Y calibration + * @param gyro_cal_z gyro Z calibration + * @param accel_cal_x accel X calibration + * @param accel_cal_y accel Y calibration + * @param accel_cal_z accel Z calibration + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_sensor_offsets_send(mavlink_channel_t chan, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[42]; + _mav_put_float(buf, 0, mag_declination); + _mav_put_int32_t(buf, 4, raw_press); + _mav_put_int32_t(buf, 8, raw_temp); + _mav_put_float(buf, 12, gyro_cal_x); + _mav_put_float(buf, 16, gyro_cal_y); + _mav_put_float(buf, 20, gyro_cal_z); + _mav_put_float(buf, 24, accel_cal_x); + _mav_put_float(buf, 28, accel_cal_y); + _mav_put_float(buf, 32, accel_cal_z); + _mav_put_int16_t(buf, 36, mag_ofs_x); + _mav_put_int16_t(buf, 38, mag_ofs_y); + _mav_put_int16_t(buf, 40, mag_ofs_z); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, buf, 42, 134); +#else + mavlink_sensor_offsets_t packet; + packet.mag_declination = mag_declination; + packet.raw_press = raw_press; + packet.raw_temp = raw_temp; + packet.gyro_cal_x = gyro_cal_x; + packet.gyro_cal_y = gyro_cal_y; + packet.gyro_cal_z = gyro_cal_z; + packet.accel_cal_x = accel_cal_x; + packet.accel_cal_y = accel_cal_y; + packet.accel_cal_z = accel_cal_z; + packet.mag_ofs_x = mag_ofs_x; + packet.mag_ofs_y = mag_ofs_y; + packet.mag_ofs_z = mag_ofs_z; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)&packet, 42, 134); +#endif +} + +#endif + +// MESSAGE SENSOR_OFFSETS UNPACKING + + +/** + * @brief Get field mag_ofs_x from sensor_offsets message + * + * @return magnetometer X offset + */ +static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 36); +} + +/** + * @brief Get field mag_ofs_y from sensor_offsets message + * + * @return magnetometer Y offset + */ +static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 38); +} + +/** + * @brief Get field mag_ofs_z from sensor_offsets message + * + * @return magnetometer Z offset + */ +static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 40); +} + +/** + * @brief Get field mag_declination from sensor_offsets message + * + * @return magnetic declination (radians) + */ +static inline float mavlink_msg_sensor_offsets_get_mag_declination(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field raw_press from sensor_offsets message + * + * @return raw pressure from barometer + */ +static inline int32_t mavlink_msg_sensor_offsets_get_raw_press(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field raw_temp from sensor_offsets message + * + * @return raw temperature from barometer + */ +static inline int32_t mavlink_msg_sensor_offsets_get_raw_temp(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field gyro_cal_x from sensor_offsets message + * + * @return gyro X calibration + */ +static inline float mavlink_msg_sensor_offsets_get_gyro_cal_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field gyro_cal_y from sensor_offsets message + * + * @return gyro Y calibration + */ +static inline float mavlink_msg_sensor_offsets_get_gyro_cal_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field gyro_cal_z from sensor_offsets message + * + * @return gyro Z calibration + */ +static inline float mavlink_msg_sensor_offsets_get_gyro_cal_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field accel_cal_x from sensor_offsets message + * + * @return accel X calibration + */ +static inline float mavlink_msg_sensor_offsets_get_accel_cal_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field accel_cal_y from sensor_offsets message + * + * @return accel Y calibration + */ +static inline float mavlink_msg_sensor_offsets_get_accel_cal_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field accel_cal_z from sensor_offsets message + * + * @return accel Z calibration + */ +static inline float mavlink_msg_sensor_offsets_get_accel_cal_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Decode a sensor_offsets message into a struct + * + * @param msg The message to decode + * @param sensor_offsets C-struct to decode the message contents into + */ +static inline void mavlink_msg_sensor_offsets_decode(const mavlink_message_t* msg, mavlink_sensor_offsets_t* sensor_offsets) +{ +#if MAVLINK_NEED_BYTE_SWAP + sensor_offsets->mag_declination = mavlink_msg_sensor_offsets_get_mag_declination(msg); + sensor_offsets->raw_press = mavlink_msg_sensor_offsets_get_raw_press(msg); + sensor_offsets->raw_temp = mavlink_msg_sensor_offsets_get_raw_temp(msg); + sensor_offsets->gyro_cal_x = mavlink_msg_sensor_offsets_get_gyro_cal_x(msg); + sensor_offsets->gyro_cal_y = mavlink_msg_sensor_offsets_get_gyro_cal_y(msg); + sensor_offsets->gyro_cal_z = mavlink_msg_sensor_offsets_get_gyro_cal_z(msg); + sensor_offsets->accel_cal_x = mavlink_msg_sensor_offsets_get_accel_cal_x(msg); + sensor_offsets->accel_cal_y = mavlink_msg_sensor_offsets_get_accel_cal_y(msg); + sensor_offsets->accel_cal_z = mavlink_msg_sensor_offsets_get_accel_cal_z(msg); + sensor_offsets->mag_ofs_x = mavlink_msg_sensor_offsets_get_mag_ofs_x(msg); + sensor_offsets->mag_ofs_y = mavlink_msg_sensor_offsets_get_mag_ofs_y(msg); + sensor_offsets->mag_ofs_z = mavlink_msg_sensor_offsets_get_mag_ofs_z(msg); +#else + memcpy(sensor_offsets, _MAV_PAYLOAD(msg), 42); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h new file mode 100644 index 0000000000000000000000000000000000000000..4c13fd1863d3db61a9e625bd7a70cc53867ef4d6 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h @@ -0,0 +1,232 @@ +// MESSAGE SET_MAG_OFFSETS PACKING + +#define MAVLINK_MSG_ID_SET_MAG_OFFSETS 151 + +typedef struct __mavlink_set_mag_offsets_t +{ + int16_t mag_ofs_x; ///< magnetometer X offset + int16_t mag_ofs_y; ///< magnetometer Y offset + int16_t mag_ofs_z; ///< magnetometer Z offset + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_set_mag_offsets_t; + +#define MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN 8 +#define MAVLINK_MSG_ID_151_LEN 8 + + + +#define MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS { \ + "SET_MAG_OFFSETS", \ + 5, \ + { { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_set_mag_offsets_t, mag_ofs_x) }, \ + { "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_set_mag_offsets_t, mag_ofs_y) }, \ + { "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_set_mag_offsets_t, mag_ofs_z) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_set_mag_offsets_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_set_mag_offsets_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a set_mag_offsets 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 target_system System ID + * @param target_component Component ID + * @param mag_ofs_x magnetometer X offset + * @param mag_ofs_y magnetometer Y offset + * @param mag_ofs_z magnetometer Z offset + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[8]; + _mav_put_int16_t(buf, 0, mag_ofs_x); + _mav_put_int16_t(buf, 2, mag_ofs_y); + _mav_put_int16_t(buf, 4, mag_ofs_z); + _mav_put_uint8_t(buf, 6, target_system); + _mav_put_uint8_t(buf, 7, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); +#else + mavlink_set_mag_offsets_t packet; + packet.mag_ofs_x = mag_ofs_x; + packet.mag_ofs_y = mag_ofs_y; + packet.mag_ofs_z = mag_ofs_z; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS; + return mavlink_finalize_message(msg, system_id, component_id, 8, 219); +} + +/** + * @brief Pack a set_mag_offsets 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 target_system System ID + * @param target_component Component ID + * @param mag_ofs_x magnetometer X offset + * @param mag_ofs_y magnetometer Y offset + * @param mag_ofs_z magnetometer Z offset + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_mag_offsets_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[8]; + _mav_put_int16_t(buf, 0, mag_ofs_x); + _mav_put_int16_t(buf, 2, mag_ofs_y); + _mav_put_int16_t(buf, 4, mag_ofs_z); + _mav_put_uint8_t(buf, 6, target_system); + _mav_put_uint8_t(buf, 7, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); +#else + mavlink_set_mag_offsets_t packet; + packet.mag_ofs_x = mag_ofs_x; + packet.mag_ofs_y = mag_ofs_y; + packet.mag_ofs_z = mag_ofs_z; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8, 219); +} + +/** + * @brief Encode a set_mag_offsets 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 set_mag_offsets C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_mag_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mag_offsets_t* set_mag_offsets) +{ + return mavlink_msg_set_mag_offsets_pack(system_id, component_id, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z); +} + +/** + * @brief Send a set_mag_offsets message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param mag_ofs_x magnetometer X offset + * @param mag_ofs_y magnetometer Y offset + * @param mag_ofs_z magnetometer Z offset + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_mag_offsets_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[8]; + _mav_put_int16_t(buf, 0, mag_ofs_x); + _mav_put_int16_t(buf, 2, mag_ofs_y); + _mav_put_int16_t(buf, 4, mag_ofs_z); + _mav_put_uint8_t(buf, 6, target_system); + _mav_put_uint8_t(buf, 7, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, 8, 219); +#else + mavlink_set_mag_offsets_t packet; + packet.mag_ofs_x = mag_ofs_x; + packet.mag_ofs_y = mag_ofs_y; + packet.mag_ofs_z = mag_ofs_z; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)&packet, 8, 219); +#endif +} + +#endif + +// MESSAGE SET_MAG_OFFSETS UNPACKING + + +/** + * @brief Get field target_system from set_mag_offsets message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_mag_offsets_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field target_component from set_mag_offsets message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_mag_offsets_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field mag_ofs_x from set_mag_offsets message + * + * @return magnetometer X offset + */ +static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 0); +} + +/** + * @brief Get field mag_ofs_y from set_mag_offsets message + * + * @return magnetometer Y offset + */ +static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 2); +} + +/** + * @brief Get field mag_ofs_z from set_mag_offsets message + * + * @return magnetometer Z offset + */ +static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 4); +} + +/** + * @brief Decode a set_mag_offsets message into a struct + * + * @param msg The message to decode + * @param set_mag_offsets C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_mag_offsets_decode(const mavlink_message_t* msg, mavlink_set_mag_offsets_t* set_mag_offsets) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_mag_offsets->mag_ofs_x = mavlink_msg_set_mag_offsets_get_mag_ofs_x(msg); + set_mag_offsets->mag_ofs_y = mavlink_msg_set_mag_offsets_get_mag_ofs_y(msg); + set_mag_offsets->mag_ofs_z = mavlink_msg_set_mag_offsets_get_mag_ofs_z(msg); + set_mag_offsets->target_system = mavlink_msg_set_mag_offsets_get_target_system(msg); + set_mag_offsets->target_component = mavlink_msg_set_mag_offsets_get_target_component(msg); +#else + memcpy(set_mag_offsets, _MAV_PAYLOAD(msg), 8); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h new file mode 100644 index 0000000000000000000000000000000000000000..dfcddfc2b6c8ef8d54c411017e69f83942228654 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h @@ -0,0 +1,320 @@ +// MESSAGE SIMSTATE PACKING + +#define MAVLINK_MSG_ID_SIMSTATE 164 + +typedef struct __mavlink_simstate_t +{ + float roll; ///< Roll angle (rad) + float pitch; ///< Pitch angle (rad) + float yaw; ///< Yaw angle (rad) + float xacc; ///< X acceleration m/s/s + float yacc; ///< Y acceleration m/s/s + float zacc; ///< Z acceleration m/s/s + float xgyro; ///< Angular speed around X axis rad/s + float ygyro; ///< Angular speed around Y axis rad/s + float zgyro; ///< Angular speed around Z axis rad/s +} mavlink_simstate_t; + +#define MAVLINK_MSG_ID_SIMSTATE_LEN 36 +#define MAVLINK_MSG_ID_164_LEN 36 + + + +#define MAVLINK_MESSAGE_INFO_SIMSTATE { \ + "SIMSTATE", \ + 9, \ + { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_simstate_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_simstate_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_simstate_t, yaw) }, \ + { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_simstate_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_simstate_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_simstate_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_simstate_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_simstate_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_simstate_t, zgyro) }, \ + } \ +} + + +/** + * @brief Pack a simstate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param xacc X acceleration m/s/s + * @param yacc Y acceleration m/s/s + * @param zacc Z acceleration m/s/s + * @param xgyro Angular speed around X axis rad/s + * @param ygyro Angular speed around Y axis rad/s + * @param zgyro Angular speed around Z axis rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, xacc); + _mav_put_float(buf, 16, yacc); + _mav_put_float(buf, 20, zacc); + _mav_put_float(buf, 24, xgyro); + _mav_put_float(buf, 28, ygyro); + _mav_put_float(buf, 32, zgyro); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); +#else + mavlink_simstate_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); +#endif + + msg->msgid = MAVLINK_MSG_ID_SIMSTATE; + return mavlink_finalize_message(msg, system_id, component_id, 36, 42); +} + +/** + * @brief Pack a simstate 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 roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param xacc X acceleration m/s/s + * @param yacc Y acceleration m/s/s + * @param zacc Z acceleration m/s/s + * @param xgyro Angular speed around X axis rad/s + * @param ygyro Angular speed around Y axis rad/s + * @param zgyro Angular speed around Z axis rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, xacc); + _mav_put_float(buf, 16, yacc); + _mav_put_float(buf, 20, zacc); + _mav_put_float(buf, 24, xgyro); + _mav_put_float(buf, 28, ygyro); + _mav_put_float(buf, 32, zgyro); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); +#else + mavlink_simstate_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); +#endif + + msg->msgid = MAVLINK_MSG_ID_SIMSTATE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36, 42); +} + +/** + * @brief Encode a simstate 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 simstate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_simstate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_simstate_t* simstate) +{ + return mavlink_msg_simstate_pack(system_id, component_id, msg, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro); +} + +/** + * @brief Send a simstate message + * @param chan MAVLink channel to send the message + * + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param xacc X acceleration m/s/s + * @param yacc Y acceleration m/s/s + * @param zacc Z acceleration m/s/s + * @param xgyro Angular speed around X axis rad/s + * @param ygyro Angular speed around Y axis rad/s + * @param zgyro Angular speed around Z axis rad/s + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, xacc); + _mav_put_float(buf, 16, yacc); + _mav_put_float(buf, 20, zacc); + _mav_put_float(buf, 24, xgyro); + _mav_put_float(buf, 28, ygyro); + _mav_put_float(buf, 32, zgyro); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, 36, 42); +#else + mavlink_simstate_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)&packet, 36, 42); +#endif +} + +#endif + +// MESSAGE SIMSTATE UNPACKING + + +/** + * @brief Get field roll from simstate message + * + * @return Roll angle (rad) + */ +static inline float mavlink_msg_simstate_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field pitch from simstate message + * + * @return Pitch angle (rad) + */ +static inline float mavlink_msg_simstate_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field yaw from simstate message + * + * @return Yaw angle (rad) + */ +static inline float mavlink_msg_simstate_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field xacc from simstate message + * + * @return X acceleration m/s/s + */ +static inline float mavlink_msg_simstate_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field yacc from simstate message + * + * @return Y acceleration m/s/s + */ +static inline float mavlink_msg_simstate_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field zacc from simstate message + * + * @return Z acceleration m/s/s + */ +static inline float mavlink_msg_simstate_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field xgyro from simstate message + * + * @return Angular speed around X axis rad/s + */ +static inline float mavlink_msg_simstate_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field ygyro from simstate message + * + * @return Angular speed around Y axis rad/s + */ +static inline float mavlink_msg_simstate_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field zgyro from simstate message + * + * @return Angular speed around Z axis rad/s + */ +static inline float mavlink_msg_simstate_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Decode a simstate message into a struct + * + * @param msg The message to decode + * @param simstate C-struct to decode the message contents into + */ +static inline void mavlink_msg_simstate_decode(const mavlink_message_t* msg, mavlink_simstate_t* simstate) +{ +#if MAVLINK_NEED_BYTE_SWAP + simstate->roll = mavlink_msg_simstate_get_roll(msg); + simstate->pitch = mavlink_msg_simstate_get_pitch(msg); + simstate->yaw = mavlink_msg_simstate_get_yaw(msg); + simstate->xacc = mavlink_msg_simstate_get_xacc(msg); + simstate->yacc = mavlink_msg_simstate_get_yacc(msg); + simstate->zacc = mavlink_msg_simstate_get_zacc(msg); + simstate->xgyro = mavlink_msg_simstate_get_xgyro(msg); + simstate->ygyro = mavlink_msg_simstate_get_ygyro(msg); + simstate->zgyro = mavlink_msg_simstate_get_zgyro(msg); +#else + memcpy(simstate, _MAV_PAYLOAD(msg), 36); +#endif +} diff --git a/mavlink/include/v0.9/ardupilotmega/testsuite.h b/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h similarity index 94% rename from mavlink/include/v0.9/ardupilotmega/testsuite.h rename to mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h index 948fec18e992880b247059f72215f47cc3bce32f..5ef38f3732429574e6a52a66669b0e282b41e06f 100644 --- a/mavlink/include/v0.9/ardupilotmega/testsuite.h +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h @@ -30,24 +30,21 @@ static void mavlink_test_sensor_offsets(uint8_t system_id, uint8_t component_id, uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint16_t i; mavlink_sensor_offsets_t packet_in = { - 17235, - 17339, - 17443, - 59.0, - 963497984, - 963498192, - 143.0, - 171.0, - 199.0, - 227.0, - 255.0, - 283.0, + 17.0, + 963497672, + 963497880, + 101.0, + 129.0, + 157.0, + 185.0, + 213.0, + 241.0, + 19107, + 19211, + 19315, }; mavlink_sensor_offsets_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); - packet1.mag_ofs_x = packet_in.mag_ofs_x; - packet1.mag_ofs_y = packet_in.mag_ofs_y; - packet1.mag_ofs_z = packet_in.mag_ofs_z; packet1.mag_declination = packet_in.mag_declination; packet1.raw_press = packet_in.raw_press; packet1.raw_temp = packet_in.raw_temp; @@ -57,6 +54,9 @@ static void mavlink_test_sensor_offsets(uint8_t system_id, uint8_t component_id, packet1.accel_cal_x = packet_in.accel_cal_x; packet1.accel_cal_y = packet_in.accel_cal_y; packet1.accel_cal_z = packet_in.accel_cal_z; + packet1.mag_ofs_x = packet_in.mag_ofs_x; + packet1.mag_ofs_y = packet_in.mag_ofs_y; + packet1.mag_ofs_z = packet_in.mag_ofs_z; @@ -95,19 +95,19 @@ static void mavlink_test_set_mag_offsets(uint8_t system_id, uint8_t component_id uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint16_t i; mavlink_set_mag_offsets_t packet_in = { - 5, - 72, + 17235, 17339, 17443, - 17547, + 151, + 218, }; mavlink_set_mag_offsets_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; packet1.mag_ofs_x = packet_in.mag_ofs_x; packet1.mag_ofs_y = packet_in.mag_ofs_y; packet1.mag_ofs_z = packet_in.mag_ofs_z; + packet1.target_system = packet_in.target_system; + packet1.target_component = packet_in.target_component; @@ -244,31 +244,31 @@ static void mavlink_test_digicam_configure(uint8_t system_id, uint8_t component_ uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint16_t i; mavlink_digicam_configure_t packet_in = { - 5, - 72, - 139, - 17391, - 84, + 17.0, + 17443, 151, 218, 29, 96, 163, - 94.0, + 230, + 41, + 108, + 175, }; mavlink_digicam_configure_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); + packet1.extra_value = packet_in.extra_value; + packet1.shutter_speed = packet_in.shutter_speed; packet1.target_system = packet_in.target_system; packet1.target_component = packet_in.target_component; packet1.mode = packet_in.mode; - packet1.shutter_speed = packet_in.shutter_speed; packet1.aperture = packet_in.aperture; packet1.iso = packet_in.iso; packet1.exposure_type = packet_in.exposure_type; packet1.command_id = packet_in.command_id; packet1.engine_cut_off = packet_in.engine_cut_off; packet1.extra_param = packet_in.extra_param; - packet1.extra_value = packet_in.extra_value; @@ -307,19 +307,20 @@ static void mavlink_test_digicam_control(uint8_t system_id, uint8_t component_id uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint16_t i; mavlink_digicam_control_t packet_in = { - 5, - 72, - 139, - 206, + 17.0, 17, 84, 151, 218, 29, - 80.0, + 96, + 163, + 230, + 41, }; mavlink_digicam_control_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); + packet1.extra_value = packet_in.extra_value; packet1.target_system = packet_in.target_system; packet1.target_component = packet_in.target_component; packet1.session = packet_in.session; @@ -329,7 +330,6 @@ static void mavlink_test_digicam_control(uint8_t system_id, uint8_t component_id packet1.shot = packet_in.shot; packet1.command_id = packet_in.command_id; packet1.extra_param = packet_in.extra_param; - packet1.extra_value = packet_in.extra_value; @@ -421,20 +421,20 @@ static void mavlink_test_mount_control(uint8_t system_id, uint8_t component_id, uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint16_t i; mavlink_mount_control_t packet_in = { - 5, - 72, - 963497568, - 963497776, - 963497984, + 963497464, + 963497672, + 963497880, + 41, + 108, 175, }; mavlink_mount_control_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; packet1.input_a = packet_in.input_a; packet1.input_b = packet_in.input_b; packet1.input_c = packet_in.input_c; + packet1.target_system = packet_in.target_system; + packet1.target_component = packet_in.target_component; packet1.save_position = packet_in.save_position; @@ -474,19 +474,19 @@ static void mavlink_test_mount_status(uint8_t system_id, uint8_t component_id, m uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint16_t i; mavlink_mount_status_t packet_in = { - 5, - 72, - 963497568, - 963497776, - 963497984, + 963497464, + 963497672, + 963497880, + 41, + 108, }; mavlink_mount_status_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; packet1.pointing_a = packet_in.pointing_a; packet1.pointing_b = packet_in.pointing_b; packet1.pointing_c = packet_in.pointing_c; + packet1.target_system = packet_in.target_system; + packet1.target_component = packet_in.target_component; @@ -525,21 +525,21 @@ static void mavlink_test_fence_point(uint8_t system_id, uint8_t component_id, ma uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint16_t i; mavlink_fence_point_t packet_in = { - 5, - 72, - 139, - 206, + 17.0, 45.0, - 73.0, + 29, + 96, + 163, + 230, }; mavlink_fence_point_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); + packet1.lat = packet_in.lat; + packet1.lng = packet_in.lng; packet1.target_system = packet_in.target_system; packet1.target_component = packet_in.target_component; packet1.idx = packet_in.idx; packet1.count = packet_in.count; - packet1.lat = packet_in.lat; - packet1.lng = packet_in.lng; @@ -625,17 +625,17 @@ static void mavlink_test_fence_status(uint8_t system_id, uint8_t component_id, m uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint16_t i; mavlink_fence_status_t packet_in = { - 5, - 17287, - 206, - 963497672, + 963497464, + 17443, + 151, + 218, }; mavlink_fence_status_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); - packet1.breach_status = packet_in.breach_status; + packet1.breach_time = packet_in.breach_time; packet1.breach_count = packet_in.breach_count; + packet1.breach_status = packet_in.breach_status; packet1.breach_type = packet_in.breach_type; - packet1.breach_time = packet_in.breach_time; @@ -782,51 +782,6 @@ static void mavlink_test_simstate(uint8_t system_id, uint8_t component_id, mavli MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } -static void mavlink_test_hwstatus(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_hwstatus_t packet_in = { - 17235, - 139, - }; - mavlink_hwstatus_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.Vcc = packet_in.Vcc; - packet1.I2Cerr = packet_in.I2Cerr; - - - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hwstatus_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hwstatus_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hwstatus_pack(system_id, component_id, &msg , packet1.Vcc , packet1.I2Cerr ); - mavlink_msg_hwstatus_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hwstatus_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.Vcc , packet1.I2Cerr ); - mavlink_msg_hwstatus_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 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ + MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ + MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ + MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ + MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */ + MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ + MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ + MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ + MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ + MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ + MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ + MAV_CMD_ENUM_END=401, /* | */ +}; +#endif + +/** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a + recommendation to the autopilot software. Individual autopilots may or may not obey + the recommended messages. */ +#ifndef HAVE_ENUM_MAV_DATA_STREAM +#define HAVE_ENUM_MAV_DATA_STREAM +enum MAV_DATA_STREAM +{ + MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */ + MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */ + MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */ + MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */ + MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */ + MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | */ + MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */ + MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */ + MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */ + MAV_DATA_STREAM_ENUM_END=13, /* | */ +}; +#endif + +/** @brief The ROI (region of interest) for the vehicle. This can be + be used by the vehicle for camera/vehicle attitude alignment (see + MAV_CMD_NAV_ROI). */ +#ifndef HAVE_ENUM_MAV_ROI +#define HAVE_ENUM_MAV_ROI +enum MAV_ROI +{ + MAV_ROI_NONE=0, /* No region of interest. | */ + MAV_ROI_WPNEXT=1, /* Point toward next MISSION. | */ + MAV_ROI_WPINDEX=2, /* Point toward given MISSION. | */ + MAV_ROI_LOCATION=3, /* Point toward fixed location. | */ + MAV_ROI_TARGET=4, /* Point toward of given id. | */ + MAV_ROI_ENUM_END=5, /* | */ +}; +#endif + +/** @brief ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. */ +#ifndef HAVE_ENUM_MAV_CMD_ACK +#define HAVE_ENUM_MAV_CMD_ACK +enum MAV_CMD_ACK +{ + MAV_CMD_ACK_OK=1, /* Command / mission item is ok. | */ + MAV_CMD_ACK_ERR_FAIL=2, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | */ + MAV_CMD_ACK_ERR_ACCESS_DENIED=3, /* The system is refusing to accept this command from this source / communication partner. | */ + MAV_CMD_ACK_ERR_NOT_SUPPORTED=4, /* Command or mission item is not supported, other commands would be accepted. | */ + MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED=5, /* The coordinate frame of this command / mission item is not supported. | */ + MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE=6, /* The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. | */ + MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE=7, /* The X or latitude value is out of range. | */ + MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE=8, /* The Y or longitude value is out of range. | */ + MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE=9, /* The Z or altitude value is out of range. | */ + MAV_CMD_ACK_ENUM_END=10, /* | */ +}; +#endif + +/** @brief type of a mavlink parameter */ +#ifndef HAVE_ENUM_MAV_VAR +#define HAVE_ENUM_MAV_VAR +enum MAV_VAR +{ + MAV_VAR_FLOAT=0, /* 32 bit float | */ + MAV_VAR_UINT8=1, /* 8 bit unsigned integer | */ + MAV_VAR_INT8=2, /* 8 bit signed integer | */ + MAV_VAR_UINT16=3, /* 16 bit unsigned integer | */ + MAV_VAR_INT16=4, /* 16 bit signed integer | */ + MAV_VAR_UINT32=5, /* 32 bit unsigned integer | */ + MAV_VAR_INT32=6, /* 32 bit signed integer | */ + MAV_VAR_ENUM_END=7, /* | */ +}; +#endif + +/** @brief result from a mavlink command */ +#ifndef HAVE_ENUM_MAV_RESULT +#define HAVE_ENUM_MAV_RESULT +enum MAV_RESULT +{ + MAV_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */ + MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */ + MAV_RESULT_DENIED=2, /* Command PERMANENTLY DENIED | */ + MAV_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */ + MAV_RESULT_FAILED=4, /* Command executed, but failed | */ + MAV_RESULT_ENUM_END=5, /* | */ +}; +#endif + +/** @brief result in a mavlink mission ack */ +#ifndef HAVE_ENUM_MAV_MISSION_RESULT +#define HAVE_ENUM_MAV_MISSION_RESULT +enum MAV_MISSION_RESULT +{ + MAV_MISSION_ACCEPTED=0, /* mission accepted OK | */ + MAV_MISSION_ERROR=1, /* generic error / not accepting mission commands at all right now | */ + MAV_MISSION_UNSUPPORTED_FRAME=2, /* coordinate frame is not supported | */ + MAV_MISSION_UNSUPPORTED=3, /* command is not supported | */ + MAV_MISSION_NO_SPACE=4, /* mission item exceeds storage space | */ + MAV_MISSION_INVALID=5, /* one of the parameters has an invalid value | */ + MAV_MISSION_INVALID_PARAM1=6, /* param1 has an invalid value | */ + MAV_MISSION_INVALID_PARAM2=7, /* param2 has an invalid value | */ + MAV_MISSION_INVALID_PARAM3=8, /* param3 has an invalid value | */ + MAV_MISSION_INVALID_PARAM4=9, /* param4 has an invalid value | */ + MAV_MISSION_INVALID_PARAM5_X=10, /* x/param5 has an invalid value | */ + MAV_MISSION_INVALID_PARAM6_Y=11, /* y/param6 has an invalid value | */ + MAV_MISSION_INVALID_PARAM7=12, /* param7 has an invalid value | */ + MAV_MISSION_INVALID_SEQUENCE=13, /* received waypoint out of sequence | */ + MAV_MISSION_DENIED=14, /* not accepting any mission commands from this communication partner | */ + MAV_MISSION_RESULT_ENUM_END=15, /* | */ +}; +#endif + +/** @brief Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. */ +#ifndef HAVE_ENUM_MAV_SEVERITY +#define HAVE_ENUM_MAV_SEVERITY +enum MAV_SEVERITY +{ + MAV_SEVERITY_EMERGENCY=0, /* System is unusable. This is a "panic" condition. | */ + MAV_SEVERITY_ALERT=1, /* Action should be taken immediately. Indicates error in non-critical systems. | */ + MAV_SEVERITY_CRITICAL=2, /* Action must be taken immediately. Indicates failure in a primary system. | */ + MAV_SEVERITY_ERROR=3, /* Indicates an error in secondary/redundant systems. | */ + MAV_SEVERITY_WARNING=4, /* Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. | */ + MAV_SEVERITY_NOTICE=5, /* An unusual event has occured, though not an error condition. This should be investigated for the root cause. | */ + MAV_SEVERITY_INFO=6, /* Normal operational messages. Useful for logging. No action is required for these messages. | */ + MAV_SEVERITY_DEBUG=7, /* Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | */ + MAV_SEVERITY_ENUM_END=8, /* | */ +}; +#endif + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_heartbeat.h" +#include "./mavlink_msg_sys_status.h" +#include "./mavlink_msg_system_time.h" +#include "./mavlink_msg_ping.h" +#include "./mavlink_msg_change_operator_control.h" +#include "./mavlink_msg_change_operator_control_ack.h" +#include "./mavlink_msg_auth_key.h" +#include "./mavlink_msg_set_mode.h" +#include "./mavlink_msg_param_request_read.h" +#include "./mavlink_msg_param_request_list.h" +#include "./mavlink_msg_param_value.h" +#include "./mavlink_msg_param_set.h" +#include "./mavlink_msg_gps_raw_int.h" +#include "./mavlink_msg_gps_status.h" +#include "./mavlink_msg_scaled_imu.h" +#include "./mavlink_msg_raw_imu.h" +#include "./mavlink_msg_raw_pressure.h" +#include "./mavlink_msg_scaled_pressure.h" +#include "./mavlink_msg_attitude.h" +#include "./mavlink_msg_attitude_quaternion.h" +#include "./mavlink_msg_local_position_ned.h" +#include "./mavlink_msg_global_position_int.h" +#include "./mavlink_msg_rc_channels_scaled.h" +#include "./mavlink_msg_rc_channels_raw.h" +#include "./mavlink_msg_servo_output_raw.h" +#include "./mavlink_msg_mission_request_partial_list.h" +#include "./mavlink_msg_mission_write_partial_list.h" +#include "./mavlink_msg_mission_item.h" +#include "./mavlink_msg_mission_request.h" +#include "./mavlink_msg_mission_set_current.h" +#include "./mavlink_msg_mission_current.h" +#include "./mavlink_msg_mission_request_list.h" +#include "./mavlink_msg_mission_count.h" +#include "./mavlink_msg_mission_clear_all.h" +#include "./mavlink_msg_mission_item_reached.h" +#include "./mavlink_msg_mission_ack.h" +#include "./mavlink_msg_set_gps_global_origin.h" +#include "./mavlink_msg_gps_global_origin.h" +#include "./mavlink_msg_set_local_position_setpoint.h" +#include "./mavlink_msg_local_position_setpoint.h" +#include "./mavlink_msg_global_position_setpoint_int.h" +#include "./mavlink_msg_set_global_position_setpoint_int.h" +#include "./mavlink_msg_safety_set_allowed_area.h" +#include "./mavlink_msg_safety_allowed_area.h" +#include "./mavlink_msg_set_roll_pitch_yaw_thrust.h" +#include "./mavlink_msg_set_roll_pitch_yaw_speed_thrust.h" +#include "./mavlink_msg_roll_pitch_yaw_thrust_setpoint.h" +#include "./mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h" +#include "./mavlink_msg_set_quad_motors_setpoint.h" +#include "./mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h" +#include "./mavlink_msg_nav_controller_output.h" +#include "./mavlink_msg_state_correction.h" +#include "./mavlink_msg_request_data_stream.h" +#include "./mavlink_msg_data_stream.h" +#include "./mavlink_msg_manual_control.h" +#include "./mavlink_msg_rc_channels_override.h" +#include "./mavlink_msg_vfr_hud.h" +#include "./mavlink_msg_command_long.h" +#include "./mavlink_msg_command_ack.h" +#include "./mavlink_msg_local_position_ned_system_global_offset.h" +#include "./mavlink_msg_hil_state.h" +#include "./mavlink_msg_hil_controls.h" +#include "./mavlink_msg_hil_rc_inputs_raw.h" +#include "./mavlink_msg_optical_flow.h" +#include "./mavlink_msg_global_vision_position_estimate.h" +#include "./mavlink_msg_vision_position_estimate.h" +#include "./mavlink_msg_vision_speed_estimate.h" +#include "./mavlink_msg_vicon_position_estimate.h" +#include "./mavlink_msg_memory_vect.h" +#include "./mavlink_msg_debug_vect.h" +#include "./mavlink_msg_named_value_float.h" +#include "./mavlink_msg_named_value_int.h" +#include "./mavlink_msg_statustext.h" +#include "./mavlink_msg_debug.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // COMMON_H diff --git a/mavlink/include/mavlink/v1.0/common/mavlink.h b/mavlink/include/mavlink/v1.0/common/mavlink.h new file mode 100644 index 0000000000000000000000000000000000000000..17b7329709156ab2cc4aa1924a8b35d9fc4b26bf --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink.h @@ -0,0 +1,27 @@ +/** @file + * @brief MAVLink comm protocol built from common.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 "common.h" + +#endif // MAVLINK_H diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h new file mode 100644 index 0000000000000000000000000000000000000000..9074a1d80fec2502ea7155e082c8adf3091bb102 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h @@ -0,0 +1,276 @@ +// MESSAGE ATTITUDE PACKING + +#define MAVLINK_MSG_ID_ATTITUDE 30 + +typedef struct __mavlink_attitude_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + float roll; ///< Roll angle (rad) + float pitch; ///< Pitch angle (rad) + float yaw; ///< Yaw angle (rad) + float rollspeed; ///< Roll angular speed (rad/s) + float pitchspeed; ///< Pitch angular speed (rad/s) + float yawspeed; ///< Yaw angular speed (rad/s) +} mavlink_attitude_t; + +#define MAVLINK_MSG_ID_ATTITUDE_LEN 28 +#define MAVLINK_MSG_ID_30_LEN 28 + + + +#define MAVLINK_MESSAGE_INFO_ATTITUDE { \ + "ATTITUDE", \ + 7, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \ + { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \ + { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \ + { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \ + } \ +} + + +/** + * @brief Pack a attitude message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, rollspeed); + _mav_put_float(buf, 20, pitchspeed); + _mav_put_float(buf, 24, yawspeed); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); +#else + mavlink_attitude_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE; + return mavlink_finalize_message(msg, system_id, component_id, 28, 39); +} + +/** + * @brief Pack a attitude message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, rollspeed); + _mav_put_float(buf, 20, pitchspeed); + _mav_put_float(buf, 24, yawspeed); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); +#else + mavlink_attitude_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 39); +} + +/** + * @brief Encode a attitude 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 attitude C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_t* attitude) +{ + return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); +} + +/** + * @brief Send a attitude message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, rollspeed); + _mav_put_float(buf, 20, pitchspeed); + _mav_put_float(buf, 24, yawspeed); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, 28, 39); +#else + mavlink_attitude_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, 28, 39); +#endif +} + +#endif + +// MESSAGE ATTITUDE UNPACKING + + +/** + * @brief Get field time_boot_ms from attitude message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field roll from attitude message + * + * @return Roll angle (rad) + */ +static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field pitch from attitude message + * + * @return Pitch angle (rad) + */ +static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw from attitude message + * + * @return Yaw angle (rad) + */ +static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field rollspeed from attitude message + * + * @return Roll angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field pitchspeed from attitude message + * + * @return Pitch angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field yawspeed from attitude message + * + * @return Yaw angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a attitude message into a struct + * + * @param msg The message to decode + * @param attitude C-struct to decode the message contents into + */ +static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude) +{ +#if MAVLINK_NEED_BYTE_SWAP + attitude->time_boot_ms = mavlink_msg_attitude_get_time_boot_ms(msg); + attitude->roll = mavlink_msg_attitude_get_roll(msg); + attitude->pitch = mavlink_msg_attitude_get_pitch(msg); + attitude->yaw = mavlink_msg_attitude_get_yaw(msg); + attitude->rollspeed = mavlink_msg_attitude_get_rollspeed(msg); + attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg); + attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg); +#else + memcpy(attitude, _MAV_PAYLOAD(msg), 28); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h new file mode 100644 index 0000000000000000000000000000000000000000..556048865510de531bcac997826e7a033d5f77f2 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h @@ -0,0 +1,298 @@ +// MESSAGE ATTITUDE_QUATERNION PACKING + +#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31 + +typedef struct __mavlink_attitude_quaternion_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + float q1; ///< Quaternion component 1 + float q2; ///< Quaternion component 2 + float q3; ///< Quaternion component 3 + float q4; ///< Quaternion component 4 + float rollspeed; ///< Roll angular speed (rad/s) + float pitchspeed; ///< Pitch angular speed (rad/s) + float yawspeed; ///< Yaw angular speed (rad/s) +} mavlink_attitude_quaternion_t; + +#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32 +#define MAVLINK_MSG_ID_31_LEN 32 + + + +#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \ + "ATTITUDE_QUATERNION", \ + 8, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \ + { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \ + { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \ + { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \ + { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \ + { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \ + { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \ + { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \ + } \ +} + + +/** + * @brief Pack a attitude_quaternion message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param q1 Quaternion component 1 + * @param q2 Quaternion component 2 + * @param q3 Quaternion component 3 + * @param q4 Quaternion component 4 + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, q1); + _mav_put_float(buf, 8, q2); + _mav_put_float(buf, 12, q3); + _mav_put_float(buf, 16, q4); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); +#else + mavlink_attitude_quaternion_t packet; + packet.time_boot_ms = time_boot_ms; + packet.q1 = q1; + packet.q2 = q2; + packet.q3 = q3; + packet.q4 = q4; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION; + return mavlink_finalize_message(msg, system_id, component_id, 32, 246); +} + +/** + * @brief Pack a attitude_quaternion message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param q1 Quaternion component 1 + * @param q2 Quaternion component 2 + * @param q3 Quaternion component 3 + * @param q4 Quaternion component 4 + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float q1,float q2,float q3,float q4,float rollspeed,float pitchspeed,float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, q1); + _mav_put_float(buf, 8, q2); + _mav_put_float(buf, 12, q3); + _mav_put_float(buf, 16, q4); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); +#else + mavlink_attitude_quaternion_t packet; + packet.time_boot_ms = time_boot_ms; + packet.q1 = q1; + packet.q2 = q2; + packet.q3 = q3; + packet.q4 = q4; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 246); +} + +/** + * @brief Encode a attitude_quaternion 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 attitude_quaternion C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion) +{ + return mavlink_msg_attitude_quaternion_pack(system_id, component_id, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed); +} + +/** + * @brief Send a attitude_quaternion message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param q1 Quaternion component 1 + * @param q2 Quaternion component 2 + * @param q3 Quaternion component 3 + * @param q4 Quaternion component 4 + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, q1); + _mav_put_float(buf, 8, q2); + _mav_put_float(buf, 12, q3); + _mav_put_float(buf, 16, q4); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, 32, 246); +#else + mavlink_attitude_quaternion_t packet; + packet.time_boot_ms = time_boot_ms; + packet.q1 = q1; + packet.q2 = q2; + packet.q3 = q3; + packet.q4 = q4; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, 32, 246); +#endif +} + +#endif + +// MESSAGE ATTITUDE_QUATERNION UNPACKING + + +/** + * @brief Get field time_boot_ms from attitude_quaternion message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field q1 from attitude_quaternion message + * + * @return Quaternion component 1 + */ +static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field q2 from attitude_quaternion message + * + * @return Quaternion component 2 + */ +static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field q3 from attitude_quaternion message + * + * @return Quaternion component 3 + */ +static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field q4 from attitude_quaternion message + * + * @return Quaternion component 4 + */ +static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field rollspeed from attitude_quaternion message + * + * @return Roll angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitchspeed from attitude_quaternion message + * + * @return Pitch angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yawspeed from attitude_quaternion message + * + * @return Yaw angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a attitude_quaternion message into a struct + * + * @param msg The message to decode + * @param attitude_quaternion C-struct to decode the message contents into + */ +static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_t* attitude_quaternion) +{ +#if MAVLINK_NEED_BYTE_SWAP + attitude_quaternion->time_boot_ms = mavlink_msg_attitude_quaternion_get_time_boot_ms(msg); + attitude_quaternion->q1 = mavlink_msg_attitude_quaternion_get_q1(msg); + attitude_quaternion->q2 = mavlink_msg_attitude_quaternion_get_q2(msg); + attitude_quaternion->q3 = mavlink_msg_attitude_quaternion_get_q3(msg); + attitude_quaternion->q4 = mavlink_msg_attitude_quaternion_get_q4(msg); + attitude_quaternion->rollspeed = mavlink_msg_attitude_quaternion_get_rollspeed(msg); + attitude_quaternion->pitchspeed = mavlink_msg_attitude_quaternion_get_pitchspeed(msg); + attitude_quaternion->yawspeed = mavlink_msg_attitude_quaternion_get_yawspeed(msg); +#else + memcpy(attitude_quaternion, _MAV_PAYLOAD(msg), 32); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h new file mode 100644 index 0000000000000000000000000000000000000000..baa119fde1a17f020e2955eebf65dfcc5ab97ba9 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h @@ -0,0 +1,144 @@ +// MESSAGE AUTH_KEY PACKING + +#define MAVLINK_MSG_ID_AUTH_KEY 7 + +typedef struct __mavlink_auth_key_t +{ + char key[32]; ///< key +} mavlink_auth_key_t; + +#define MAVLINK_MSG_ID_AUTH_KEY_LEN 32 +#define MAVLINK_MSG_ID_7_LEN 32 + +#define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32 + +#define MAVLINK_MESSAGE_INFO_AUTH_KEY { \ + "AUTH_KEY", \ + 1, \ + { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \ + } \ +} + + +/** + * @brief Pack a auth_key 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 key key + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const char *key) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + + _mav_put_char_array(buf, 0, key, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); +#else + mavlink_auth_key_t packet; + + mav_array_memcpy(packet.key, key, sizeof(char)*32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; + return mavlink_finalize_message(msg, system_id, component_id, 32, 119); +} + +/** + * @brief Pack a auth_key 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 key key + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const char *key) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + + _mav_put_char_array(buf, 0, key, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); +#else + mavlink_auth_key_t packet; + + mav_array_memcpy(packet.key, key, sizeof(char)*32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 119); +} + +/** + * @brief Encode a auth_key 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 auth_key C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key) +{ + return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key); +} + +/** + * @brief Send a auth_key message + * @param chan MAVLink channel to send the message + * + * @param key key + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char *key) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + + _mav_put_char_array(buf, 0, key, 32); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, 32, 119); +#else + mavlink_auth_key_t packet; + + mav_array_memcpy(packet.key, key, sizeof(char)*32); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, 32, 119); +#endif +} + +#endif + +// MESSAGE AUTH_KEY UNPACKING + + +/** + * @brief Get field key from auth_key message + * + * @return key + */ +static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char *key) +{ + return _MAV_RETURN_char_array(msg, key, 32, 0); +} + +/** + * @brief Decode a auth_key message into a struct + * + * @param msg The message to decode + * @param auth_key C-struct to decode the message contents into + */ +static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mavlink_auth_key_t* auth_key) +{ +#if MAVLINK_NEED_BYTE_SWAP + mavlink_msg_auth_key_get_key(msg, auth_key->key); +#else + memcpy(auth_key, _MAV_PAYLOAD(msg), 32); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h new file mode 100644 index 0000000000000000000000000000000000000000..a558510084590c26fd6bbd3848686aff36fa44c2 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h @@ -0,0 +1,204 @@ +// MESSAGE CHANGE_OPERATOR_CONTROL PACKING + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5 + +typedef struct __mavlink_change_operator_control_t +{ + uint8_t target_system; ///< System the GCS requests control for + uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV + uint8_t version; ///< 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + char passkey[25]; ///< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" +} mavlink_change_operator_control_t; + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28 +#define MAVLINK_MSG_ID_5_LEN 28 + +#define MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_PASSKEY_LEN 25 + +#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \ + "CHANGE_OPERATOR_CONTROL", \ + 4, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_t, target_system) }, \ + { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_t, control_request) }, \ + { "version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_t, version) }, \ + { "passkey", NULL, MAVLINK_TYPE_CHAR, 25, 3, offsetof(mavlink_change_operator_control_t, passkey) }, \ + } \ +} + + +/** + * @brief Pack a change_operator_control 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 target_system System the GCS requests control for + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, version); + _mav_put_char_array(buf, 3, passkey, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); +#else + mavlink_change_operator_control_t packet; + packet.target_system = target_system; + packet.control_request = control_request; + packet.version = version; + mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; + return mavlink_finalize_message(msg, system_id, component_id, 28, 217); +} + +/** + * @brief Pack a change_operator_control 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 target_system System the GCS requests control for + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t control_request,uint8_t version,const char *passkey) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, version); + _mav_put_char_array(buf, 3, passkey, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); +#else + mavlink_change_operator_control_t packet; + packet.target_system = target_system; + packet.control_request = control_request; + packet.version = version; + mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 217); +} + +/** + * @brief Encode a change_operator_control 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 change_operator_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control) +{ + return mavlink_msg_change_operator_control_pack(system_id, component_id, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey); +} + +/** + * @brief Send a change_operator_control message + * @param chan MAVLink channel to send the message + * + * @param target_system System the GCS requests control for + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, version); + _mav_put_char_array(buf, 3, passkey, 25); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, 28, 217); +#else + mavlink_change_operator_control_t packet; + packet.target_system = target_system; + packet.control_request = control_request; + packet.version = version; + mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, 28, 217); +#endif +} + +#endif + +// MESSAGE CHANGE_OPERATOR_CONTROL UNPACKING + + +/** + * @brief Get field target_system from change_operator_control message + * + * @return System the GCS requests control for + */ +static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field control_request from change_operator_control message + * + * @return 0: request control of this MAV, 1: Release control of this MAV + */ +static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field version from change_operator_control message + * + * @return 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + */ +static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field passkey from change_operator_control message + * + * @return Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + */ +static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char *passkey) +{ + return _MAV_RETURN_char_array(msg, passkey, 25, 3); +} + +/** + * @brief Decode a change_operator_control message into a struct + * + * @param msg The message to decode + * @param change_operator_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_change_operator_control_decode(const mavlink_message_t* msg, mavlink_change_operator_control_t* change_operator_control) +{ +#if MAVLINK_NEED_BYTE_SWAP + change_operator_control->target_system = mavlink_msg_change_operator_control_get_target_system(msg); + change_operator_control->control_request = mavlink_msg_change_operator_control_get_control_request(msg); + change_operator_control->version = mavlink_msg_change_operator_control_get_version(msg); + mavlink_msg_change_operator_control_get_passkey(msg, change_operator_control->passkey); +#else + memcpy(change_operator_control, _MAV_PAYLOAD(msg), 28); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h new file mode 100644 index 0000000000000000000000000000000000000000..1d89a0f787536d049c6fc19e827a34928965878b --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h @@ -0,0 +1,188 @@ +// MESSAGE CHANGE_OPERATOR_CONTROL_ACK PACKING + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6 + +typedef struct __mavlink_change_operator_control_ack_t +{ + uint8_t gcs_system_id; ///< ID of the GCS this message + uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV + uint8_t ack; ///< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control +} mavlink_change_operator_control_ack_t; + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN 3 +#define MAVLINK_MSG_ID_6_LEN 3 + + + +#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK { \ + "CHANGE_OPERATOR_CONTROL_ACK", \ + 3, \ + { { "gcs_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_ack_t, gcs_system_id) }, \ + { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_ack_t, control_request) }, \ + { "ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_ack_t, ack) }, \ + } \ +} + + +/** + * @brief Pack a change_operator_control_ack 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 gcs_system_id ID of the GCS this message + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, gcs_system_id); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, ack); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); +#else + mavlink_change_operator_control_ack_t packet; + packet.gcs_system_id = gcs_system_id; + packet.control_request = control_request; + packet.ack = ack; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; + return mavlink_finalize_message(msg, system_id, component_id, 3, 104); +} + +/** + * @brief Pack a change_operator_control_ack 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 gcs_system_id ID of the GCS this message + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t gcs_system_id,uint8_t control_request,uint8_t ack) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, gcs_system_id); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, ack); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); +#else + mavlink_change_operator_control_ack_t packet; + packet.gcs_system_id = gcs_system_id; + packet.control_request = control_request; + packet.ack = ack; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 104); +} + +/** + * @brief Encode a change_operator_control_ack 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 change_operator_control_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack) +{ + return mavlink_msg_change_operator_control_ack_pack(system_id, component_id, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack); +} + +/** + * @brief Send a change_operator_control_ack message + * @param chan MAVLink channel to send the message + * + * @param gcs_system_id ID of the GCS this message + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_change_operator_control_ack_send(mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, gcs_system_id); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, ack); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, 3, 104); +#else + mavlink_change_operator_control_ack_t packet; + packet.gcs_system_id = gcs_system_id; + packet.control_request = control_request; + packet.ack = ack; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, 3, 104); +#endif +} + +#endif + +// MESSAGE CHANGE_OPERATOR_CONTROL_ACK UNPACKING + + +/** + * @brief Get field gcs_system_id from change_operator_control_ack message + * + * @return ID of the GCS this message + */ +static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field control_request from change_operator_control_ack message + * + * @return 0: request control of this MAV, 1: Release control of this MAV + */ +static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_request(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field ack from change_operator_control_ack message + * + * @return 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + */ +static inline uint8_t mavlink_msg_change_operator_control_ack_get_ack(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Decode a change_operator_control_ack message into a struct + * + * @param msg The message to decode + * @param change_operator_control_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_change_operator_control_ack_decode(const mavlink_message_t* msg, mavlink_change_operator_control_ack_t* change_operator_control_ack) +{ +#if MAVLINK_NEED_BYTE_SWAP + change_operator_control_ack->gcs_system_id = mavlink_msg_change_operator_control_ack_get_gcs_system_id(msg); + change_operator_control_ack->control_request = mavlink_msg_change_operator_control_ack_get_control_request(msg); + change_operator_control_ack->ack = mavlink_msg_change_operator_control_ack_get_ack(msg); +#else + memcpy(change_operator_control_ack, _MAV_PAYLOAD(msg), 3); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h new file mode 100644 index 0000000000000000000000000000000000000000..df6e9b9e3b7ec998a2b2dbc37c7de695648eab01 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h @@ -0,0 +1,166 @@ +// MESSAGE COMMAND_ACK PACKING + +#define MAVLINK_MSG_ID_COMMAND_ACK 77 + +typedef struct __mavlink_command_ack_t +{ + uint16_t command; ///< Command ID, as defined by MAV_CMD enum. + uint8_t result; ///< See MAV_RESULT enum +} mavlink_command_ack_t; + +#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3 +#define MAVLINK_MSG_ID_77_LEN 3 + + + +#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \ + "COMMAND_ACK", \ + 2, \ + { { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \ + { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \ + } \ +} + + +/** + * @brief Pack a command_ack 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 command Command ID, as defined by MAV_CMD enum. + * @param result See MAV_RESULT enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t command, uint8_t result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint16_t(buf, 0, command); + _mav_put_uint8_t(buf, 2, result); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); +#else + mavlink_command_ack_t packet; + packet.command = command; + packet.result = result; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; + return mavlink_finalize_message(msg, system_id, component_id, 3, 143); +} + +/** + * @brief Pack a command_ack 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 command Command ID, as defined by MAV_CMD enum. + * @param result See MAV_RESULT enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t command,uint8_t result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint16_t(buf, 0, command); + _mav_put_uint8_t(buf, 2, result); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); +#else + mavlink_command_ack_t packet; + packet.command = command; + packet.result = result; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 143); +} + +/** + * @brief Encode a command_ack 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 command_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack) +{ + return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result); +} + +/** + * @brief Send a command_ack message + * @param chan MAVLink channel to send the message + * + * @param command Command ID, as defined by MAV_CMD enum. + * @param result See MAV_RESULT enum + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t command, uint8_t result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint16_t(buf, 0, command); + _mav_put_uint8_t(buf, 2, result); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, 3, 143); +#else + mavlink_command_ack_t packet; + packet.command = command; + packet.result = result; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, 3, 143); +#endif +} + +#endif + +// MESSAGE COMMAND_ACK UNPACKING + + +/** + * @brief Get field command from command_ack message + * + * @return Command ID, as defined by MAV_CMD enum. + */ +static inline uint16_t mavlink_msg_command_ack_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field result from command_ack message + * + * @return See MAV_RESULT enum + */ +static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Decode a command_ack message into a struct + * + * @param msg The message to decode + * @param command_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg, mavlink_command_ack_t* command_ack) +{ +#if MAVLINK_NEED_BYTE_SWAP + command_ack->command = mavlink_msg_command_ack_get_command(msg); + command_ack->result = mavlink_msg_command_ack_get_result(msg); +#else + memcpy(command_ack, _MAV_PAYLOAD(msg), 3); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h new file mode 100644 index 0000000000000000000000000000000000000000..54ca77eaa2e5585d2f43d455a908ef15d56b370b --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h @@ -0,0 +1,364 @@ +// MESSAGE COMMAND_LONG PACKING + +#define MAVLINK_MSG_ID_COMMAND_LONG 76 + +typedef struct __mavlink_command_long_t +{ + float param1; ///< Parameter 1, as defined by MAV_CMD enum. + float param2; ///< Parameter 2, as defined by MAV_CMD enum. + float param3; ///< Parameter 3, as defined by MAV_CMD enum. + float param4; ///< Parameter 4, as defined by MAV_CMD enum. + float param5; ///< Parameter 5, as defined by MAV_CMD enum. + float param6; ///< Parameter 6, as defined by MAV_CMD enum. + float param7; ///< Parameter 7, as defined by MAV_CMD enum. + uint16_t command; ///< Command ID, as defined by MAV_CMD enum. + uint8_t target_system; ///< System which should execute the command + uint8_t target_component; ///< Component which should execute the command, 0 for all components + uint8_t confirmation; ///< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) +} mavlink_command_long_t; + +#define MAVLINK_MSG_ID_COMMAND_LONG_LEN 33 +#define MAVLINK_MSG_ID_76_LEN 33 + + + +#define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \ + "COMMAND_LONG", \ + 11, \ + { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \ + { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \ + { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \ + { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \ + { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \ + { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \ + { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \ + { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \ + } \ +} + + +/** + * @brief Pack a command_long 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 target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID, as defined by MAV_CMD enum. + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1, as defined by MAV_CMD enum. + * @param param2 Parameter 2, as defined by MAV_CMD enum. + * @param param3 Parameter 3, as defined by MAV_CMD enum. + * @param param4 Parameter 4, as defined by MAV_CMD enum. + * @param param5 Parameter 5, as defined by MAV_CMD enum. + * @param param6 Parameter 6, as defined by MAV_CMD enum. + * @param param7 Parameter 7, as defined by MAV_CMD enum. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[33]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, param5); + _mav_put_float(buf, 20, param6); + _mav_put_float(buf, 24, param7); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, confirmation); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33); +#else + mavlink_command_long_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.param5 = param5; + packet.param6 = param6; + packet.param7 = param7; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.confirmation = confirmation; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG; + return mavlink_finalize_message(msg, system_id, component_id, 33, 152); +} + +/** + * @brief Pack a command_long 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 target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID, as defined by MAV_CMD enum. + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1, as defined by MAV_CMD enum. + * @param param2 Parameter 2, as defined by MAV_CMD enum. + * @param param3 Parameter 3, as defined by MAV_CMD enum. + * @param param4 Parameter 4, as defined by MAV_CMD enum. + * @param param5 Parameter 5, as defined by MAV_CMD enum. + * @param param6 Parameter 6, as defined by MAV_CMD enum. + * @param param7 Parameter 7, as defined by MAV_CMD enum. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t command,uint8_t confirmation,float param1,float param2,float param3,float param4,float param5,float param6,float param7) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[33]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, param5); + _mav_put_float(buf, 20, param6); + _mav_put_float(buf, 24, param7); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, confirmation); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33); +#else + mavlink_command_long_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.param5 = param5; + packet.param6 = param6; + packet.param7 = param7; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.confirmation = confirmation; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 33, 152); +} + +/** + * @brief Encode a command_long 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 command_long C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_long_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_long_t* command_long) +{ + return mavlink_msg_command_long_pack(system_id, component_id, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); +} + +/** + * @brief Send a command_long message + * @param chan MAVLink channel to send the message + * + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID, as defined by MAV_CMD enum. + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1, as defined by MAV_CMD enum. + * @param param2 Parameter 2, as defined by MAV_CMD enum. + * @param param3 Parameter 3, as defined by MAV_CMD enum. + * @param param4 Parameter 4, as defined by MAV_CMD enum. + * @param param5 Parameter 5, as defined by MAV_CMD enum. + * @param param6 Parameter 6, as defined by MAV_CMD enum. + * @param param7 Parameter 7, as defined by MAV_CMD enum. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_command_long_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[33]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, param5); + _mav_put_float(buf, 20, param6); + _mav_put_float(buf, 24, param7); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, confirmation); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, 33, 152); +#else + mavlink_command_long_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.param5 = param5; + packet.param6 = param6; + packet.param7 = param7; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.confirmation = confirmation; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, 33, 152); +#endif +} + +#endif + +// MESSAGE COMMAND_LONG UNPACKING + + +/** + * @brief Get field target_system from command_long message + * + * @return System which should execute the command + */ +static inline uint8_t mavlink_msg_command_long_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 30); +} + +/** + * @brief Get field target_component from command_long message + * + * @return Component which should execute the command, 0 for all components + */ +static inline uint8_t mavlink_msg_command_long_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 31); +} + +/** + * @brief Get field command from command_long message + * + * @return Command ID, as defined by MAV_CMD enum. + */ +static inline uint16_t mavlink_msg_command_long_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field confirmation from command_long message + * + * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + */ +static inline uint8_t mavlink_msg_command_long_get_confirmation(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field param1 from command_long message + * + * @return Parameter 1, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param2 from command_long message + * + * @return Parameter 2, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field param3 from command_long message + * + * @return Parameter 3, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field param4 from command_long message + * + * @return Parameter 4, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field param5 from command_long message + * + * @return Parameter 5, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param5(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field param6 from command_long message + * + * @return Parameter 6, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param6(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field param7 from command_long message + * + * @return Parameter 7, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param7(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a command_long message into a struct + * + * @param msg The message to decode + * @param command_long C-struct to decode the message contents into + */ +static inline void mavlink_msg_command_long_decode(const mavlink_message_t* msg, mavlink_command_long_t* command_long) +{ +#if MAVLINK_NEED_BYTE_SWAP + command_long->param1 = mavlink_msg_command_long_get_param1(msg); + command_long->param2 = mavlink_msg_command_long_get_param2(msg); + command_long->param3 = mavlink_msg_command_long_get_param3(msg); + command_long->param4 = mavlink_msg_command_long_get_param4(msg); + command_long->param5 = mavlink_msg_command_long_get_param5(msg); + command_long->param6 = mavlink_msg_command_long_get_param6(msg); + command_long->param7 = mavlink_msg_command_long_get_param7(msg); + command_long->command = mavlink_msg_command_long_get_command(msg); + command_long->target_system = mavlink_msg_command_long_get_target_system(msg); + command_long->target_component = mavlink_msg_command_long_get_target_component(msg); + command_long->confirmation = mavlink_msg_command_long_get_confirmation(msg); +#else + memcpy(command_long, _MAV_PAYLOAD(msg), 33); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h new file mode 100644 index 0000000000000000000000000000000000000000..e5ec290452f45c009051d9f098400787abfa645a --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h @@ -0,0 +1,188 @@ +// MESSAGE DATA_STREAM PACKING + +#define MAVLINK_MSG_ID_DATA_STREAM 67 + +typedef struct __mavlink_data_stream_t +{ + uint16_t message_rate; ///< The requested interval between two messages of this type + uint8_t stream_id; ///< The ID of the requested data stream + uint8_t on_off; ///< 1 stream is enabled, 0 stream is stopped. +} mavlink_data_stream_t; + +#define MAVLINK_MSG_ID_DATA_STREAM_LEN 4 +#define MAVLINK_MSG_ID_67_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_DATA_STREAM { \ + "DATA_STREAM", \ + 3, \ + { { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \ + { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \ + { "on_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \ + } \ +} + + +/** + * @brief Pack a data_stream 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 stream_id The ID of the requested data stream + * @param message_rate The requested interval between two messages of this type + * @param on_off 1 stream is enabled, 0 stream is stopped. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t stream_id, uint16_t message_rate, uint8_t on_off) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, message_rate); + _mav_put_uint8_t(buf, 2, stream_id); + _mav_put_uint8_t(buf, 3, on_off); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); +#else + mavlink_data_stream_t packet; + packet.message_rate = message_rate; + packet.stream_id = stream_id; + packet.on_off = on_off; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; + return mavlink_finalize_message(msg, system_id, component_id, 4, 21); +} + +/** + * @brief Pack a data_stream 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 stream_id The ID of the requested data stream + * @param message_rate The requested interval between two messages of this type + * @param on_off 1 stream is enabled, 0 stream is stopped. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t stream_id,uint16_t message_rate,uint8_t on_off) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, message_rate); + _mav_put_uint8_t(buf, 2, stream_id); + _mav_put_uint8_t(buf, 3, on_off); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); +#else + mavlink_data_stream_t packet; + packet.message_rate = message_rate; + packet.stream_id = stream_id; + packet.on_off = on_off; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 21); +} + +/** + * @brief Encode a data_stream 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 data_stream C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_stream_t* data_stream) +{ + return mavlink_msg_data_stream_pack(system_id, component_id, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off); +} + +/** + * @brief Send a data_stream message + * @param chan MAVLink channel to send the message + * + * @param stream_id The ID of the requested data stream + * @param message_rate The requested interval between two messages of this type + * @param on_off 1 stream is enabled, 0 stream is stopped. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_data_stream_send(mavlink_channel_t chan, uint8_t stream_id, uint16_t message_rate, uint8_t on_off) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, message_rate); + _mav_put_uint8_t(buf, 2, stream_id); + _mav_put_uint8_t(buf, 3, on_off); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, 4, 21); +#else + mavlink_data_stream_t packet; + packet.message_rate = message_rate; + packet.stream_id = stream_id; + packet.on_off = on_off; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)&packet, 4, 21); +#endif +} + +#endif + +// MESSAGE DATA_STREAM UNPACKING + + +/** + * @brief Get field stream_id from data_stream message + * + * @return The ID of the requested data stream + */ +static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field message_rate from data_stream message + * + * @return The requested interval between two messages of this type + */ +static inline uint16_t mavlink_msg_data_stream_get_message_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field on_off from data_stream message + * + * @return 1 stream is enabled, 0 stream is stopped. + */ +static inline uint8_t mavlink_msg_data_stream_get_on_off(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Decode a data_stream message into a struct + * + * @param msg The message to decode + * @param data_stream C-struct to decode the message contents into + */ +static inline void mavlink_msg_data_stream_decode(const mavlink_message_t* msg, mavlink_data_stream_t* data_stream) +{ +#if MAVLINK_NEED_BYTE_SWAP + data_stream->message_rate = mavlink_msg_data_stream_get_message_rate(msg); + data_stream->stream_id = mavlink_msg_data_stream_get_stream_id(msg); + data_stream->on_off = mavlink_msg_data_stream_get_on_off(msg); +#else + memcpy(data_stream, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h new file mode 100644 index 0000000000000000000000000000000000000000..5ff88e6a8a2cd9a71fe99bf9eb5296e591b9e456 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h @@ -0,0 +1,188 @@ +// MESSAGE DEBUG PACKING + +#define MAVLINK_MSG_ID_DEBUG 254 + +typedef struct __mavlink_debug_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + float value; ///< DEBUG value + uint8_t ind; ///< index of debug variable +} mavlink_debug_t; + +#define MAVLINK_MSG_ID_DEBUG_LEN 9 +#define MAVLINK_MSG_ID_254_LEN 9 + + + +#define MAVLINK_MESSAGE_INFO_DEBUG { \ + "DEBUG", \ + 3, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \ + { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \ + { "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \ + } \ +} + + +/** + * @brief Pack a debug message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param ind index of debug variable + * @param value DEBUG value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t ind, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_uint8_t(buf, 8, ind); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); +#else + mavlink_debug_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + packet.ind = ind; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); +#endif + + msg->msgid = MAVLINK_MSG_ID_DEBUG; + return mavlink_finalize_message(msg, system_id, component_id, 9, 46); +} + +/** + * @brief Pack a debug message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param ind index of debug variable + * @param value DEBUG value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t ind,float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_uint8_t(buf, 8, ind); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); +#else + mavlink_debug_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + packet.ind = ind; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); +#endif + + msg->msgid = MAVLINK_MSG_ID_DEBUG; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 46); +} + +/** + * @brief Encode a debug 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 debug C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_t* debug) +{ + return mavlink_msg_debug_pack(system_id, component_id, msg, debug->time_boot_ms, debug->ind, debug->value); +} + +/** + * @brief Send a debug message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param ind index of debug variable + * @param value DEBUG value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_uint8_t(buf, 8, ind); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, 9, 46); +#else + mavlink_debug_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + packet.ind = ind; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, 9, 46); +#endif +} + +#endif + +// MESSAGE DEBUG UNPACKING + + +/** + * @brief Get field time_boot_ms from debug message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_debug_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field ind from debug message + * + * @return index of debug variable + */ +static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Get field value from debug message + * + * @return DEBUG value + */ +static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Decode a debug message into a struct + * + * @param msg The message to decode + * @param debug C-struct to decode the message contents into + */ +static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlink_debug_t* debug) +{ +#if MAVLINK_NEED_BYTE_SWAP + debug->time_boot_ms = mavlink_msg_debug_get_time_boot_ms(msg); + debug->value = mavlink_msg_debug_get_value(msg); + debug->ind = mavlink_msg_debug_get_ind(msg); +#else + memcpy(debug, _MAV_PAYLOAD(msg), 9); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h new file mode 100644 index 0000000000000000000000000000000000000000..0b443a061138eab5f5ffc8ed6caf5eafcd3d7f54 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h @@ -0,0 +1,226 @@ +// MESSAGE DEBUG_VECT PACKING + +#define MAVLINK_MSG_ID_DEBUG_VECT 250 + +typedef struct __mavlink_debug_vect_t +{ + uint64_t time_usec; ///< Timestamp + float x; ///< x + float y; ///< y + float z; ///< z + char name[10]; ///< Name +} mavlink_debug_vect_t; + +#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30 +#define MAVLINK_MSG_ID_250_LEN 30 + +#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10 + +#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \ + "DEBUG_VECT", \ + 5, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \ + } \ +} + + +/** + * @brief Pack a debug_vect message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param name Name + * @param time_usec Timestamp + * @param x x + * @param y y + * @param z z + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const char *name, uint64_t time_usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[30]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_char_array(buf, 20, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30); +#else + mavlink_debug_vect_t packet; + packet.time_usec = time_usec; + packet.x = x; + packet.y = y; + packet.z = z; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30); +#endif + + msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; + return mavlink_finalize_message(msg, system_id, component_id, 30, 49); +} + +/** + * @brief Pack a debug_vect 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 name Name + * @param time_usec Timestamp + * @param x x + * @param y y + * @param z z + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const char *name,uint64_t time_usec,float x,float y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[30]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_char_array(buf, 20, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30); +#else + mavlink_debug_vect_t packet; + packet.time_usec = time_usec; + packet.x = x; + packet.y = y; + packet.z = z; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30); +#endif + + msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30, 49); +} + +/** + * @brief Encode a debug_vect 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 debug_vect C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect) +{ + return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z); +} + +/** + * @brief Send a debug_vect message + * @param chan MAVLink channel to send the message + * + * @param name Name + * @param time_usec Timestamp + * @param x x + * @param y y + * @param z z + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[30]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_char_array(buf, 20, name, 10); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, 30, 49); +#else + mavlink_debug_vect_t packet; + packet.time_usec = time_usec; + packet.x = x; + packet.y = y; + packet.z = z; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, 30, 49); +#endif +} + +#endif + +// MESSAGE DEBUG_VECT UNPACKING + + +/** + * @brief Get field name from debug_vect message + * + * @return Name + */ +static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char *name) +{ + return _MAV_RETURN_char_array(msg, name, 10, 20); +} + +/** + * @brief Get field time_usec from debug_vect message + * + * @return Timestamp + */ +static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from debug_vect message + * + * @return x + */ +static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from debug_vect message + * + * @return y + */ +static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from debug_vect message + * + * @return z + */ +static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a debug_vect message into a struct + * + * @param msg The message to decode + * @param debug_vect C-struct to decode the message contents into + */ +static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect) +{ +#if MAVLINK_NEED_BYTE_SWAP + debug_vect->time_usec = mavlink_msg_debug_vect_get_time_usec(msg); + debug_vect->x = mavlink_msg_debug_vect_get_x(msg); + debug_vect->y = mavlink_msg_debug_vect_get_y(msg); + debug_vect->z = mavlink_msg_debug_vect_get_z(msg); + mavlink_msg_debug_vect_get_name(msg, debug_vect->name); +#else + memcpy(debug_vect, _MAV_PAYLOAD(msg), 30); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h new file mode 100644 index 0000000000000000000000000000000000000000..780f562c5b690b605553aac4d958602e1944af75 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h @@ -0,0 +1,320 @@ +// MESSAGE GLOBAL_POSITION_INT PACKING + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33 + +typedef struct __mavlink_global_position_int_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + int32_t lat; ///< Latitude, expressed as * 1E7 + int32_t lon; ///< Longitude, expressed as * 1E7 + int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters), above MSL + int32_t relative_alt; ///< Altitude above ground in meters, expressed as * 1000 (millimeters) + int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100 + int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100 + int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100 + uint16_t hdg; ///< Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 +} mavlink_global_position_int_t; + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28 +#define MAVLINK_MSG_ID_33_LEN 28 + + + +#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \ + "GLOBAL_POSITION_INT", \ + 9, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \ + { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \ + { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \ + { "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \ + } \ +} + + +/** + * @brief Pack a global_position_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL + * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, alt); + _mav_put_int32_t(buf, 16, relative_alt); + _mav_put_int16_t(buf, 20, vx); + _mav_put_int16_t(buf, 22, vy); + _mav_put_int16_t(buf, 24, vz); + _mav_put_uint16_t(buf, 26, hdg); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); +#else + mavlink_global_position_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.relative_alt = relative_alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.hdg = hdg; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; + return mavlink_finalize_message(msg, system_id, component_id, 28, 104); +} + +/** + * @brief Pack a global_position_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL + * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,int16_t vx,int16_t vy,int16_t vz,uint16_t hdg) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, alt); + _mav_put_int32_t(buf, 16, relative_alt); + _mav_put_int16_t(buf, 20, vx); + _mav_put_int16_t(buf, 22, vy); + _mav_put_int16_t(buf, 24, vz); + _mav_put_uint16_t(buf, 26, hdg); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); +#else + mavlink_global_position_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.relative_alt = relative_alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.hdg = hdg; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 104); +} + +/** + * @brief Encode a global_position_int 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 global_position_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int) +{ + return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg); +} + +/** + * @brief Send a global_position_int message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL + * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, alt); + _mav_put_int32_t(buf, 16, relative_alt); + _mav_put_int16_t(buf, 20, vx); + _mav_put_int16_t(buf, 22, vy); + _mav_put_int16_t(buf, 24, vz); + _mav_put_uint16_t(buf, 26, hdg); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, 28, 104); +#else + mavlink_global_position_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.relative_alt = relative_alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.hdg = hdg; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, 28, 104); +#endif +} + +#endif + +// MESSAGE GLOBAL_POSITION_INT UNPACKING + + +/** + * @brief Get field time_boot_ms from global_position_int message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field lat from global_position_int message + * + * @return Latitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field lon from global_position_int message + * + * @return Longitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field alt from global_position_int message + * + * @return Altitude in meters, expressed as * 1000 (millimeters), above MSL + */ +static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field relative_alt from global_position_int message + * + * @return Altitude above ground in meters, expressed as * 1000 (millimeters) + */ +static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field vx from global_position_int message + * + * @return Ground X Speed (Latitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Get field vy from global_position_int message + * + * @return Ground Y Speed (Longitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 22); +} + +/** + * @brief Get field vz from global_position_int message + * + * @return Ground Z Speed (Altitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 24); +} + +/** + * @brief Get field hdg from global_position_int message + * + * @return Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + */ +static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Decode a global_position_int message into a struct + * + * @param msg The message to decode + * @param global_position_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + global_position_int->time_boot_ms = mavlink_msg_global_position_int_get_time_boot_ms(msg); + global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg); + global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg); + global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg); + global_position_int->relative_alt = mavlink_msg_global_position_int_get_relative_alt(msg); + global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg); + global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg); + global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg); + global_position_int->hdg = mavlink_msg_global_position_int_get_hdg(msg); +#else + memcpy(global_position_int, _MAV_PAYLOAD(msg), 28); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h new file mode 100644 index 0000000000000000000000000000000000000000..853b85daeb3f5b602dbd56b1a12674567b0aeead --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h @@ -0,0 +1,232 @@ +// MESSAGE GLOBAL_POSITION_SETPOINT_INT PACKING + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT 52 + +typedef struct __mavlink_global_position_setpoint_int_t +{ + int32_t latitude; ///< WGS84 Latitude position in degrees * 1E7 + int32_t longitude; ///< WGS84 Longitude position in degrees * 1E7 + int32_t altitude; ///< WGS84 Altitude in meters * 1000 (positive for up) + int16_t yaw; ///< Desired yaw angle in degrees * 100 + uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT +} mavlink_global_position_setpoint_int_t; + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN 15 +#define MAVLINK_MSG_ID_52_LEN 15 + + + +#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT { \ + "GLOBAL_POSITION_SETPOINT_INT", \ + 5, \ + { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_global_position_setpoint_int_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_setpoint_int_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_setpoint_int_t, altitude) }, \ + { "yaw", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_global_position_setpoint_int_t, yaw) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_global_position_setpoint_int_t, coordinate_frame) }, \ + } \ +} + + +/** + * @brief Pack a global_position_setpoint_int 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 coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT + * @param latitude WGS84 Latitude position in degrees * 1E7 + * @param longitude WGS84 Longitude position in degrees * 1E7 + * @param altitude WGS84 Altitude in meters * 1000 (positive for up) + * @param yaw Desired yaw angle in degrees * 100 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_setpoint_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[15]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_int16_t(buf, 12, yaw); + _mav_put_uint8_t(buf, 14, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); +#else + mavlink_global_position_setpoint_int_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.yaw = yaw; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT; + return mavlink_finalize_message(msg, system_id, component_id, 15, 141); +} + +/** + * @brief Pack a global_position_setpoint_int 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 coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT + * @param latitude WGS84 Latitude position in degrees * 1E7 + * @param longitude WGS84 Longitude position in degrees * 1E7 + * @param altitude WGS84 Altitude in meters * 1000 (positive for up) + * @param yaw Desired yaw angle in degrees * 100 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_setpoint_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t coordinate_frame,int32_t latitude,int32_t longitude,int32_t altitude,int16_t yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[15]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_int16_t(buf, 12, yaw); + _mav_put_uint8_t(buf, 14, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); +#else + mavlink_global_position_setpoint_int_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.yaw = yaw; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 15, 141); +} + +/** + * @brief Encode a global_position_setpoint_int 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 global_position_setpoint_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_position_setpoint_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_setpoint_int_t* global_position_setpoint_int) +{ + return mavlink_msg_global_position_setpoint_int_pack(system_id, component_id, msg, global_position_setpoint_int->coordinate_frame, global_position_setpoint_int->latitude, global_position_setpoint_int->longitude, global_position_setpoint_int->altitude, global_position_setpoint_int->yaw); +} + +/** + * @brief Send a global_position_setpoint_int message + * @param chan MAVLink channel to send the message + * + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT + * @param latitude WGS84 Latitude position in degrees * 1E7 + * @param longitude WGS84 Longitude position in degrees * 1E7 + * @param altitude WGS84 Altitude in meters * 1000 (positive for up) + * @param yaw Desired yaw angle in degrees * 100 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_global_position_setpoint_int_send(mavlink_channel_t chan, uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[15]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_int16_t(buf, 12, yaw); + _mav_put_uint8_t(buf, 14, coordinate_frame); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, buf, 15, 141); +#else + mavlink_global_position_setpoint_int_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.yaw = yaw; + packet.coordinate_frame = coordinate_frame; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, 15, 141); +#endif +} + +#endif + +// MESSAGE GLOBAL_POSITION_SETPOINT_INT UNPACKING + + +/** + * @brief Get field coordinate_frame from global_position_setpoint_int message + * + * @return Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT + */ +static inline uint8_t mavlink_msg_global_position_setpoint_int_get_coordinate_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 14); +} + +/** + * @brief Get field latitude from global_position_setpoint_int message + * + * @return WGS84 Latitude position in degrees * 1E7 + */ +static inline int32_t mavlink_msg_global_position_setpoint_int_get_latitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field longitude from global_position_setpoint_int message + * + * @return WGS84 Longitude position in degrees * 1E7 + */ +static inline int32_t mavlink_msg_global_position_setpoint_int_get_longitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field altitude from global_position_setpoint_int message + * + * @return WGS84 Altitude in meters * 1000 (positive for up) + */ +static inline int32_t mavlink_msg_global_position_setpoint_int_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field yaw from global_position_setpoint_int message + * + * @return Desired yaw angle in degrees * 100 + */ +static inline int16_t mavlink_msg_global_position_setpoint_int_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Decode a global_position_setpoint_int message into a struct + * + * @param msg The message to decode + * @param global_position_setpoint_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_global_position_setpoint_int_decode(const mavlink_message_t* msg, mavlink_global_position_setpoint_int_t* global_position_setpoint_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + global_position_setpoint_int->latitude = mavlink_msg_global_position_setpoint_int_get_latitude(msg); + global_position_setpoint_int->longitude = mavlink_msg_global_position_setpoint_int_get_longitude(msg); + global_position_setpoint_int->altitude = mavlink_msg_global_position_setpoint_int_get_altitude(msg); + global_position_setpoint_int->yaw = mavlink_msg_global_position_setpoint_int_get_yaw(msg); + global_position_setpoint_int->coordinate_frame = mavlink_msg_global_position_setpoint_int_get_coordinate_frame(msg); +#else + memcpy(global_position_setpoint_int, _MAV_PAYLOAD(msg), 15); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h new file mode 100644 index 0000000000000000000000000000000000000000..e4617702bd4dee220fca267be5a23d040dd8818d --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h @@ -0,0 +1,276 @@ +// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE 101 + +typedef struct __mavlink_global_vision_position_estimate_t +{ + uint64_t usec; ///< Timestamp (milliseconds) + float x; ///< Global X position + float y; ///< Global Y position + float z; ///< Global Z position + float roll; ///< Roll angle in rad + float pitch; ///< Pitch angle in rad + float yaw; ///< Yaw angle in rad +} mavlink_global_vision_position_estimate_t; + +#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 32 +#define MAVLINK_MSG_ID_101_LEN 32 + + + +#define MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE { \ + "GLOBAL_VISION_POSITION_ESTIMATE", \ + 7, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_vision_position_estimate_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_vision_position_estimate_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_vision_position_estimate_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_vision_position_estimate_t, z) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_vision_position_estimate_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_vision_position_estimate_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_vision_position_estimate_t, yaw) }, \ + } \ +} + + +/** + * @brief Pack a global_vision_position_estimate 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 usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); +#else + mavlink_global_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE; + return mavlink_finalize_message(msg, system_id, component_id, 32, 102); +} + +/** + * @brief Pack a global_vision_position_estimate 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 usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); +#else + mavlink_global_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 102); +} + +/** + * @brief Encode a global_vision_position_estimate 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 global_vision_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate) +{ + return mavlink_msg_global_vision_position_estimate_pack(system_id, component_id, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw); +} + +/** + * @brief Send a global_vision_position_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_global_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, 32, 102); +#else + mavlink_global_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, 32, 102); +#endif +} + +#endif + +// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE UNPACKING + + +/** + * @brief Get field usec from global_vision_position_estimate message + * + * @return Timestamp (milliseconds) + */ +static inline uint64_t mavlink_msg_global_vision_position_estimate_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from global_vision_position_estimate message + * + * @return Global X position + */ +static inline float mavlink_msg_global_vision_position_estimate_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from global_vision_position_estimate message + * + * @return Global Y position + */ +static inline float mavlink_msg_global_vision_position_estimate_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from global_vision_position_estimate message + * + * @return Global Z position + */ +static inline float mavlink_msg_global_vision_position_estimate_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field roll from global_vision_position_estimate message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_global_vision_position_estimate_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitch from global_vision_position_estimate message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_global_vision_position_estimate_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yaw from global_vision_position_estimate message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_global_vision_position_estimate_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a global_vision_position_estimate message into a struct + * + * @param msg The message to decode + * @param global_vision_position_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_global_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_global_vision_position_estimate_t* global_vision_position_estimate) +{ +#if MAVLINK_NEED_BYTE_SWAP + global_vision_position_estimate->usec = mavlink_msg_global_vision_position_estimate_get_usec(msg); + global_vision_position_estimate->x = mavlink_msg_global_vision_position_estimate_get_x(msg); + global_vision_position_estimate->y = mavlink_msg_global_vision_position_estimate_get_y(msg); + global_vision_position_estimate->z = mavlink_msg_global_vision_position_estimate_get_z(msg); + global_vision_position_estimate->roll = mavlink_msg_global_vision_position_estimate_get_roll(msg); + global_vision_position_estimate->pitch = mavlink_msg_global_vision_position_estimate_get_pitch(msg); + global_vision_position_estimate->yaw = mavlink_msg_global_vision_position_estimate_get_yaw(msg); +#else + memcpy(global_vision_position_estimate, _MAV_PAYLOAD(msg), 32); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h new file mode 100644 index 0000000000000000000000000000000000000000..2084718b5d26b99fd773235585fd62b0262ddcc0 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h @@ -0,0 +1,188 @@ +// MESSAGE GPS_GLOBAL_ORIGIN PACKING + +#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49 + +typedef struct __mavlink_gps_global_origin_t +{ + int32_t latitude; ///< Latitude (WGS84), expressed as * 1E7 + int32_t longitude; ///< Longitude (WGS84), expressed as * 1E7 + int32_t altitude; ///< Altitude(WGS84), expressed as * 1000 +} mavlink_gps_global_origin_t; + +#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12 +#define MAVLINK_MSG_ID_49_LEN 12 + + + +#define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \ + "GPS_GLOBAL_ORIGIN", \ + 3, \ + { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_global_origin_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_global_origin_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_global_origin_t, altitude) }, \ + } \ +} + + +/** + * @brief Pack a gps_global_origin 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 latitude Latitude (WGS84), expressed as * 1E7 + * @param longitude Longitude (WGS84), expressed as * 1E7 + * @param altitude Altitude(WGS84), expressed as * 1000 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; + return mavlink_finalize_message(msg, system_id, component_id, 12, 39); +} + +/** + * @brief Pack a gps_global_origin 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 latitude Latitude (WGS84), expressed as * 1E7 + * @param longitude Longitude (WGS84), expressed as * 1E7 + * @param altitude Altitude(WGS84), expressed as * 1000 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int32_t latitude,int32_t longitude,int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 39); +} + +/** + * @brief Encode a gps_global_origin 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 gps_global_origin C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin) +{ + return mavlink_msg_gps_global_origin_pack(system_id, component_id, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude); +} + +/** + * @brief Send a gps_global_origin message + * @param chan MAVLink channel to send the message + * + * @param latitude Latitude (WGS84), expressed as * 1E7 + * @param longitude Longitude (WGS84), expressed as * 1E7 + * @param altitude Altitude(WGS84), expressed as * 1000 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, 12, 39); +#else + mavlink_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, 12, 39); +#endif +} + +#endif + +// MESSAGE GPS_GLOBAL_ORIGIN UNPACKING + + +/** + * @brief Get field latitude from gps_global_origin message + * + * @return Latitude (WGS84), expressed as * 1E7 + */ +static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field longitude from gps_global_origin message + * + * @return Longitude (WGS84), expressed as * 1E7 + */ +static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field altitude from gps_global_origin message + * + * @return Altitude(WGS84), expressed as * 1000 + */ +static inline int32_t mavlink_msg_gps_global_origin_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Decode a gps_global_origin message into a struct + * + * @param msg The message to decode + * @param gps_global_origin C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_global_origin_t* gps_global_origin) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_global_origin->latitude = mavlink_msg_gps_global_origin_get_latitude(msg); + gps_global_origin->longitude = mavlink_msg_gps_global_origin_get_longitude(msg); + gps_global_origin->altitude = mavlink_msg_gps_global_origin_get_altitude(msg); +#else + memcpy(gps_global_origin, _MAV_PAYLOAD(msg), 12); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h new file mode 100644 index 0000000000000000000000000000000000000000..57ec97376327f784a3816d57c251e478820b8c23 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h @@ -0,0 +1,342 @@ +// MESSAGE GPS_RAW_INT PACKING + +#define MAVLINK_MSG_ID_GPS_RAW_INT 24 + +typedef struct __mavlink_gps_raw_int_t +{ + uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + int32_t lat; ///< Latitude in 1E7 degrees + int32_t lon; ///< Longitude in 1E7 degrees + int32_t alt; ///< Altitude in 1E3 meters (millimeters) above MSL + uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + uint16_t epv; ///< GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: 65535 + uint16_t cog; ///< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + uint8_t satellites_visible; ///< Number of satellites visible. If unknown, set to 255 +} mavlink_gps_raw_int_t; + +#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30 +#define MAVLINK_MSG_ID_24_LEN 30 + + + +#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \ + "GPS_RAW_INT", \ + 10, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \ + { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \ + { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \ + { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \ + { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \ + { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \ + } \ +} + + +/** + * @brief Pack a gps_raw_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude in 1E7 degrees + * @param lon Longitude in 1E7 degrees + * @param alt Altitude in 1E3 meters (millimeters) above MSL + * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[30]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_uint16_t(buf, 26, cog); + _mav_put_uint8_t(buf, 28, fix_type); + _mav_put_uint8_t(buf, 29, satellites_visible); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30); +#else + mavlink_gps_raw_int_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT; + return mavlink_finalize_message(msg, system_id, component_id, 30, 24); +} + +/** + * @brief Pack a gps_raw_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude in 1E7 degrees + * @param lon Longitude in 1E7 degrees + * @param alt Altitude in 1E3 meters (millimeters) above MSL + * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,uint16_t cog,uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[30]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_uint16_t(buf, 26, cog); + _mav_put_uint8_t(buf, 28, fix_type); + _mav_put_uint8_t(buf, 29, satellites_visible); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30); +#else + mavlink_gps_raw_int_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30, 24); +} + +/** + * @brief Encode a gps_raw_int 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 gps_raw_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int) +{ + return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible); +} + +/** + * @brief Send a gps_raw_int message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude in 1E7 degrees + * @param lon Longitude in 1E7 degrees + * @param alt Altitude in 1E3 meters (millimeters) above MSL + * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[30]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_uint16_t(buf, 26, cog); + _mav_put_uint8_t(buf, 28, fix_type); + _mav_put_uint8_t(buf, 29, satellites_visible); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, 30, 24); +#else + mavlink_gps_raw_int_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, 30, 24); +#endif +} + +#endif + +// MESSAGE GPS_RAW_INT UNPACKING + + +/** + * @brief Get field time_usec from gps_raw_int message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field fix_type from gps_raw_int message + * + * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + */ +static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 28); +} + +/** + * @brief Get field lat from gps_raw_int message + * + * @return Latitude in 1E7 degrees + */ +static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field lon from gps_raw_int message + * + * @return Longitude in 1E7 degrees + */ +static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field alt from gps_raw_int message + * + * @return Altitude in 1E3 meters (millimeters) above MSL + */ +static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field eph from gps_raw_int message + * + * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + */ +static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Get field epv from gps_raw_int message + * + * @return GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + */ +static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field vel from gps_raw_int message + * + * @return GPS ground speed (m/s * 100). If unknown, set to: 65535 + */ +static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field cog from gps_raw_int message + * + * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + */ +static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Get field satellites_visible from gps_raw_int message + * + * @return Number of satellites visible. If unknown, set to 255 + */ +static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 29); +} + +/** + * @brief Decode a gps_raw_int message into a struct + * + * @param msg The message to decode + * @param gps_raw_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg, mavlink_gps_raw_int_t* gps_raw_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_raw_int->time_usec = mavlink_msg_gps_raw_int_get_time_usec(msg); + gps_raw_int->lat = mavlink_msg_gps_raw_int_get_lat(msg); + gps_raw_int->lon = mavlink_msg_gps_raw_int_get_lon(msg); + gps_raw_int->alt = mavlink_msg_gps_raw_int_get_alt(msg); + gps_raw_int->eph = mavlink_msg_gps_raw_int_get_eph(msg); + gps_raw_int->epv = mavlink_msg_gps_raw_int_get_epv(msg); + gps_raw_int->vel = mavlink_msg_gps_raw_int_get_vel(msg); + gps_raw_int->cog = mavlink_msg_gps_raw_int_get_cog(msg); + gps_raw_int->fix_type = mavlink_msg_gps_raw_int_get_fix_type(msg); + gps_raw_int->satellites_visible = mavlink_msg_gps_raw_int_get_satellites_visible(msg); +#else + memcpy(gps_raw_int, _MAV_PAYLOAD(msg), 30); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h new file mode 100644 index 0000000000000000000000000000000000000000..bd3257f889b58c7bc7928a18e9d26ca583cbcba1 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h @@ -0,0 +1,252 @@ +// MESSAGE GPS_STATUS PACKING + +#define MAVLINK_MSG_ID_GPS_STATUS 25 + +typedef struct __mavlink_gps_status_t +{ + uint8_t satellites_visible; ///< Number of satellites visible + uint8_t satellite_prn[20]; ///< Global satellite ID + uint8_t satellite_used[20]; ///< 0: Satellite not used, 1: used for localization + uint8_t satellite_elevation[20]; ///< Elevation (0: right on top of receiver, 90: on the horizon) of satellite + uint8_t satellite_azimuth[20]; ///< Direction of satellite, 0: 0 deg, 255: 360 deg. + uint8_t satellite_snr[20]; ///< Signal to noise ratio of satellite +} mavlink_gps_status_t; + +#define MAVLINK_MSG_ID_GPS_STATUS_LEN 101 +#define MAVLINK_MSG_ID_25_LEN 101 + +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20 + +#define MAVLINK_MESSAGE_INFO_GPS_STATUS { \ + "GPS_STATUS", \ + 6, \ + { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \ + { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \ + { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \ + { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \ + { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \ + { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \ + } \ +} + + +/** + * @brief Pack a gps_status 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 satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr Signal to noise ratio of satellite + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[101]; + _mav_put_uint8_t(buf, 0, satellites_visible); + _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); + _mav_put_uint8_t_array(buf, 21, satellite_used, 20); + _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); + _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); + _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 101); +#else + mavlink_gps_status_t packet; + packet.satellites_visible = satellites_visible; + mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 101); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; + return mavlink_finalize_message(msg, system_id, component_id, 101, 23); +} + +/** + * @brief Pack a gps_status 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 satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr Signal to noise ratio of satellite + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t satellites_visible,const uint8_t *satellite_prn,const uint8_t *satellite_used,const uint8_t *satellite_elevation,const uint8_t *satellite_azimuth,const uint8_t *satellite_snr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[101]; + _mav_put_uint8_t(buf, 0, satellites_visible); + _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); + _mav_put_uint8_t_array(buf, 21, satellite_used, 20); + _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); + _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); + _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 101); +#else + mavlink_gps_status_t packet; + packet.satellites_visible = satellites_visible; + mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 101); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 101, 23); +} + +/** + * @brief Encode a gps_status 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 gps_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status) +{ + return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); +} + +/** + * @brief Send a gps_status message + * @param chan MAVLink channel to send the message + * + * @param satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr Signal to noise ratio of satellite + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[101]; + _mav_put_uint8_t(buf, 0, satellites_visible); + _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); + _mav_put_uint8_t_array(buf, 21, satellite_used, 20); + _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); + _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); + _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, 101, 23); +#else + mavlink_gps_status_t packet; + packet.satellites_visible = satellites_visible; + mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, 101, 23); +#endif +} + +#endif + +// MESSAGE GPS_STATUS UNPACKING + + +/** + * @brief Get field satellites_visible from gps_status message + * + * @return Number of satellites visible + */ +static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field satellite_prn from gps_status message + * + * @return Global satellite ID + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, uint8_t *satellite_prn) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_prn, 20, 1); +} + +/** + * @brief Get field satellite_used from gps_status message + * + * @return 0: Satellite not used, 1: used for localization + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, uint8_t *satellite_used) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_used, 20, 21); +} + +/** + * @brief Get field satellite_elevation from gps_status message + * + * @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_elevation, 20, 41); +} + +/** + * @brief Get field satellite_azimuth from gps_status message + * + * @return Direction of satellite, 0: 0 deg, 255: 360 deg. + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_azimuth, 20, 61); +} + +/** + * @brief Get field satellite_snr from gps_status message + * + * @return Signal to noise ratio of satellite + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_snr, 20, 81); +} + +/** + * @brief Decode a gps_status message into a struct + * + * @param msg The message to decode + * @param gps_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg); + mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn); + mavlink_msg_gps_status_get_satellite_used(msg, gps_status->satellite_used); + mavlink_msg_gps_status_get_satellite_elevation(msg, gps_status->satellite_elevation); + mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth); + mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr); +#else + memcpy(gps_status, _MAV_PAYLOAD(msg), 101); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h new file mode 100644 index 0000000000000000000000000000000000000000..599ea0bc5e9f6b95e1f290ec004610066b1e773a --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h @@ -0,0 +1,251 @@ +// MESSAGE HEARTBEAT PACKING + +#define MAVLINK_MSG_ID_HEARTBEAT 0 + +typedef struct __mavlink_heartbeat_t +{ + uint32_t custom_mode; ///< A bitfield for use for autopilot-specific flags. + uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + uint8_t autopilot; ///< Autopilot type / class. defined in MAV_AUTOPILOT ENUM + uint8_t base_mode; ///< System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + uint8_t system_status; ///< System status flag, see MAV_STATE ENUM + uint8_t mavlink_version; ///< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version +} mavlink_heartbeat_t; + +#define MAVLINK_MSG_ID_HEARTBEAT_LEN 9 +#define MAVLINK_MSG_ID_0_LEN 9 + + + +#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \ + "HEARTBEAT", \ + 6, \ + { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \ + { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \ + { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \ + { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \ + { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \ + } \ +} + + +/** + * @brief Pack a heartbeat 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 type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM + * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + * @param custom_mode A bitfield for use for autopilot-specific flags. + * @param system_status System status flag, see MAV_STATE ENUM + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, autopilot); + _mav_put_uint8_t(buf, 6, base_mode); + _mav_put_uint8_t(buf, 7, system_status); + _mav_put_uint8_t(buf, 8, 3); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); +#else + mavlink_heartbeat_t packet; + packet.custom_mode = custom_mode; + packet.type = type; + packet.autopilot = autopilot; + packet.base_mode = base_mode; + packet.system_status = system_status; + packet.mavlink_version = 3; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); +#endif + + msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; + return mavlink_finalize_message(msg, system_id, component_id, 9, 50); +} + +/** + * @brief Pack a heartbeat 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 type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM + * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + * @param custom_mode A bitfield for use for autopilot-specific flags. + * @param system_status System status flag, see MAV_STATE ENUM + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t type,uint8_t autopilot,uint8_t base_mode,uint32_t custom_mode,uint8_t system_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, autopilot); + _mav_put_uint8_t(buf, 6, base_mode); + _mav_put_uint8_t(buf, 7, system_status); + _mav_put_uint8_t(buf, 8, 3); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); +#else + mavlink_heartbeat_t packet; + packet.custom_mode = custom_mode; + packet.type = type; + packet.autopilot = autopilot; + packet.base_mode = base_mode; + packet.system_status = system_status; + packet.mavlink_version = 3; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); +#endif + + msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 50); +} + +/** + * @brief Encode a heartbeat 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 heartbeat C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) +{ + return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status); +} + +/** + * @brief Send a heartbeat message + * @param chan MAVLink channel to send the message + * + * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM + * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + * @param custom_mode A bitfield for use for autopilot-specific flags. + * @param system_status System status flag, see MAV_STATE ENUM + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, autopilot); + _mav_put_uint8_t(buf, 6, base_mode); + _mav_put_uint8_t(buf, 7, system_status); + _mav_put_uint8_t(buf, 8, 3); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, 9, 50); +#else + mavlink_heartbeat_t packet; + packet.custom_mode = custom_mode; + packet.type = type; + packet.autopilot = autopilot; + packet.base_mode = base_mode; + packet.system_status = system_status; + packet.mavlink_version = 3; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, 9, 50); +#endif +} + +#endif + +// MESSAGE HEARTBEAT UNPACKING + + +/** + * @brief Get field type from heartbeat message + * + * @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + */ +static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field autopilot from heartbeat message + * + * @return Autopilot type / class. defined in MAV_AUTOPILOT ENUM + */ +static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field base_mode from heartbeat message + * + * @return System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + */ +static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field custom_mode from heartbeat message + * + * @return A bitfield for use for autopilot-specific flags. + */ +static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field system_status from heartbeat message + * + * @return System status flag, see MAV_STATE ENUM + */ +static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field mavlink_version from heartbeat message + * + * @return MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version + */ +static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Decode a heartbeat message into a struct + * + * @param msg The message to decode + * @param heartbeat C-struct to decode the message contents into + */ +static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat) +{ +#if MAVLINK_NEED_BYTE_SWAP + heartbeat->custom_mode = mavlink_msg_heartbeat_get_custom_mode(msg); + heartbeat->type = mavlink_msg_heartbeat_get_type(msg); + heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg); + heartbeat->base_mode = mavlink_msg_heartbeat_get_base_mode(msg); + heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg); + heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg); +#else + memcpy(heartbeat, _MAV_PAYLOAD(msg), 9); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h new file mode 100644 index 0000000000000000000000000000000000000000..41a9bc9498b63aa0134310d8e1db72df517df75d --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h @@ -0,0 +1,364 @@ +// MESSAGE HIL_CONTROLS PACKING + +#define MAVLINK_MSG_ID_HIL_CONTROLS 91 + +typedef struct __mavlink_hil_controls_t +{ + uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + float roll_ailerons; ///< Control output -1 .. 1 + float pitch_elevator; ///< Control output -1 .. 1 + float yaw_rudder; ///< Control output -1 .. 1 + float throttle; ///< Throttle 0 .. 1 + float aux1; ///< Aux 1, -1 .. 1 + float aux2; ///< Aux 2, -1 .. 1 + float aux3; ///< Aux 3, -1 .. 1 + float aux4; ///< Aux 4, -1 .. 1 + uint8_t mode; ///< System mode (MAV_MODE) + uint8_t nav_mode; ///< Navigation mode (MAV_NAV_MODE) +} mavlink_hil_controls_t; + +#define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42 +#define MAVLINK_MSG_ID_91_LEN 42 + + + +#define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \ + "HIL_CONTROLS", \ + 11, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \ + { "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \ + { "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \ + { "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \ + { "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \ + { "aux1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_controls_t, aux1) }, \ + { "aux2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_controls_t, aux2) }, \ + { "aux3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_controls_t, aux3) }, \ + { "aux4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_controls_t, aux4) }, \ + { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_hil_controls_t, mode) }, \ + { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_hil_controls_t, nav_mode) }, \ + } \ +} + + +/** + * @brief Pack a hil_controls message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll_ailerons Control output -1 .. 1 + * @param pitch_elevator Control output -1 .. 1 + * @param yaw_rudder Control output -1 .. 1 + * @param throttle Throttle 0 .. 1 + * @param aux1 Aux 1, -1 .. 1 + * @param aux2 Aux 2, -1 .. 1 + * @param aux3 Aux 3, -1 .. 1 + * @param aux4 Aux 4, -1 .. 1 + * @param mode System mode (MAV_MODE) + * @param nav_mode Navigation mode (MAV_NAV_MODE) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[42]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll_ailerons); + _mav_put_float(buf, 12, pitch_elevator); + _mav_put_float(buf, 16, yaw_rudder); + _mav_put_float(buf, 20, throttle); + _mav_put_float(buf, 24, aux1); + _mav_put_float(buf, 28, aux2); + _mav_put_float(buf, 32, aux3); + _mav_put_float(buf, 36, aux4); + _mav_put_uint8_t(buf, 40, mode); + _mav_put_uint8_t(buf, 41, nav_mode); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42); +#else + mavlink_hil_controls_t packet; + packet.time_usec = time_usec; + packet.roll_ailerons = roll_ailerons; + packet.pitch_elevator = pitch_elevator; + packet.yaw_rudder = yaw_rudder; + packet.throttle = throttle; + packet.aux1 = aux1; + packet.aux2 = aux2; + packet.aux3 = aux3; + packet.aux4 = aux4; + packet.mode = mode; + packet.nav_mode = nav_mode; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS; + return mavlink_finalize_message(msg, system_id, component_id, 42, 63); +} + +/** + * @brief Pack a hil_controls message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll_ailerons Control output -1 .. 1 + * @param pitch_elevator Control output -1 .. 1 + * @param yaw_rudder Control output -1 .. 1 + * @param throttle Throttle 0 .. 1 + * @param aux1 Aux 1, -1 .. 1 + * @param aux2 Aux 2, -1 .. 1 + * @param aux3 Aux 3, -1 .. 1 + * @param aux4 Aux 4, -1 .. 1 + * @param mode System mode (MAV_MODE) + * @param nav_mode Navigation mode (MAV_NAV_MODE) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float roll_ailerons,float pitch_elevator,float yaw_rudder,float throttle,float aux1,float aux2,float aux3,float aux4,uint8_t mode,uint8_t nav_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[42]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll_ailerons); + _mav_put_float(buf, 12, pitch_elevator); + _mav_put_float(buf, 16, yaw_rudder); + _mav_put_float(buf, 20, throttle); + _mav_put_float(buf, 24, aux1); + _mav_put_float(buf, 28, aux2); + _mav_put_float(buf, 32, aux3); + _mav_put_float(buf, 36, aux4); + _mav_put_uint8_t(buf, 40, mode); + _mav_put_uint8_t(buf, 41, nav_mode); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42); +#else + mavlink_hil_controls_t packet; + packet.time_usec = time_usec; + packet.roll_ailerons = roll_ailerons; + packet.pitch_elevator = pitch_elevator; + packet.yaw_rudder = yaw_rudder; + packet.throttle = throttle; + packet.aux1 = aux1; + packet.aux2 = aux2; + packet.aux3 = aux3; + packet.aux4 = aux4; + packet.mode = mode; + packet.nav_mode = nav_mode; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 42, 63); +} + +/** + * @brief Encode a hil_controls 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 hil_controls C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls) +{ + return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode); +} + +/** + * @brief Send a hil_controls message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll_ailerons Control output -1 .. 1 + * @param pitch_elevator Control output -1 .. 1 + * @param yaw_rudder Control output -1 .. 1 + * @param throttle Throttle 0 .. 1 + * @param aux1 Aux 1, -1 .. 1 + * @param aux2 Aux 2, -1 .. 1 + * @param aux3 Aux 3, -1 .. 1 + * @param aux4 Aux 4, -1 .. 1 + * @param mode System mode (MAV_MODE) + * @param nav_mode Navigation mode (MAV_NAV_MODE) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[42]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll_ailerons); + _mav_put_float(buf, 12, pitch_elevator); + _mav_put_float(buf, 16, yaw_rudder); + _mav_put_float(buf, 20, throttle); + _mav_put_float(buf, 24, aux1); + _mav_put_float(buf, 28, aux2); + _mav_put_float(buf, 32, aux3); + _mav_put_float(buf, 36, aux4); + _mav_put_uint8_t(buf, 40, mode); + _mav_put_uint8_t(buf, 41, nav_mode); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, 42, 63); +#else + mavlink_hil_controls_t packet; + packet.time_usec = time_usec; + packet.roll_ailerons = roll_ailerons; + packet.pitch_elevator = pitch_elevator; + packet.yaw_rudder = yaw_rudder; + packet.throttle = throttle; + packet.aux1 = aux1; + packet.aux2 = aux2; + packet.aux3 = aux3; + packet.aux4 = aux4; + packet.mode = mode; + packet.nav_mode = nav_mode; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, 42, 63); +#endif +} + +#endif + +// MESSAGE HIL_CONTROLS UNPACKING + + +/** + * @brief Get field time_usec from hil_controls message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_hil_controls_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field roll_ailerons from hil_controls message + * + * @return Control output -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field pitch_elevator from hil_controls message + * + * @return Control output -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field yaw_rudder from hil_controls message + * + * @return Control output -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field throttle from hil_controls message + * + * @return Throttle 0 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field aux1 from hil_controls message + * + * @return Aux 1, -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_aux1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field aux2 from hil_controls message + * + * @return Aux 2, -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_aux2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field aux3 from hil_controls message + * + * @return Aux 3, -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_aux3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field aux4 from hil_controls message + * + * @return Aux 4, -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_aux4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field mode from hil_controls message + * + * @return System mode (MAV_MODE) + */ +static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 40); +} + +/** + * @brief Get field nav_mode from hil_controls message + * + * @return Navigation mode (MAV_NAV_MODE) + */ +static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 41); +} + +/** + * @brief Decode a hil_controls message into a struct + * + * @param msg The message to decode + * @param hil_controls C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t* msg, mavlink_hil_controls_t* hil_controls) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_controls->time_usec = mavlink_msg_hil_controls_get_time_usec(msg); + hil_controls->roll_ailerons = mavlink_msg_hil_controls_get_roll_ailerons(msg); + hil_controls->pitch_elevator = mavlink_msg_hil_controls_get_pitch_elevator(msg); + hil_controls->yaw_rudder = mavlink_msg_hil_controls_get_yaw_rudder(msg); + hil_controls->throttle = mavlink_msg_hil_controls_get_throttle(msg); + hil_controls->aux1 = mavlink_msg_hil_controls_get_aux1(msg); + hil_controls->aux2 = mavlink_msg_hil_controls_get_aux2(msg); + hil_controls->aux3 = mavlink_msg_hil_controls_get_aux3(msg); + hil_controls->aux4 = mavlink_msg_hil_controls_get_aux4(msg); + hil_controls->mode = mavlink_msg_hil_controls_get_mode(msg); + hil_controls->nav_mode = mavlink_msg_hil_controls_get_nav_mode(msg); +#else + memcpy(hil_controls, _MAV_PAYLOAD(msg), 42); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h new file mode 100644 index 0000000000000000000000000000000000000000..7ac0853d31871b173e092784a1063672bbc750bd --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h @@ -0,0 +1,430 @@ +// MESSAGE HIL_RC_INPUTS_RAW PACKING + +#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW 92 + +typedef struct __mavlink_hil_rc_inputs_raw_t +{ + uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + uint16_t chan1_raw; ///< RC channel 1 value, in microseconds + uint16_t chan2_raw; ///< RC channel 2 value, in microseconds + uint16_t chan3_raw; ///< RC channel 3 value, in microseconds + uint16_t chan4_raw; ///< RC channel 4 value, in microseconds + uint16_t chan5_raw; ///< RC channel 5 value, in microseconds + uint16_t chan6_raw; ///< RC channel 6 value, in microseconds + uint16_t chan7_raw; ///< RC channel 7 value, in microseconds + uint16_t chan8_raw; ///< RC channel 8 value, in microseconds + uint16_t chan9_raw; ///< RC channel 9 value, in microseconds + uint16_t chan10_raw; ///< RC channel 10 value, in microseconds + uint16_t chan11_raw; ///< RC channel 11 value, in microseconds + uint16_t chan12_raw; ///< RC channel 12 value, in microseconds + uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100% +} mavlink_hil_rc_inputs_raw_t; + +#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN 33 +#define MAVLINK_MSG_ID_92_LEN 33 + + + +#define MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW { \ + "HIL_RC_INPUTS_RAW", \ + 14, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_rc_inputs_raw_t, time_usec) }, \ + { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_hil_rc_inputs_raw_t, chan1_raw) }, \ + { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_hil_rc_inputs_raw_t, chan2_raw) }, \ + { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_hil_rc_inputs_raw_t, chan3_raw) }, \ + { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_hil_rc_inputs_raw_t, chan4_raw) }, \ + { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_hil_rc_inputs_raw_t, chan5_raw) }, \ + { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_hil_rc_inputs_raw_t, chan6_raw) }, \ + { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_rc_inputs_raw_t, chan7_raw) }, \ + { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_rc_inputs_raw_t, chan8_raw) }, \ + { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_rc_inputs_raw_t, chan9_raw) }, \ + { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_hil_rc_inputs_raw_t, chan10_raw) }, \ + { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_hil_rc_inputs_raw_t, chan11_raw) }, \ + { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_hil_rc_inputs_raw_t, chan12_raw) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_hil_rc_inputs_raw_t, rssi) }, \ + } \ +} + + +/** + * @brief Pack a hil_rc_inputs_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param chan9_raw RC channel 9 value, in microseconds + * @param chan10_raw RC channel 10 value, in microseconds + * @param chan11_raw RC channel 11 value, in microseconds + * @param chan12_raw RC channel 12 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[33]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 8, chan1_raw); + _mav_put_uint16_t(buf, 10, chan2_raw); + _mav_put_uint16_t(buf, 12, chan3_raw); + _mav_put_uint16_t(buf, 14, chan4_raw); + _mav_put_uint16_t(buf, 16, chan5_raw); + _mav_put_uint16_t(buf, 18, chan6_raw); + _mav_put_uint16_t(buf, 20, chan7_raw); + _mav_put_uint16_t(buf, 22, chan8_raw); + _mav_put_uint16_t(buf, 24, chan9_raw); + _mav_put_uint16_t(buf, 26, chan10_raw); + _mav_put_uint16_t(buf, 28, chan11_raw); + _mav_put_uint16_t(buf, 30, chan12_raw); + _mav_put_uint8_t(buf, 32, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33); +#else + mavlink_hil_rc_inputs_raw_t packet; + packet.time_usec = time_usec; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.chan9_raw = chan9_raw; + packet.chan10_raw = chan10_raw; + packet.chan11_raw = chan11_raw; + packet.chan12_raw = chan12_raw; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW; + return mavlink_finalize_message(msg, system_id, component_id, 33, 54); +} + +/** + * @brief Pack a hil_rc_inputs_raw message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param chan9_raw RC channel 9 value, in microseconds + * @param chan10_raw RC channel 10 value, in microseconds + * @param chan11_raw RC channel 11 value, in microseconds + * @param chan12_raw RC channel 12 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint16_t chan9_raw,uint16_t chan10_raw,uint16_t chan11_raw,uint16_t chan12_raw,uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[33]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 8, chan1_raw); + _mav_put_uint16_t(buf, 10, chan2_raw); + _mav_put_uint16_t(buf, 12, chan3_raw); + _mav_put_uint16_t(buf, 14, chan4_raw); + _mav_put_uint16_t(buf, 16, chan5_raw); + _mav_put_uint16_t(buf, 18, chan6_raw); + _mav_put_uint16_t(buf, 20, chan7_raw); + _mav_put_uint16_t(buf, 22, chan8_raw); + _mav_put_uint16_t(buf, 24, chan9_raw); + _mav_put_uint16_t(buf, 26, chan10_raw); + _mav_put_uint16_t(buf, 28, chan11_raw); + _mav_put_uint16_t(buf, 30, chan12_raw); + _mav_put_uint8_t(buf, 32, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33); +#else + mavlink_hil_rc_inputs_raw_t packet; + packet.time_usec = time_usec; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.chan9_raw = chan9_raw; + packet.chan10_raw = chan10_raw; + packet.chan11_raw = chan11_raw; + packet.chan12_raw = chan12_raw; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 33, 54); +} + +/** + * @brief Encode a hil_rc_inputs_raw 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 hil_rc_inputs_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) +{ + return mavlink_msg_hil_rc_inputs_raw_pack(system_id, component_id, msg, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi); +} + +/** + * @brief Send a hil_rc_inputs_raw message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param chan9_raw RC channel 9 value, in microseconds + * @param chan10_raw RC channel 10 value, in microseconds + * @param chan11_raw RC channel 11 value, in microseconds + * @param chan12_raw RC channel 12 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_rc_inputs_raw_send(mavlink_channel_t chan, uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[33]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 8, chan1_raw); + _mav_put_uint16_t(buf, 10, chan2_raw); + _mav_put_uint16_t(buf, 12, chan3_raw); + _mav_put_uint16_t(buf, 14, chan4_raw); + _mav_put_uint16_t(buf, 16, chan5_raw); + _mav_put_uint16_t(buf, 18, chan6_raw); + _mav_put_uint16_t(buf, 20, chan7_raw); + _mav_put_uint16_t(buf, 22, chan8_raw); + _mav_put_uint16_t(buf, 24, chan9_raw); + _mav_put_uint16_t(buf, 26, chan10_raw); + _mav_put_uint16_t(buf, 28, chan11_raw); + _mav_put_uint16_t(buf, 30, chan12_raw); + _mav_put_uint8_t(buf, 32, rssi); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, 33, 54); +#else + mavlink_hil_rc_inputs_raw_t packet; + packet.time_usec = time_usec; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.chan9_raw = chan9_raw; + packet.chan10_raw = chan10_raw; + packet.chan11_raw = chan11_raw; + packet.chan12_raw = chan12_raw; + packet.rssi = rssi; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)&packet, 33, 54); +#endif +} + +#endif + +// MESSAGE HIL_RC_INPUTS_RAW UNPACKING + + +/** + * @brief Get field time_usec from hil_rc_inputs_raw message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_hil_rc_inputs_raw_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field chan1_raw from hil_rc_inputs_raw message + * + * @return RC channel 1 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field chan2_raw from hil_rc_inputs_raw message + * + * @return RC channel 2 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field chan3_raw from hil_rc_inputs_raw message + * + * @return RC channel 3 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field chan4_raw from hil_rc_inputs_raw message + * + * @return RC channel 4 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Get field chan5_raw from hil_rc_inputs_raw message + * + * @return RC channel 5 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field chan6_raw from hil_rc_inputs_raw message + * + * @return RC channel 6 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field chan7_raw from hil_rc_inputs_raw message + * + * @return RC channel 7 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Get field chan8_raw from hil_rc_inputs_raw message + * + * @return RC channel 8 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field chan9_raw from hil_rc_inputs_raw message + * + * @return RC channel 9 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field chan10_raw from hil_rc_inputs_raw message + * + * @return RC channel 10 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Get field chan11_raw from hil_rc_inputs_raw message + * + * @return RC channel 11 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field chan12_raw from hil_rc_inputs_raw message + * + * @return RC channel 12 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 30); +} + +/** + * @brief Get field rssi from hil_rc_inputs_raw message + * + * @return Receive signal strength indicator, 0: 0%, 255: 100% + */ +static inline uint8_t mavlink_msg_hil_rc_inputs_raw_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Decode a hil_rc_inputs_raw message into a struct + * + * @param msg The message to decode + * @param hil_rc_inputs_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_rc_inputs_raw_decode(const mavlink_message_t* msg, mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_rc_inputs_raw->time_usec = mavlink_msg_hil_rc_inputs_raw_get_time_usec(msg); + hil_rc_inputs_raw->chan1_raw = mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(msg); + hil_rc_inputs_raw->chan2_raw = mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(msg); + hil_rc_inputs_raw->chan3_raw = mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(msg); + hil_rc_inputs_raw->chan4_raw = mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(msg); + hil_rc_inputs_raw->chan5_raw = mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(msg); + hil_rc_inputs_raw->chan6_raw = mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(msg); + hil_rc_inputs_raw->chan7_raw = mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(msg); + hil_rc_inputs_raw->chan8_raw = mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(msg); + hil_rc_inputs_raw->chan9_raw = mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(msg); + hil_rc_inputs_raw->chan10_raw = mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(msg); + hil_rc_inputs_raw->chan11_raw = mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(msg); + hil_rc_inputs_raw->chan12_raw = mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(msg); + hil_rc_inputs_raw->rssi = mavlink_msg_hil_rc_inputs_raw_get_rssi(msg); +#else + memcpy(hil_rc_inputs_raw, _MAV_PAYLOAD(msg), 33); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h new file mode 100644 index 0000000000000000000000000000000000000000..1447812956a12f273199a5289d85977bb138fcd4 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h @@ -0,0 +1,474 @@ +// MESSAGE HIL_STATE PACKING + +#define MAVLINK_MSG_ID_HIL_STATE 90 + +typedef struct __mavlink_hil_state_t +{ + uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + float roll; ///< Roll angle (rad) + float pitch; ///< Pitch angle (rad) + float yaw; ///< Yaw angle (rad) + float rollspeed; ///< Roll angular speed (rad/s) + float pitchspeed; ///< Pitch angular speed (rad/s) + float yawspeed; ///< Yaw angular speed (rad/s) + int32_t lat; ///< Latitude, expressed as * 1E7 + int32_t lon; ///< Longitude, expressed as * 1E7 + int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters) + int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100 + int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100 + int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100 + int16_t xacc; ///< X acceleration (mg) + int16_t yacc; ///< Y acceleration (mg) + int16_t zacc; ///< Z acceleration (mg) +} mavlink_hil_state_t; + +#define MAVLINK_MSG_ID_HIL_STATE_LEN 56 +#define MAVLINK_MSG_ID_90_LEN 56 + + + +#define MAVLINK_MESSAGE_INFO_HIL_STATE { \ + "HIL_STATE", \ + 16, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \ + { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \ + { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \ + { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \ + { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \ + } \ +} + + +/** + * @brief Pack a hil_state message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[56]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll); + _mav_put_float(buf, 12, pitch); + _mav_put_float(buf, 16, yaw); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_int32_t(buf, 32, lat); + _mav_put_int32_t(buf, 36, lon); + _mav_put_int32_t(buf, 40, alt); + _mav_put_int16_t(buf, 44, vx); + _mav_put_int16_t(buf, 46, vy); + _mav_put_int16_t(buf, 48, vz); + _mav_put_int16_t(buf, 50, xacc); + _mav_put_int16_t(buf, 52, yacc); + _mav_put_int16_t(buf, 54, zacc); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 56); +#else + mavlink_hil_state_t packet; + packet.time_usec = time_usec; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 56); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_STATE; + return mavlink_finalize_message(msg, system_id, component_id, 56, 183); +} + +/** + * @brief Pack a hil_state message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,int16_t xacc,int16_t yacc,int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[56]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll); + _mav_put_float(buf, 12, pitch); + _mav_put_float(buf, 16, yaw); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_int32_t(buf, 32, lat); + _mav_put_int32_t(buf, 36, lon); + _mav_put_int32_t(buf, 40, alt); + _mav_put_int16_t(buf, 44, vx); + _mav_put_int16_t(buf, 46, vy); + _mav_put_int16_t(buf, 48, vz); + _mav_put_int16_t(buf, 50, xacc); + _mav_put_int16_t(buf, 52, yacc); + _mav_put_int16_t(buf, 54, zacc); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 56); +#else + mavlink_hil_state_t packet; + packet.time_usec = time_usec; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 56); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_STATE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 56, 183); +} + +/** + * @brief Encode a hil_state 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 hil_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state) +{ + return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc); +} + +/** + * @brief Send a hil_state message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[56]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll); + _mav_put_float(buf, 12, pitch); + _mav_put_float(buf, 16, yaw); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_int32_t(buf, 32, lat); + _mav_put_int32_t(buf, 36, lon); + _mav_put_int32_t(buf, 40, alt); + _mav_put_int16_t(buf, 44, vx); + _mav_put_int16_t(buf, 46, vy); + _mav_put_int16_t(buf, 48, vz); + _mav_put_int16_t(buf, 50, xacc); + _mav_put_int16_t(buf, 52, yacc); + _mav_put_int16_t(buf, 54, zacc); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, 56, 183); +#else + mavlink_hil_state_t packet; + packet.time_usec = time_usec; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, 56, 183); +#endif +} + +#endif + +// MESSAGE HIL_STATE UNPACKING + + +/** + * @brief Get field time_usec from hil_state message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field roll from hil_state message + * + * @return Roll angle (rad) + */ +static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field pitch from hil_state message + * + * @return Pitch angle (rad) + */ +static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field yaw from hil_state message + * + * @return Yaw angle (rad) + */ +static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field rollspeed from hil_state message + * + * @return Roll angular speed (rad/s) + */ +static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitchspeed from hil_state message + * + * @return Pitch angular speed (rad/s) + */ +static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yawspeed from hil_state message + * + * @return Yaw angular speed (rad/s) + */ +static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field lat from hil_state message + * + * @return Latitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 32); +} + +/** + * @brief Get field lon from hil_state message + * + * @return Longitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 36); +} + +/** + * @brief Get field alt from hil_state message + * + * @return Altitude in meters, expressed as * 1000 (millimeters) + */ +static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 40); +} + +/** + * @brief Get field vx from hil_state message + * + * @return Ground X Speed (Latitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 44); +} + +/** + * @brief Get field vy from hil_state message + * + * @return Ground Y Speed (Longitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 46); +} + +/** + * @brief Get field vz from hil_state message + * + * @return Ground Z Speed (Altitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 48); +} + +/** + * @brief Get field xacc from hil_state message + * + * @return X acceleration (mg) + */ +static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 50); +} + +/** + * @brief Get field yacc from hil_state message + * + * @return Y acceleration (mg) + */ +static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 52); +} + +/** + * @brief Get field zacc from hil_state message + * + * @return Z acceleration (mg) + */ +static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 54); +} + +/** + * @brief Decode a hil_state message into a struct + * + * @param msg The message to decode + * @param hil_state C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, mavlink_hil_state_t* hil_state) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_state->time_usec = mavlink_msg_hil_state_get_time_usec(msg); + hil_state->roll = mavlink_msg_hil_state_get_roll(msg); + hil_state->pitch = mavlink_msg_hil_state_get_pitch(msg); + hil_state->yaw = mavlink_msg_hil_state_get_yaw(msg); + hil_state->rollspeed = mavlink_msg_hil_state_get_rollspeed(msg); + hil_state->pitchspeed = mavlink_msg_hil_state_get_pitchspeed(msg); + hil_state->yawspeed = mavlink_msg_hil_state_get_yawspeed(msg); + hil_state->lat = mavlink_msg_hil_state_get_lat(msg); + hil_state->lon = mavlink_msg_hil_state_get_lon(msg); + hil_state->alt = mavlink_msg_hil_state_get_alt(msg); + hil_state->vx = mavlink_msg_hil_state_get_vx(msg); + hil_state->vy = mavlink_msg_hil_state_get_vy(msg); + hil_state->vz = mavlink_msg_hil_state_get_vz(msg); + hil_state->xacc = mavlink_msg_hil_state_get_xacc(msg); + hil_state->yacc = mavlink_msg_hil_state_get_yacc(msg); + hil_state->zacc = mavlink_msg_hil_state_get_zacc(msg); +#else + memcpy(hil_state, _MAV_PAYLOAD(msg), 56); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h new file mode 100644 index 0000000000000000000000000000000000000000..fe0a791fc5c0449268d7b3fd81f59c07f8936e1d --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h @@ -0,0 +1,276 @@ +// MESSAGE LOCAL_POSITION_NED PACKING + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED 32 + +typedef struct __mavlink_local_position_ned_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + float x; ///< X Position + float y; ///< Y Position + float z; ///< Z Position + float vx; ///< X Speed + float vy; ///< Y Speed + float vz; ///< Z Speed +} mavlink_local_position_ned_t; + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN 28 +#define MAVLINK_MSG_ID_32_LEN 28 + + + +#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED { \ + "LOCAL_POSITION_NED", \ + 7, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_t, time_boot_ms) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_t, z) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_t, vz) }, \ + } \ +} + + +/** + * @brief Pack a local_position_ned message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); +#else + mavlink_local_position_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED; + return mavlink_finalize_message(msg, system_id, component_id, 28, 185); +} + +/** + * @brief Pack a local_position_ned message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float x,float y,float z,float vx,float vy,float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); +#else + mavlink_local_position_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 185); +} + +/** + * @brief Encode a local_position_ned 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 local_position_ned C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned) +{ + return mavlink_msg_local_position_ned_pack(system_id, component_id, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz); +} + +/** + * @brief Send a local_position_ned message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_position_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, 28, 185); +#else + mavlink_local_position_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, 28, 185); +#endif +} + +#endif + +// MESSAGE LOCAL_POSITION_NED UNPACKING + + +/** + * @brief Get field time_boot_ms from local_position_ned message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_local_position_ned_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field x from local_position_ned message + * + * @return X Position + */ +static inline float mavlink_msg_local_position_ned_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field y from local_position_ned message + * + * @return Y Position + */ +static inline float mavlink_msg_local_position_ned_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field z from local_position_ned message + * + * @return Z Position + */ +static inline float mavlink_msg_local_position_ned_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field vx from local_position_ned message + * + * @return X Speed + */ +static inline float mavlink_msg_local_position_ned_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field vy from local_position_ned message + * + * @return Y Speed + */ +static inline float mavlink_msg_local_position_ned_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vz from local_position_ned message + * + * @return Z Speed + */ +static inline float mavlink_msg_local_position_ned_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a local_position_ned message into a struct + * + * @param msg The message to decode + * @param local_position_ned C-struct to decode the message contents into + */ +static inline void mavlink_msg_local_position_ned_decode(const mavlink_message_t* msg, mavlink_local_position_ned_t* local_position_ned) +{ +#if MAVLINK_NEED_BYTE_SWAP + local_position_ned->time_boot_ms = mavlink_msg_local_position_ned_get_time_boot_ms(msg); + local_position_ned->x = mavlink_msg_local_position_ned_get_x(msg); + local_position_ned->y = mavlink_msg_local_position_ned_get_y(msg); + local_position_ned->z = mavlink_msg_local_position_ned_get_z(msg); + local_position_ned->vx = mavlink_msg_local_position_ned_get_vx(msg); + local_position_ned->vy = mavlink_msg_local_position_ned_get_vy(msg); + local_position_ned->vz = mavlink_msg_local_position_ned_get_vz(msg); +#else + memcpy(local_position_ned, _MAV_PAYLOAD(msg), 28); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h new file mode 100644 index 0000000000000000000000000000000000000000..ac1941db091323375b5b6a2759df602351804702 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h @@ -0,0 +1,276 @@ +// MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET PACKING + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET 89 + +typedef struct __mavlink_local_position_ned_system_global_offset_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + float x; ///< X Position + float y; ///< Y Position + float z; ///< Z Position + float roll; ///< Roll + float pitch; ///< Pitch + float yaw; ///< Yaw +} mavlink_local_position_ned_system_global_offset_t; + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN 28 +#define MAVLINK_MSG_ID_89_LEN 28 + + + +#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET { \ + "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET", \ + 7, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_system_global_offset_t, time_boot_ms) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_system_global_offset_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_system_global_offset_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_system_global_offset_t, z) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_system_global_offset_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_system_global_offset_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_system_global_offset_t, yaw) }, \ + } \ +} + + +/** + * @brief Pack a local_position_ned_system_global_offset message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param roll Roll + * @param pitch Pitch + * @param yaw Yaw + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); +#else + mavlink_local_position_ned_system_global_offset_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET; + return mavlink_finalize_message(msg, system_id, component_id, 28, 231); +} + +/** + * @brief Pack a local_position_ned_system_global_offset message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param roll Roll + * @param pitch Pitch + * @param yaw Yaw + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float x,float y,float z,float roll,float pitch,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); +#else + mavlink_local_position_ned_system_global_offset_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 231); +} + +/** + * @brief Encode a local_position_ned_system_global_offset 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 local_position_ned_system_global_offset C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) +{ + return mavlink_msg_local_position_ned_system_global_offset_pack(system_id, component_id, msg, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw); +} + +/** + * @brief Send a local_position_ned_system_global_offset message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param roll Roll + * @param pitch Pitch + * @param yaw Yaw + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_position_ned_system_global_offset_send(mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, 28, 231); +#else + mavlink_local_position_ned_system_global_offset_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)&packet, 28, 231); +#endif +} + +#endif + +// MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET UNPACKING + + +/** + * @brief Get field time_boot_ms from local_position_ned_system_global_offset message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field x from local_position_ned_system_global_offset message + * + * @return X Position + */ +static inline float mavlink_msg_local_position_ned_system_global_offset_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field y from local_position_ned_system_global_offset message + * + * @return Y Position + */ +static inline float mavlink_msg_local_position_ned_system_global_offset_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field z from local_position_ned_system_global_offset message + * + * @return Z Position + */ +static inline float mavlink_msg_local_position_ned_system_global_offset_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field roll from local_position_ned_system_global_offset message + * + * @return Roll + */ +static inline float mavlink_msg_local_position_ned_system_global_offset_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field pitch from local_position_ned_system_global_offset message + * + * @return Pitch + */ +static inline float mavlink_msg_local_position_ned_system_global_offset_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field yaw from local_position_ned_system_global_offset message + * + * @return Yaw + */ +static inline float mavlink_msg_local_position_ned_system_global_offset_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a local_position_ned_system_global_offset message into a struct + * + * @param msg The message to decode + * @param local_position_ned_system_global_offset C-struct to decode the message contents into + */ +static inline void mavlink_msg_local_position_ned_system_global_offset_decode(const mavlink_message_t* msg, mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) +{ +#if MAVLINK_NEED_BYTE_SWAP + local_position_ned_system_global_offset->time_boot_ms = mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms(msg); + local_position_ned_system_global_offset->x = mavlink_msg_local_position_ned_system_global_offset_get_x(msg); + local_position_ned_system_global_offset->y = mavlink_msg_local_position_ned_system_global_offset_get_y(msg); + local_position_ned_system_global_offset->z = mavlink_msg_local_position_ned_system_global_offset_get_z(msg); + local_position_ned_system_global_offset->roll = mavlink_msg_local_position_ned_system_global_offset_get_roll(msg); + local_position_ned_system_global_offset->pitch = mavlink_msg_local_position_ned_system_global_offset_get_pitch(msg); + local_position_ned_system_global_offset->yaw = mavlink_msg_local_position_ned_system_global_offset_get_yaw(msg); +#else + memcpy(local_position_ned_system_global_offset, _MAV_PAYLOAD(msg), 28); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h new file mode 100644 index 0000000000000000000000000000000000000000..9ab87d0dafc2b7f16e826fb7f9fc04ed0d52a626 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h @@ -0,0 +1,232 @@ +// MESSAGE LOCAL_POSITION_SETPOINT PACKING + +#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT 51 + +typedef struct __mavlink_local_position_setpoint_t +{ + float x; ///< x position + float y; ///< y position + float z; ///< z position + float yaw; ///< Desired yaw angle + uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU +} mavlink_local_position_setpoint_t; + +#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN 17 +#define MAVLINK_MSG_ID_51_LEN 17 + + + +#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT { \ + "LOCAL_POSITION_SETPOINT", \ + 5, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_local_position_setpoint_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_setpoint_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_setpoint_t, z) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_setpoint_t, yaw) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_local_position_setpoint_t, coordinate_frame) }, \ + } \ +} + + +/** + * @brief Pack a local_position_setpoint message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU + * @param x x position + * @param y y position + * @param z z position + * @param yaw Desired yaw angle + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t coordinate_frame, float x, float y, float z, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[17]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint8_t(buf, 16, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17); +#else + mavlink_local_position_setpoint_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; + return mavlink_finalize_message(msg, system_id, component_id, 17, 223); +} + +/** + * @brief Pack a local_position_setpoint message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU + * @param x x position + * @param y y position + * @param z z position + * @param yaw Desired yaw angle + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t coordinate_frame,float x,float y,float z,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[17]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint8_t(buf, 16, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17); +#else + mavlink_local_position_setpoint_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 17, 223); +} + +/** + * @brief Encode a local_position_setpoint struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param local_position_setpoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_setpoint_t* local_position_setpoint) +{ + return mavlink_msg_local_position_setpoint_pack(system_id, component_id, msg, local_position_setpoint->coordinate_frame, local_position_setpoint->x, local_position_setpoint->y, local_position_setpoint->z, local_position_setpoint->yaw); +} + +/** + * @brief Send a local_position_setpoint message + * @param chan MAVLink channel to send the message + * + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU + * @param x x position + * @param y y position + * @param z z position + * @param yaw Desired yaw angle + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t chan, uint8_t coordinate_frame, float x, float y, float z, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[17]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint8_t(buf, 16, coordinate_frame); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, buf, 17, 223); +#else + mavlink_local_position_setpoint_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.coordinate_frame = coordinate_frame; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, (const char *)&packet, 17, 223); +#endif +} + +#endif + +// MESSAGE LOCAL_POSITION_SETPOINT UNPACKING + + +/** + * @brief Get field coordinate_frame from local_position_setpoint message + * + * @return Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU + */ +static inline uint8_t mavlink_msg_local_position_setpoint_get_coordinate_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field x from local_position_setpoint message + * + * @return x position + */ +static inline float mavlink_msg_local_position_setpoint_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field y from local_position_setpoint message + * + * @return y position + */ +static inline float mavlink_msg_local_position_setpoint_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field z from local_position_setpoint message + * + * @return z position + */ +static inline float mavlink_msg_local_position_setpoint_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw from local_position_setpoint message + * + * @return Desired yaw angle + */ +static inline float mavlink_msg_local_position_setpoint_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a local_position_setpoint message into a struct + * + * @param msg The message to decode + * @param local_position_setpoint C-struct to decode the message contents into + */ +static inline void mavlink_msg_local_position_setpoint_decode(const mavlink_message_t* msg, mavlink_local_position_setpoint_t* local_position_setpoint) +{ +#if MAVLINK_NEED_BYTE_SWAP + local_position_setpoint->x = mavlink_msg_local_position_setpoint_get_x(msg); + local_position_setpoint->y = mavlink_msg_local_position_setpoint_get_y(msg); + local_position_setpoint->z = mavlink_msg_local_position_setpoint_get_z(msg); + local_position_setpoint->yaw = mavlink_msg_local_position_setpoint_get_yaw(msg); + local_position_setpoint->coordinate_frame = mavlink_msg_local_position_setpoint_get_coordinate_frame(msg); +#else + memcpy(local_position_setpoint, _MAV_PAYLOAD(msg), 17); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h new file mode 100644 index 0000000000000000000000000000000000000000..93adce265b546a09cd9e9a3400e9abaecc7f3b8e --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h @@ -0,0 +1,320 @@ +// MESSAGE MANUAL_CONTROL PACKING + +#define MAVLINK_MSG_ID_MANUAL_CONTROL 69 + +typedef struct __mavlink_manual_control_t +{ + float roll; ///< roll + float pitch; ///< pitch + float yaw; ///< yaw + float thrust; ///< thrust + uint8_t target; ///< The system to be controlled + uint8_t roll_manual; ///< roll control enabled auto:0, manual:1 + uint8_t pitch_manual; ///< pitch auto:0, manual:1 + uint8_t yaw_manual; ///< yaw auto:0, manual:1 + uint8_t thrust_manual; ///< thrust auto:0, manual:1 +} mavlink_manual_control_t; + +#define MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 21 +#define MAVLINK_MSG_ID_69_LEN 21 + + + +#define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \ + "MANUAL_CONTROL", \ + 9, \ + { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_manual_control_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_control_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_control_t, yaw) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_control_t, thrust) }, \ + { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_manual_control_t, target) }, \ + { "roll_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_manual_control_t, roll_manual) }, \ + { "pitch_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_manual_control_t, pitch_manual) }, \ + { "yaw_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_manual_control_t, yaw_manual) }, \ + { "thrust_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_control_t, thrust_manual) }, \ + } \ +} + + +/** + * @brief Pack a manual_control 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 target The system to be controlled + * @param roll roll + * @param pitch pitch + * @param yaw yaw + * @param thrust thrust + * @param roll_manual roll control enabled auto:0, manual:1 + * @param pitch_manual pitch auto:0, manual:1 + * @param yaw_manual yaw auto:0, manual:1 + * @param thrust_manual thrust auto:0, manual:1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[21]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target); + _mav_put_uint8_t(buf, 17, roll_manual); + _mav_put_uint8_t(buf, 18, pitch_manual); + _mav_put_uint8_t(buf, 19, yaw_manual); + _mav_put_uint8_t(buf, 20, thrust_manual); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21); +#else + mavlink_manual_control_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.target = target; + packet.roll_manual = roll_manual; + packet.pitch_manual = pitch_manual; + packet.yaw_manual = yaw_manual; + packet.thrust_manual = thrust_manual; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21); +#endif + + msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL; + return mavlink_finalize_message(msg, system_id, component_id, 21, 52); +} + +/** + * @brief Pack a manual_control 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 target The system to be controlled + * @param roll roll + * @param pitch pitch + * @param yaw yaw + * @param thrust thrust + * @param roll_manual roll control enabled auto:0, manual:1 + * @param pitch_manual pitch auto:0, manual:1 + * @param yaw_manual yaw auto:0, manual:1 + * @param thrust_manual thrust auto:0, manual:1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target,float roll,float pitch,float yaw,float thrust,uint8_t roll_manual,uint8_t pitch_manual,uint8_t yaw_manual,uint8_t thrust_manual) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[21]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target); + _mav_put_uint8_t(buf, 17, roll_manual); + _mav_put_uint8_t(buf, 18, pitch_manual); + _mav_put_uint8_t(buf, 19, yaw_manual); + _mav_put_uint8_t(buf, 20, thrust_manual); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21); +#else + mavlink_manual_control_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.target = target; + packet.roll_manual = roll_manual; + packet.pitch_manual = pitch_manual; + packet.yaw_manual = yaw_manual; + packet.thrust_manual = thrust_manual; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21); +#endif + + msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 21, 52); +} + +/** + * @brief Encode a manual_control struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param manual_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control) +{ + return mavlink_msg_manual_control_pack(system_id, component_id, msg, manual_control->target, manual_control->roll, manual_control->pitch, manual_control->yaw, manual_control->thrust, manual_control->roll_manual, manual_control->pitch_manual, manual_control->yaw_manual, manual_control->thrust_manual); +} + +/** + * @brief Send a manual_control message + * @param chan MAVLink channel to send the message + * + * @param target The system to be controlled + * @param roll roll + * @param pitch pitch + * @param yaw yaw + * @param thrust thrust + * @param roll_manual roll control enabled auto:0, manual:1 + * @param pitch_manual pitch auto:0, manual:1 + * @param yaw_manual yaw auto:0, manual:1 + * @param thrust_manual thrust auto:0, manual:1 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[21]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target); + _mav_put_uint8_t(buf, 17, roll_manual); + _mav_put_uint8_t(buf, 18, pitch_manual); + _mav_put_uint8_t(buf, 19, yaw_manual); + _mav_put_uint8_t(buf, 20, thrust_manual); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, 21, 52); +#else + mavlink_manual_control_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.target = target; + packet.roll_manual = roll_manual; + packet.pitch_manual = pitch_manual; + packet.yaw_manual = yaw_manual; + packet.thrust_manual = thrust_manual; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, 21, 52); +#endif +} + +#endif + +// MESSAGE MANUAL_CONTROL UNPACKING + + +/** + * @brief Get field target from manual_control message + * + * @return The system to be controlled + */ +static inline uint8_t mavlink_msg_manual_control_get_target(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field roll from manual_control message + * + * @return roll + */ +static inline float mavlink_msg_manual_control_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field pitch from manual_control message + * + * @return pitch + */ +static inline float mavlink_msg_manual_control_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field yaw from manual_control message + * + * @return yaw + */ +static inline float mavlink_msg_manual_control_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field thrust from manual_control message + * + * @return thrust + */ +static inline float mavlink_msg_manual_control_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field roll_manual from manual_control message + * + * @return roll control enabled auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_manual_control_get_roll_manual(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field pitch_manual from manual_control message + * + * @return pitch auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_manual_control_get_pitch_manual(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 18); +} + +/** + * @brief Get field yaw_manual from manual_control message + * + * @return yaw auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_manual_control_get_yaw_manual(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 19); +} + +/** + * @brief Get field thrust_manual from manual_control message + * + * @return thrust auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_manual_control_get_thrust_manual(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Decode a manual_control message into a struct + * + * @param msg The message to decode + * @param manual_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_manual_control_decode(const mavlink_message_t* msg, mavlink_manual_control_t* manual_control) +{ +#if MAVLINK_NEED_BYTE_SWAP + manual_control->roll = mavlink_msg_manual_control_get_roll(msg); + manual_control->pitch = mavlink_msg_manual_control_get_pitch(msg); + manual_control->yaw = mavlink_msg_manual_control_get_yaw(msg); + manual_control->thrust = mavlink_msg_manual_control_get_thrust(msg); + manual_control->target = mavlink_msg_manual_control_get_target(msg); + manual_control->roll_manual = mavlink_msg_manual_control_get_roll_manual(msg); + manual_control->pitch_manual = mavlink_msg_manual_control_get_pitch_manual(msg); + manual_control->yaw_manual = mavlink_msg_manual_control_get_yaw_manual(msg); + manual_control->thrust_manual = mavlink_msg_manual_control_get_thrust_manual(msg); +#else + memcpy(manual_control, _MAV_PAYLOAD(msg), 21); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h new file mode 100644 index 0000000000000000000000000000000000000000..a61c13019be3146d5b4a87e03dadefa19f35b5c7 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h @@ -0,0 +1,204 @@ +// MESSAGE MEMORY_VECT PACKING + +#define MAVLINK_MSG_ID_MEMORY_VECT 249 + +typedef struct __mavlink_memory_vect_t +{ + uint16_t address; ///< Starting address of the debug variables + uint8_t ver; ///< Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + uint8_t type; ///< Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + int8_t value[32]; ///< Memory contents at specified address +} mavlink_memory_vect_t; + +#define MAVLINK_MSG_ID_MEMORY_VECT_LEN 36 +#define MAVLINK_MSG_ID_249_LEN 36 + +#define MAVLINK_MSG_MEMORY_VECT_FIELD_VALUE_LEN 32 + +#define MAVLINK_MESSAGE_INFO_MEMORY_VECT { \ + "MEMORY_VECT", \ + 4, \ + { { "address", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_memory_vect_t, address) }, \ + { "ver", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_memory_vect_t, ver) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_memory_vect_t, type) }, \ + { "value", NULL, MAVLINK_TYPE_INT8_T, 32, 4, offsetof(mavlink_memory_vect_t, value) }, \ + } \ +} + + +/** + * @brief Pack a memory_vect 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 address Starting address of the debug variables + * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + * @param value Memory contents at specified address + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_memory_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_uint16_t(buf, 0, address); + _mav_put_uint8_t(buf, 2, ver); + _mav_put_uint8_t(buf, 3, type); + _mav_put_int8_t_array(buf, 4, value, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); +#else + mavlink_memory_vect_t packet; + packet.address = address; + packet.ver = ver; + packet.type = type; + mav_array_memcpy(packet.value, value, sizeof(int8_t)*32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); +#endif + + msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT; + return mavlink_finalize_message(msg, system_id, component_id, 36, 204); +} + +/** + * @brief Pack a memory_vect 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 address Starting address of the debug variables + * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + * @param value Memory contents at specified address + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_memory_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t address,uint8_t ver,uint8_t type,const int8_t *value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_uint16_t(buf, 0, address); + _mav_put_uint8_t(buf, 2, ver); + _mav_put_uint8_t(buf, 3, type); + _mav_put_int8_t_array(buf, 4, value, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); +#else + mavlink_memory_vect_t packet; + packet.address = address; + packet.ver = ver; + packet.type = type; + mav_array_memcpy(packet.value, value, sizeof(int8_t)*32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); +#endif + + msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36, 204); +} + +/** + * @brief Encode a memory_vect 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 memory_vect C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_memory_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect) +{ + return mavlink_msg_memory_vect_pack(system_id, component_id, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value); +} + +/** + * @brief Send a memory_vect message + * @param chan MAVLink channel to send the message + * + * @param address Starting address of the debug variables + * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + * @param value Memory contents at specified address + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_memory_vect_send(mavlink_channel_t chan, uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_uint16_t(buf, 0, address); + _mav_put_uint8_t(buf, 2, ver); + _mav_put_uint8_t(buf, 3, type); + _mav_put_int8_t_array(buf, 4, value, 32); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, 36, 204); +#else + mavlink_memory_vect_t packet; + packet.address = address; + packet.ver = ver; + packet.type = type; + mav_array_memcpy(packet.value, value, sizeof(int8_t)*32); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)&packet, 36, 204); +#endif +} + +#endif + +// MESSAGE MEMORY_VECT UNPACKING + + +/** + * @brief Get field address from memory_vect message + * + * @return Starting address of the debug variables + */ +static inline uint16_t mavlink_msg_memory_vect_get_address(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field ver from memory_vect message + * + * @return Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + */ +static inline uint8_t mavlink_msg_memory_vect_get_ver(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field type from memory_vect message + * + * @return Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + */ +static inline uint8_t mavlink_msg_memory_vect_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field value from memory_vect message + * + * @return Memory contents at specified address + */ +static inline uint16_t mavlink_msg_memory_vect_get_value(const mavlink_message_t* msg, int8_t *value) +{ + return _MAV_RETURN_int8_t_array(msg, value, 32, 4); +} + +/** + * @brief Decode a memory_vect message into a struct + * + * @param msg The message to decode + * @param memory_vect C-struct to decode the message contents into + */ +static inline void mavlink_msg_memory_vect_decode(const mavlink_message_t* msg, mavlink_memory_vect_t* memory_vect) +{ +#if MAVLINK_NEED_BYTE_SWAP + memory_vect->address = mavlink_msg_memory_vect_get_address(msg); + memory_vect->ver = mavlink_msg_memory_vect_get_ver(msg); + memory_vect->type = mavlink_msg_memory_vect_get_type(msg); + mavlink_msg_memory_vect_get_value(msg, memory_vect->value); +#else + memcpy(memory_vect, _MAV_PAYLOAD(msg), 36); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h new file mode 100644 index 0000000000000000000000000000000000000000..92eca79d1cb3947e3b743ca7d585d611c118a896 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h @@ -0,0 +1,188 @@ +// MESSAGE MISSION_ACK PACKING + +#define MAVLINK_MSG_ID_MISSION_ACK 47 + +typedef struct __mavlink_mission_ack_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t type; ///< See MAV_MISSION_RESULT enum +} mavlink_mission_ack_t; + +#define MAVLINK_MSG_ID_MISSION_ACK_LEN 3 +#define MAVLINK_MSG_ID_47_LEN 3 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_ACK { \ + "MISSION_ACK", \ + 3, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_ack_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_ack_t, target_component) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_ack_t, type) }, \ + } \ +} + + +/** + * @brief Pack a mission_ack 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 target_system System ID + * @param target_component Component ID + * @param type See MAV_MISSION_RESULT enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); +#else + mavlink_mission_ack_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type = type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ACK; + return mavlink_finalize_message(msg, system_id, component_id, 3, 153); +} + +/** + * @brief Pack a mission_ack 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 target_system System ID + * @param target_component Component ID + * @param type See MAV_MISSION_RESULT enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); +#else + mavlink_mission_ack_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type = type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ACK; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 153); +} + +/** + * @brief Encode a mission_ack 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 mission_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_ack_t* mission_ack) +{ + return mavlink_msg_mission_ack_pack(system_id, component_id, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type); +} + +/** + * @brief Send a mission_ack message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param type See MAV_MISSION_RESULT enum + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, type); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, 3, 153); +#else + mavlink_mission_ack_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type = type; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)&packet, 3, 153); +#endif +} + +#endif + +// MESSAGE MISSION_ACK UNPACKING + + +/** + * @brief Get field target_system from mission_ack message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_ack_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from mission_ack message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_ack_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field type from mission_ack message + * + * @return See MAV_MISSION_RESULT enum + */ +static inline uint8_t mavlink_msg_mission_ack_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Decode a mission_ack message into a struct + * + * @param msg The message to decode + * @param mission_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_ack_decode(const mavlink_message_t* msg, mavlink_mission_ack_t* mission_ack) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_ack->target_system = mavlink_msg_mission_ack_get_target_system(msg); + mission_ack->target_component = mavlink_msg_mission_ack_get_target_component(msg); + mission_ack->type = mavlink_msg_mission_ack_get_type(msg); +#else + memcpy(mission_ack, _MAV_PAYLOAD(msg), 3); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h new file mode 100644 index 0000000000000000000000000000000000000000..602852f7e32946b6ae24718745befaeaf6886aca --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h @@ -0,0 +1,166 @@ +// MESSAGE MISSION_CLEAR_ALL PACKING + +#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL 45 + +typedef struct __mavlink_mission_clear_all_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_mission_clear_all_t; + +#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN 2 +#define MAVLINK_MSG_ID_45_LEN 2 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL { \ + "MISSION_CLEAR_ALL", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_clear_all_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_clear_all_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_clear_all 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 target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_clear_all_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); +#else + mavlink_mission_clear_all_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL; + return mavlink_finalize_message(msg, system_id, component_id, 2, 232); +} + +/** + * @brief Pack a mission_clear_all 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 target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_clear_all_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); +#else + mavlink_mission_clear_all_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 232); +} + +/** + * @brief Encode a mission_clear_all 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 mission_clear_all C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_clear_all_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_clear_all_t* mission_clear_all) +{ + return mavlink_msg_mission_clear_all_pack(system_id, component_id, msg, mission_clear_all->target_system, mission_clear_all->target_component); +} + +/** + * @brief Send a mission_clear_all message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, 2, 232); +#else + mavlink_mission_clear_all_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)&packet, 2, 232); +#endif +} + +#endif + +// MESSAGE MISSION_CLEAR_ALL UNPACKING + + +/** + * @brief Get field target_system from mission_clear_all message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_clear_all_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from mission_clear_all message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_clear_all_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a mission_clear_all message into a struct + * + * @param msg The message to decode + * @param mission_clear_all C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_clear_all_decode(const mavlink_message_t* msg, mavlink_mission_clear_all_t* mission_clear_all) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_clear_all->target_system = mavlink_msg_mission_clear_all_get_target_system(msg); + mission_clear_all->target_component = mavlink_msg_mission_clear_all_get_target_component(msg); +#else + memcpy(mission_clear_all, _MAV_PAYLOAD(msg), 2); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h new file mode 100644 index 0000000000000000000000000000000000000000..61d8b221c31e17a15f06ae95f2c01f026cb08812 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h @@ -0,0 +1,188 @@ +// MESSAGE MISSION_COUNT PACKING + +#define MAVLINK_MSG_ID_MISSION_COUNT 44 + +typedef struct __mavlink_mission_count_t +{ + uint16_t count; ///< Number of mission items in the sequence + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_mission_count_t; + +#define MAVLINK_MSG_ID_MISSION_COUNT_LEN 4 +#define MAVLINK_MSG_ID_44_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \ + "MISSION_COUNT", \ + 3, \ + { { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_count 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 target_system System ID + * @param target_component Component ID + * @param count Number of mission items in the sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, count); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); +#else + mavlink_mission_count_t packet; + packet.count = count; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT; + return mavlink_finalize_message(msg, system_id, component_id, 4, 221); +} + +/** + * @brief Pack a mission_count 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 target_system System ID + * @param target_component Component ID + * @param count Number of mission items in the sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_count_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, count); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); +#else + mavlink_mission_count_t packet; + packet.count = count; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 221); +} + +/** + * @brief Encode a mission_count 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 mission_count C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count) +{ + return mavlink_msg_mission_count_pack(system_id, component_id, msg, mission_count->target_system, mission_count->target_component, mission_count->count); +} + +/** + * @brief Send a mission_count message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param count Number of mission items in the sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, count); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, 4, 221); +#else + mavlink_mission_count_t packet; + packet.count = count; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, 4, 221); +#endif +} + +#endif + +// MESSAGE MISSION_COUNT UNPACKING + + +/** + * @brief Get field target_system from mission_count message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_count_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from mission_count message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_count_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field count from mission_count message + * + * @return Number of mission items in the sequence + */ +static inline uint16_t mavlink_msg_mission_count_get_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_count message into a struct + * + * @param msg The message to decode + * @param mission_count C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_count_decode(const mavlink_message_t* msg, mavlink_mission_count_t* mission_count) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_count->count = mavlink_msg_mission_count_get_count(msg); + mission_count->target_system = mavlink_msg_mission_count_get_target_system(msg); + mission_count->target_component = mavlink_msg_mission_count_get_target_component(msg); +#else + memcpy(mission_count, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h new file mode 100644 index 0000000000000000000000000000000000000000..99370f83532bec328537f62bf72c327af6478d23 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h @@ -0,0 +1,144 @@ +// MESSAGE MISSION_CURRENT PACKING + +#define MAVLINK_MSG_ID_MISSION_CURRENT 42 + +typedef struct __mavlink_mission_current_t +{ + uint16_t seq; ///< Sequence +} mavlink_mission_current_t; + +#define MAVLINK_MSG_ID_MISSION_CURRENT_LEN 2 +#define MAVLINK_MSG_ID_42_LEN 2 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_CURRENT { \ + "MISSION_CURRENT", \ + 1, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_current_t, seq) }, \ + } \ +} + + +/** + * @brief Pack a mission_current 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 seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); +#else + mavlink_mission_current_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT; + return mavlink_finalize_message(msg, system_id, component_id, 2, 28); +} + +/** + * @brief Pack a mission_current 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 seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); +#else + mavlink_mission_current_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 28); +} + +/** + * @brief Encode a mission_current 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 mission_current C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current) +{ + return mavlink_msg_mission_current_pack(system_id, component_id, msg, mission_current->seq); +} + +/** + * @brief Send a mission_current message + * @param chan MAVLink channel to send the message + * + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_current_send(mavlink_channel_t chan, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint16_t(buf, 0, seq); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, 2, 28); +#else + mavlink_mission_current_t packet; + packet.seq = seq; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, 2, 28); +#endif +} + +#endif + +// MESSAGE MISSION_CURRENT UNPACKING + + +/** + * @brief Get field seq from mission_current message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_current_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_current message into a struct + * + * @param msg The message to decode + * @param mission_current C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_current_decode(const mavlink_message_t* msg, mavlink_mission_current_t* mission_current) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_current->seq = mavlink_msg_mission_current_get_seq(msg); +#else + memcpy(mission_current, _MAV_PAYLOAD(msg), 2); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h new file mode 100644 index 0000000000000000000000000000000000000000..d2c66d4daa293777c7732be1476014457ec7421d --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h @@ -0,0 +1,430 @@ +// MESSAGE MISSION_ITEM PACKING + +#define MAVLINK_MSG_ID_MISSION_ITEM 39 + +typedef struct __mavlink_mission_item_t +{ + float param1; ///< PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters + float param2; ///< PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + float param3; ///< PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + float param4; ///< PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH + float x; ///< PARAM5 / local: x position, global: latitude + float y; ///< PARAM6 / y position: global: longitude + float z; ///< PARAM7 / z position: global: altitude + uint16_t seq; ///< Sequence + uint16_t command; ///< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t frame; ///< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + uint8_t current; ///< false:0, true:1 + uint8_t autocontinue; ///< autocontinue to next wp +} mavlink_mission_item_t; + +#define MAVLINK_MSG_ID_MISSION_ITEM_LEN 37 +#define MAVLINK_MSG_ID_39_LEN 37 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_ITEM { \ + "MISSION_ITEM", \ + 14, \ + { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \ + { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_t, param2) }, \ + { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_t, param3) }, \ + { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_t, param4) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mission_item_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mission_item_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_t, z) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \ + { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \ + { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \ + } \ +} + + +/** + * @brief Pack a mission_item 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 target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters + * @param param2 PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + * @param param3 PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + * @param param4 PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH + * @param x PARAM5 / local: x position, global: latitude + * @param y PARAM6 / y position: global: longitude + * @param z PARAM7 / z position: global: altitude + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[37]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, x); + _mav_put_float(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 37); +#else + mavlink_mission_item_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 37); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM; + return mavlink_finalize_message(msg, system_id, component_id, 37, 254); +} + +/** + * @brief Pack a mission_item 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 target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters + * @param param2 PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + * @param param3 PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + * @param param4 PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH + * @param x PARAM5 / local: x position, global: latitude + * @param y PARAM6 / y position: global: longitude + * @param z PARAM7 / z position: global: altitude + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,float x,float y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[37]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, x); + _mav_put_float(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 37); +#else + mavlink_mission_item_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 37); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 37, 254); +} + +/** + * @brief Encode a mission_item 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 mission_item C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_item_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item) +{ + return mavlink_msg_mission_item_pack(system_id, component_id, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z); +} + +/** + * @brief Send a mission_item message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters + * @param param2 PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + * @param param3 PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + * @param param4 PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH + * @param x PARAM5 / local: x position, global: latitude + * @param y PARAM6 / y position: global: longitude + * @param z PARAM7 / z position: global: altitude + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_item_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[37]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, x); + _mav_put_float(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, 37, 254); +#else + mavlink_mission_item_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, 37, 254); +#endif +} + +#endif + +// MESSAGE MISSION_ITEM UNPACKING + + +/** + * @brief Get field target_system from mission_item message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_item_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field target_component from mission_item message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_item_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field seq from mission_item message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_item_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field frame from mission_item message + * + * @return The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + */ +static inline uint8_t mavlink_msg_mission_item_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field command from mission_item message + * + * @return The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + */ +static inline uint16_t mavlink_msg_mission_item_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 30); +} + +/** + * @brief Get field current from mission_item message + * + * @return false:0, true:1 + */ +static inline uint8_t mavlink_msg_mission_item_get_current(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 35); +} + +/** + * @brief Get field autocontinue from mission_item message + * + * @return autocontinue to next wp + */ +static inline uint8_t mavlink_msg_mission_item_get_autocontinue(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 36); +} + +/** + * @brief Get field param1 from mission_item message + * + * @return PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters + */ +static inline float mavlink_msg_mission_item_get_param1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param2 from mission_item message + * + * @return PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + */ +static inline float mavlink_msg_mission_item_get_param2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field param3 from mission_item message + * + * @return PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + */ +static inline float mavlink_msg_mission_item_get_param3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field param4 from mission_item message + * + * @return PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH + */ +static inline float mavlink_msg_mission_item_get_param4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field x from mission_item message + * + * @return PARAM5 / local: x position, global: latitude + */ +static inline float mavlink_msg_mission_item_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field y from mission_item message + * + * @return PARAM6 / y position: global: longitude + */ +static inline float mavlink_msg_mission_item_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field z from mission_item message + * + * @return PARAM7 / z position: global: altitude + */ +static inline float mavlink_msg_mission_item_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a mission_item message into a struct + * + * @param msg The message to decode + * @param mission_item C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_item_decode(const mavlink_message_t* msg, mavlink_mission_item_t* mission_item) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_item->param1 = mavlink_msg_mission_item_get_param1(msg); + mission_item->param2 = mavlink_msg_mission_item_get_param2(msg); + mission_item->param3 = mavlink_msg_mission_item_get_param3(msg); + mission_item->param4 = mavlink_msg_mission_item_get_param4(msg); + mission_item->x = mavlink_msg_mission_item_get_x(msg); + mission_item->y = mavlink_msg_mission_item_get_y(msg); + mission_item->z = mavlink_msg_mission_item_get_z(msg); + mission_item->seq = mavlink_msg_mission_item_get_seq(msg); + mission_item->command = mavlink_msg_mission_item_get_command(msg); + mission_item->target_system = mavlink_msg_mission_item_get_target_system(msg); + mission_item->target_component = mavlink_msg_mission_item_get_target_component(msg); + mission_item->frame = mavlink_msg_mission_item_get_frame(msg); + mission_item->current = mavlink_msg_mission_item_get_current(msg); + mission_item->autocontinue = mavlink_msg_mission_item_get_autocontinue(msg); +#else + memcpy(mission_item, _MAV_PAYLOAD(msg), 37); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h new file mode 100644 index 0000000000000000000000000000000000000000..171f9857e8257c9b3b4ffec67e9a52aa0b006d38 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h @@ -0,0 +1,144 @@ +// MESSAGE MISSION_ITEM_REACHED PACKING + +#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED 46 + +typedef struct __mavlink_mission_item_reached_t +{ + uint16_t seq; ///< Sequence +} mavlink_mission_item_reached_t; + +#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN 2 +#define MAVLINK_MSG_ID_46_LEN 2 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED { \ + "MISSION_ITEM_REACHED", \ + 1, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_item_reached_t, seq) }, \ + } \ +} + + +/** + * @brief Pack a mission_item_reached 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 seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_reached_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); +#else + mavlink_mission_item_reached_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_REACHED; + return mavlink_finalize_message(msg, system_id, component_id, 2, 11); +} + +/** + * @brief Pack a mission_item_reached 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 seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_reached_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); +#else + mavlink_mission_item_reached_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_REACHED; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 11); +} + +/** + * @brief Encode a mission_item_reached 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 mission_item_reached C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_item_reached_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_reached_t* mission_item_reached) +{ + return mavlink_msg_mission_item_reached_pack(system_id, component_id, msg, mission_item_reached->seq); +} + +/** + * @brief Send a mission_item_reached message + * @param chan MAVLink channel to send the message + * + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_item_reached_send(mavlink_channel_t chan, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint16_t(buf, 0, seq); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, 2, 11); +#else + mavlink_mission_item_reached_t packet; + packet.seq = seq; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)&packet, 2, 11); +#endif +} + +#endif + +// MESSAGE MISSION_ITEM_REACHED UNPACKING + + +/** + * @brief Get field seq from mission_item_reached message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_item_reached_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_item_reached message into a struct + * + * @param msg The message to decode + * @param mission_item_reached C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_item_reached_decode(const mavlink_message_t* msg, mavlink_mission_item_reached_t* mission_item_reached) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_item_reached->seq = mavlink_msg_mission_item_reached_get_seq(msg); +#else + memcpy(mission_item_reached, _MAV_PAYLOAD(msg), 2); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h new file mode 100644 index 0000000000000000000000000000000000000000..cde0a0cfb9b6b6d2967c8b5b200ec914106323e1 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h @@ -0,0 +1,188 @@ +// MESSAGE MISSION_REQUEST PACKING + +#define MAVLINK_MSG_ID_MISSION_REQUEST 40 + +typedef struct __mavlink_mission_request_t +{ + uint16_t seq; ///< Sequence + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_mission_request_t; + +#define MAVLINK_MSG_ID_MISSION_REQUEST_LEN 4 +#define MAVLINK_MSG_ID_40_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \ + "MISSION_REQUEST", \ + 3, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_request 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 target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); +#else + mavlink_mission_request_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST; + return mavlink_finalize_message(msg, system_id, component_id, 4, 230); +} + +/** + * @brief Pack a mission_request 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 target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); +#else + mavlink_mission_request_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 230); +} + +/** + * @brief Encode a mission_request 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 mission_request C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request) +{ + return mavlink_msg_mission_request_pack(system_id, component_id, msg, mission_request->target_system, mission_request->target_component, mission_request->seq); +} + +/** + * @brief Send a mission_request message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, 4, 230); +#else + mavlink_mission_request_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, 4, 230); +#endif +} + +#endif + +// MESSAGE MISSION_REQUEST UNPACKING + + +/** + * @brief Get field target_system from mission_request message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_request_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from mission_request message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_request_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field seq from mission_request message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_request_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_request message into a struct + * + * @param msg The message to decode + * @param mission_request C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_request_decode(const mavlink_message_t* msg, mavlink_mission_request_t* mission_request) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_request->seq = mavlink_msg_mission_request_get_seq(msg); + mission_request->target_system = mavlink_msg_mission_request_get_target_system(msg); + mission_request->target_component = mavlink_msg_mission_request_get_target_component(msg); +#else + memcpy(mission_request, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h new file mode 100644 index 0000000000000000000000000000000000000000..1ada635b557cac3520c0d2447d638a9e9c88eb3b --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h @@ -0,0 +1,166 @@ +// MESSAGE MISSION_REQUEST_LIST PACKING + +#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST 43 + +typedef struct __mavlink_mission_request_list_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_mission_request_list_t; + +#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN 2 +#define MAVLINK_MSG_ID_43_LEN 2 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST { \ + "MISSION_REQUEST_LIST", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_request_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_request_list_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_request_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); +#else + mavlink_mission_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_LIST; + return mavlink_finalize_message(msg, system_id, component_id, 2, 132); +} + +/** + * @brief Pack a mission_request_list message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); +#else + mavlink_mission_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_LIST; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 132); +} + +/** + * @brief Encode a mission_request_list struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_list_t* mission_request_list) +{ + return mavlink_msg_mission_request_list_pack(system_id, component_id, msg, mission_request_list->target_system, mission_request_list->target_component); +} + +/** + * @brief Send a mission_request_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, 2, 132); +#else + mavlink_mission_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)&packet, 2, 132); +#endif +} + +#endif + +// MESSAGE MISSION_REQUEST_LIST UNPACKING + + +/** + * @brief Get field target_system from mission_request_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_request_list_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from mission_request_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_request_list_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a mission_request_list message into a struct + * + * @param msg The message to decode + * @param mission_request_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_request_list_decode(const mavlink_message_t* msg, mavlink_mission_request_list_t* mission_request_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_request_list->target_system = mavlink_msg_mission_request_list_get_target_system(msg); + mission_request_list->target_component = mavlink_msg_mission_request_list_get_target_component(msg); +#else + memcpy(mission_request_list, _MAV_PAYLOAD(msg), 2); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h new file mode 100644 index 0000000000000000000000000000000000000000..76fd43befad147174cece9d8968ce33d0d29c0b5 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h @@ -0,0 +1,210 @@ +// MESSAGE MISSION_REQUEST_PARTIAL_LIST PACKING + +#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST 37 + +typedef struct __mavlink_mission_request_partial_list_t +{ + int16_t start_index; ///< Start index, 0 by default + int16_t end_index; ///< End index, -1 by default (-1: send list to end). Else a valid index of the list + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_mission_request_partial_list_t; + +#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN 6 +#define MAVLINK_MSG_ID_37_LEN 6 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST { \ + "MISSION_REQUEST_PARTIAL_LIST", \ + 4, \ + { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \ + { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_request_partial_list_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_request_partial_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index, 0 by default + * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); +#else + mavlink_mission_request_partial_list_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST; + return mavlink_finalize_message(msg, system_id, component_id, 6, 212); +} + +/** + * @brief Pack a mission_request_partial_list message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index, 0 by default + * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_partial_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,int16_t start_index,int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); +#else + mavlink_mission_request_partial_list_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 212); +} + +/** + * @brief Encode a mission_request_partial_list struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_request_partial_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_partial_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_partial_list_t* mission_request_partial_list) +{ + return mavlink_msg_mission_request_partial_list_pack(system_id, component_id, msg, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index); +} + +/** + * @brief Send a mission_request_partial_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index, 0 by default + * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_request_partial_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, 6, 212); +#else + mavlink_mission_request_partial_list_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)&packet, 6, 212); +#endif +} + +#endif + +// MESSAGE MISSION_REQUEST_PARTIAL_LIST UNPACKING + + +/** + * @brief Get field target_system from mission_request_partial_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field target_component from mission_request_partial_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field start_index from mission_request_partial_list message + * + * @return Start index, 0 by default + */ +static inline int16_t mavlink_msg_mission_request_partial_list_get_start_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 0); +} + +/** + * @brief Get field end_index from mission_request_partial_list message + * + * @return End index, -1 by default (-1: send list to end). Else a valid index of the list + */ +static inline int16_t mavlink_msg_mission_request_partial_list_get_end_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 2); +} + +/** + * @brief Decode a mission_request_partial_list message into a struct + * + * @param msg The message to decode + * @param mission_request_partial_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_request_partial_list_decode(const mavlink_message_t* msg, mavlink_mission_request_partial_list_t* mission_request_partial_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_request_partial_list->start_index = mavlink_msg_mission_request_partial_list_get_start_index(msg); + mission_request_partial_list->end_index = mavlink_msg_mission_request_partial_list_get_end_index(msg); + mission_request_partial_list->target_system = mavlink_msg_mission_request_partial_list_get_target_system(msg); + mission_request_partial_list->target_component = mavlink_msg_mission_request_partial_list_get_target_component(msg); +#else + memcpy(mission_request_partial_list, _MAV_PAYLOAD(msg), 6); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h new file mode 100644 index 0000000000000000000000000000000000000000..de0dbcd75df3b3dd029eab93d34eae24be90b882 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h @@ -0,0 +1,188 @@ +// MESSAGE MISSION_SET_CURRENT PACKING + +#define MAVLINK_MSG_ID_MISSION_SET_CURRENT 41 + +typedef struct __mavlink_mission_set_current_t +{ + uint16_t seq; ///< Sequence + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_mission_set_current_t; + +#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN 4 +#define MAVLINK_MSG_ID_41_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT { \ + "MISSION_SET_CURRENT", \ + 3, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_set_current_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_set_current 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 target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_set_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); +#else + mavlink_mission_set_current_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_SET_CURRENT; + return mavlink_finalize_message(msg, system_id, component_id, 4, 28); +} + +/** + * @brief Pack a mission_set_current 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 target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_set_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); +#else + mavlink_mission_set_current_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_SET_CURRENT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 28); +} + +/** + * @brief Encode a mission_set_current 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 mission_set_current C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_set_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_set_current_t* mission_set_current) +{ + return mavlink_msg_mission_set_current_pack(system_id, component_id, msg, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq); +} + +/** + * @brief Send a mission_set_current message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_set_current_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, 4, 28); +#else + mavlink_mission_set_current_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)&packet, 4, 28); +#endif +} + +#endif + +// MESSAGE MISSION_SET_CURRENT UNPACKING + + +/** + * @brief Get field target_system from mission_set_current message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_set_current_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from mission_set_current message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_set_current_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field seq from mission_set_current message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_set_current_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_set_current message into a struct + * + * @param msg The message to decode + * @param mission_set_current C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_set_current_decode(const mavlink_message_t* msg, mavlink_mission_set_current_t* mission_set_current) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_set_current->seq = mavlink_msg_mission_set_current_get_seq(msg); + mission_set_current->target_system = mavlink_msg_mission_set_current_get_target_system(msg); + mission_set_current->target_component = mavlink_msg_mission_set_current_get_target_component(msg); +#else + memcpy(mission_set_current, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h new file mode 100644 index 0000000000000000000000000000000000000000..0e77569cfc3aecc3b0de720459d8ba94359386ac --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h @@ -0,0 +1,210 @@ +// MESSAGE MISSION_WRITE_PARTIAL_LIST PACKING + +#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST 38 + +typedef struct __mavlink_mission_write_partial_list_t +{ + int16_t start_index; ///< Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + int16_t end_index; ///< End index, equal or greater than start index. + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_mission_write_partial_list_t; + +#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN 6 +#define MAVLINK_MSG_ID_38_LEN 6 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST { \ + "MISSION_WRITE_PARTIAL_LIST", \ + 4, \ + { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \ + { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_write_partial_list_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_write_partial_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + * @param end_index End index, equal or greater than start index. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_write_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); +#else + mavlink_mission_write_partial_list_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST; + return mavlink_finalize_message(msg, system_id, component_id, 6, 9); +} + +/** + * @brief Pack a mission_write_partial_list message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + * @param end_index End index, equal or greater than start index. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_write_partial_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,int16_t start_index,int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); +#else + mavlink_mission_write_partial_list_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 9); +} + +/** + * @brief Encode a mission_write_partial_list struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_write_partial_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_write_partial_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_write_partial_list_t* mission_write_partial_list) +{ + return mavlink_msg_mission_write_partial_list_pack(system_id, component_id, msg, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index); +} + +/** + * @brief Send a mission_write_partial_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + * @param end_index End index, equal or greater than start index. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_write_partial_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, 6, 9); +#else + mavlink_mission_write_partial_list_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)&packet, 6, 9); +#endif +} + +#endif + +// MESSAGE MISSION_WRITE_PARTIAL_LIST UNPACKING + + +/** + * @brief Get field target_system from mission_write_partial_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field target_component from mission_write_partial_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field start_index from mission_write_partial_list message + * + * @return Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + */ +static inline int16_t mavlink_msg_mission_write_partial_list_get_start_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 0); +} + +/** + * @brief Get field end_index from mission_write_partial_list message + * + * @return End index, equal or greater than start index. + */ +static inline int16_t mavlink_msg_mission_write_partial_list_get_end_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 2); +} + +/** + * @brief Decode a mission_write_partial_list message into a struct + * + * @param msg The message to decode + * @param mission_write_partial_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_write_partial_list_decode(const mavlink_message_t* msg, mavlink_mission_write_partial_list_t* mission_write_partial_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_write_partial_list->start_index = mavlink_msg_mission_write_partial_list_get_start_index(msg); + mission_write_partial_list->end_index = mavlink_msg_mission_write_partial_list_get_end_index(msg); + mission_write_partial_list->target_system = mavlink_msg_mission_write_partial_list_get_target_system(msg); + mission_write_partial_list->target_component = mavlink_msg_mission_write_partial_list_get_target_component(msg); +#else + memcpy(mission_write_partial_list, _MAV_PAYLOAD(msg), 6); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h new file mode 100644 index 0000000000000000000000000000000000000000..23a819e2c9b708ba1c4d004d8902edc1d155b121 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h @@ -0,0 +1,182 @@ +// MESSAGE NAMED_VALUE_FLOAT PACKING + +#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 251 + +typedef struct __mavlink_named_value_float_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + float value; ///< Floating point value + char name[10]; ///< Name of the debug variable +} mavlink_named_value_float_t; + +#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18 +#define MAVLINK_MSG_ID_251_LEN 18 + +#define MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN 10 + +#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \ + "NAMED_VALUE_FLOAT", \ + 3, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \ + { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \ + } \ +} + + +/** + * @brief Pack a named_value_float message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Floating point value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, const char *name, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); +#else + mavlink_named_value_float_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; + return mavlink_finalize_message(msg, system_id, component_id, 18, 170); +} + +/** + * @brief Pack a named_value_float message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Floating point value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,const char *name,float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); +#else + mavlink_named_value_float_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 170); +} + +/** + * @brief Encode a named_value_float 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 named_value_float C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_named_value_float_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float) +{ + return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value); +} + +/** + * @brief Send a named_value_float message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Floating point value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, 18, 170); +#else + mavlink_named_value_float_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, 18, 170); +#endif +} + +#endif + +// MESSAGE NAMED_VALUE_FLOAT UNPACKING + + +/** + * @brief Get field time_boot_ms from named_value_float message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_named_value_float_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field name from named_value_float message + * + * @return Name of the debug variable + */ +static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_message_t* msg, char *name) +{ + return _MAV_RETURN_char_array(msg, name, 10, 8); +} + +/** + * @brief Get field value from named_value_float message + * + * @return Floating point value + */ +static inline float mavlink_msg_named_value_float_get_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Decode a named_value_float message into a struct + * + * @param msg The message to decode + * @param named_value_float C-struct to decode the message contents into + */ +static inline void mavlink_msg_named_value_float_decode(const mavlink_message_t* msg, mavlink_named_value_float_t* named_value_float) +{ +#if MAVLINK_NEED_BYTE_SWAP + named_value_float->time_boot_ms = mavlink_msg_named_value_float_get_time_boot_ms(msg); + named_value_float->value = mavlink_msg_named_value_float_get_value(msg); + mavlink_msg_named_value_float_get_name(msg, named_value_float->name); +#else + memcpy(named_value_float, _MAV_PAYLOAD(msg), 18); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h new file mode 100644 index 0000000000000000000000000000000000000000..3c67dff03fcbab7f855653fc23327d273dbca91f --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h @@ -0,0 +1,182 @@ +// MESSAGE NAMED_VALUE_INT PACKING + +#define MAVLINK_MSG_ID_NAMED_VALUE_INT 252 + +typedef struct __mavlink_named_value_int_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + int32_t value; ///< Signed integer value + char name[10]; ///< Name of the debug variable +} mavlink_named_value_int_t; + +#define MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 18 +#define MAVLINK_MSG_ID_252_LEN 18 + +#define MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN 10 + +#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT { \ + "NAMED_VALUE_INT", \ + 3, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \ + { "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \ + } \ +} + + +/** + * @brief Pack a named_value_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Signed integer value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, const char *name, int32_t value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); +#else + mavlink_named_value_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT; + return mavlink_finalize_message(msg, system_id, component_id, 18, 44); +} + +/** + * @brief Pack a named_value_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Signed integer value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,const char *name,int32_t value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); +#else + mavlink_named_value_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 44); +} + +/** + * @brief Encode a named_value_int 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 named_value_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_named_value_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int) +{ + return mavlink_msg_named_value_int_pack(system_id, component_id, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value); +} + +/** + * @brief Send a named_value_int message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Signed integer value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_named_value_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, int32_t value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, 18, 44); +#else + mavlink_named_value_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)&packet, 18, 44); +#endif +} + +#endif + +// MESSAGE NAMED_VALUE_INT UNPACKING + + +/** + * @brief Get field time_boot_ms from named_value_int message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_named_value_int_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field name from named_value_int message + * + * @return Name of the debug variable + */ +static inline uint16_t mavlink_msg_named_value_int_get_name(const mavlink_message_t* msg, char *name) +{ + return _MAV_RETURN_char_array(msg, name, 10, 8); +} + +/** + * @brief Get field value from named_value_int message + * + * @return Signed integer value + */ +static inline int32_t mavlink_msg_named_value_int_get_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Decode a named_value_int message into a struct + * + * @param msg The message to decode + * @param named_value_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_named_value_int_decode(const mavlink_message_t* msg, mavlink_named_value_int_t* named_value_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + named_value_int->time_boot_ms = mavlink_msg_named_value_int_get_time_boot_ms(msg); + named_value_int->value = mavlink_msg_named_value_int_get_value(msg); + mavlink_msg_named_value_int_get_name(msg, named_value_int->name); +#else + memcpy(named_value_int, _MAV_PAYLOAD(msg), 18); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h new file mode 100644 index 0000000000000000000000000000000000000000..028afdabc62203d7d0e7427ef6e093c1b7088741 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h @@ -0,0 +1,298 @@ +// MESSAGE NAV_CONTROLLER_OUTPUT PACKING + +#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62 + +typedef struct __mavlink_nav_controller_output_t +{ + float nav_roll; ///< Current desired roll in degrees + float nav_pitch; ///< Current desired pitch in degrees + float alt_error; ///< Current altitude error in meters + float aspd_error; ///< Current airspeed error in meters/second + float xtrack_error; ///< Current crosstrack error on x-y plane in meters + int16_t nav_bearing; ///< Current desired heading in degrees + int16_t target_bearing; ///< Bearing to current MISSION/target in degrees + uint16_t wp_dist; ///< Distance to active MISSION in meters +} mavlink_nav_controller_output_t; + +#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26 +#define MAVLINK_MSG_ID_62_LEN 26 + + + +#define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \ + "NAV_CONTROLLER_OUTPUT", \ + 8, \ + { { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \ + { "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \ + { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ + { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ + { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ + { "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \ + { "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \ + { "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \ + } \ +} + + +/** + * @brief Pack a nav_controller_output 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 nav_roll Current desired roll in degrees + * @param nav_pitch Current desired pitch in degrees + * @param nav_bearing Current desired heading in degrees + * @param target_bearing Bearing to current MISSION/target in degrees + * @param wp_dist Distance to active MISSION in meters + * @param alt_error Current altitude error in meters + * @param aspd_error Current airspeed error in meters/second + * @param xtrack_error Current crosstrack error on x-y plane in meters + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[26]; + _mav_put_float(buf, 0, nav_roll); + _mav_put_float(buf, 4, nav_pitch); + _mav_put_float(buf, 8, alt_error); + _mav_put_float(buf, 12, aspd_error); + _mav_put_float(buf, 16, xtrack_error); + _mav_put_int16_t(buf, 20, nav_bearing); + _mav_put_int16_t(buf, 22, target_bearing); + _mav_put_uint16_t(buf, 24, wp_dist); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); +#else + mavlink_nav_controller_output_t packet; + packet.nav_roll = nav_roll; + packet.nav_pitch = nav_pitch; + packet.alt_error = alt_error; + packet.aspd_error = aspd_error; + packet.xtrack_error = xtrack_error; + packet.nav_bearing = nav_bearing; + packet.target_bearing = target_bearing; + packet.wp_dist = wp_dist; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; + return mavlink_finalize_message(msg, system_id, component_id, 26, 183); +} + +/** + * @brief Pack a nav_controller_output 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 nav_roll Current desired roll in degrees + * @param nav_pitch Current desired pitch in degrees + * @param nav_bearing Current desired heading in degrees + * @param target_bearing Bearing to current MISSION/target in degrees + * @param wp_dist Distance to active MISSION in meters + * @param alt_error Current altitude error in meters + * @param aspd_error Current airspeed error in meters/second + * @param xtrack_error Current crosstrack error on x-y plane in meters + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float nav_roll,float nav_pitch,int16_t nav_bearing,int16_t target_bearing,uint16_t wp_dist,float alt_error,float aspd_error,float xtrack_error) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[26]; + _mav_put_float(buf, 0, nav_roll); + _mav_put_float(buf, 4, nav_pitch); + _mav_put_float(buf, 8, alt_error); + _mav_put_float(buf, 12, aspd_error); + _mav_put_float(buf, 16, xtrack_error); + _mav_put_int16_t(buf, 20, nav_bearing); + _mav_put_int16_t(buf, 22, target_bearing); + _mav_put_uint16_t(buf, 24, wp_dist); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); +#else + mavlink_nav_controller_output_t packet; + packet.nav_roll = nav_roll; + packet.nav_pitch = nav_pitch; + packet.alt_error = alt_error; + packet.aspd_error = aspd_error; + packet.xtrack_error = xtrack_error; + packet.nav_bearing = nav_bearing; + packet.target_bearing = target_bearing; + packet.wp_dist = wp_dist; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26, 183); +} + +/** + * @brief Encode a nav_controller_output 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 nav_controller_output C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output) +{ + return mavlink_msg_nav_controller_output_pack(system_id, component_id, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); +} + +/** + * @brief Send a nav_controller_output message + * @param chan MAVLink channel to send the message + * + * @param nav_roll Current desired roll in degrees + * @param nav_pitch Current desired pitch in degrees + * @param nav_bearing Current desired heading in degrees + * @param target_bearing Bearing to current MISSION/target in degrees + * @param wp_dist Distance to active MISSION in meters + * @param alt_error Current altitude error in meters + * @param aspd_error Current airspeed error in meters/second + * @param xtrack_error Current crosstrack error on x-y plane in meters + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_nav_controller_output_send(mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[26]; + _mav_put_float(buf, 0, nav_roll); + _mav_put_float(buf, 4, nav_pitch); + _mav_put_float(buf, 8, alt_error); + _mav_put_float(buf, 12, aspd_error); + _mav_put_float(buf, 16, xtrack_error); + _mav_put_int16_t(buf, 20, nav_bearing); + _mav_put_int16_t(buf, 22, target_bearing); + _mav_put_uint16_t(buf, 24, wp_dist); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, 26, 183); +#else + mavlink_nav_controller_output_t packet; + packet.nav_roll = nav_roll; + packet.nav_pitch = nav_pitch; + packet.alt_error = alt_error; + packet.aspd_error = aspd_error; + packet.xtrack_error = xtrack_error; + packet.nav_bearing = nav_bearing; + packet.target_bearing = target_bearing; + packet.wp_dist = wp_dist; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, 26, 183); +#endif +} + +#endif + +// MESSAGE NAV_CONTROLLER_OUTPUT UNPACKING + + +/** + * @brief Get field nav_roll from nav_controller_output message + * + * @return Current desired roll in degrees + */ +static inline float mavlink_msg_nav_controller_output_get_nav_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field nav_pitch from nav_controller_output message + * + * @return Current desired pitch in degrees + */ +static inline float mavlink_msg_nav_controller_output_get_nav_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field nav_bearing from nav_controller_output message + * + * @return Current desired heading in degrees + */ +static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Get field target_bearing from nav_controller_output message + * + * @return Bearing to current MISSION/target in degrees + */ +static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 22); +} + +/** + * @brief Get field wp_dist from nav_controller_output message + * + * @return Distance to active MISSION in meters + */ +static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field alt_error from nav_controller_output message + * + * @return Current altitude error in meters + */ +static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field aspd_error from nav_controller_output message + * + * @return Current airspeed error in meters/second + */ +static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field xtrack_error from nav_controller_output message + * + * @return Current crosstrack error on x-y plane in meters + */ +static inline float mavlink_msg_nav_controller_output_get_xtrack_error(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a nav_controller_output message into a struct + * + * @param msg The message to decode + * @param nav_controller_output C-struct to decode the message contents into + */ +static inline void mavlink_msg_nav_controller_output_decode(const mavlink_message_t* msg, mavlink_nav_controller_output_t* nav_controller_output) +{ +#if MAVLINK_NEED_BYTE_SWAP + nav_controller_output->nav_roll = mavlink_msg_nav_controller_output_get_nav_roll(msg); + nav_controller_output->nav_pitch = mavlink_msg_nav_controller_output_get_nav_pitch(msg); + nav_controller_output->alt_error = mavlink_msg_nav_controller_output_get_alt_error(msg); + nav_controller_output->aspd_error = mavlink_msg_nav_controller_output_get_aspd_error(msg); + nav_controller_output->xtrack_error = mavlink_msg_nav_controller_output_get_xtrack_error(msg); + nav_controller_output->nav_bearing = mavlink_msg_nav_controller_output_get_nav_bearing(msg); + nav_controller_output->target_bearing = mavlink_msg_nav_controller_output_get_target_bearing(msg); + nav_controller_output->wp_dist = mavlink_msg_nav_controller_output_get_wp_dist(msg); +#else + memcpy(nav_controller_output, _MAV_PAYLOAD(msg), 26); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h new file mode 100644 index 0000000000000000000000000000000000000000..b277cab5124965b179ed0c13c570954811d02ea1 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h @@ -0,0 +1,298 @@ +// MESSAGE OPTICAL_FLOW PACKING + +#define MAVLINK_MSG_ID_OPTICAL_FLOW 100 + +typedef struct __mavlink_optical_flow_t +{ + uint64_t time_usec; ///< Timestamp (UNIX) + float flow_comp_m_x; ///< Flow in meters in x-sensor direction, angular-speed compensated + float flow_comp_m_y; ///< Flow in meters in y-sensor direction, angular-speed compensated + float ground_distance; ///< Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + int16_t flow_x; ///< Flow in pixels in x-sensor direction + int16_t flow_y; ///< Flow in pixels in y-sensor direction + uint8_t sensor_id; ///< Sensor ID + uint8_t quality; ///< Optical flow quality / confidence. 0: bad, 255: maximum quality +} mavlink_optical_flow_t; + +#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 26 +#define MAVLINK_MSG_ID_100_LEN 26 + + + +#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \ + "OPTICAL_FLOW", \ + 8, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \ + { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \ + { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \ + { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \ + { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \ + { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \ + { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \ + { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \ + } \ +} + + +/** + * @brief Pack a optical_flow message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (UNIX) + * @param sensor_id Sensor ID + * @param flow_x Flow in pixels in x-sensor direction + * @param flow_y Flow in pixels in y-sensor direction + * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated + * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated + * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality + * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[26]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, flow_comp_m_x); + _mav_put_float(buf, 12, flow_comp_m_y); + _mav_put_float(buf, 16, ground_distance); + _mav_put_int16_t(buf, 20, flow_x); + _mav_put_int16_t(buf, 22, flow_y); + _mav_put_uint8_t(buf, 24, sensor_id); + _mav_put_uint8_t(buf, 25, quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); +#else + mavlink_optical_flow_t packet; + packet.time_usec = time_usec; + packet.flow_comp_m_x = flow_comp_m_x; + packet.flow_comp_m_y = flow_comp_m_y; + packet.ground_distance = ground_distance; + packet.flow_x = flow_x; + packet.flow_y = flow_y; + packet.sensor_id = sensor_id; + packet.quality = quality; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); +#endif + + msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW; + return mavlink_finalize_message(msg, system_id, component_id, 26, 175); +} + +/** + * @brief Pack a optical_flow message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (UNIX) + * @param sensor_id Sensor ID + * @param flow_x Flow in pixels in x-sensor direction + * @param flow_y Flow in pixels in y-sensor direction + * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated + * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated + * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality + * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t sensor_id,int16_t flow_x,int16_t flow_y,float flow_comp_m_x,float flow_comp_m_y,uint8_t quality,float ground_distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[26]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, flow_comp_m_x); + _mav_put_float(buf, 12, flow_comp_m_y); + _mav_put_float(buf, 16, ground_distance); + _mav_put_int16_t(buf, 20, flow_x); + _mav_put_int16_t(buf, 22, flow_y); + _mav_put_uint8_t(buf, 24, sensor_id); + _mav_put_uint8_t(buf, 25, quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); +#else + mavlink_optical_flow_t packet; + packet.time_usec = time_usec; + packet.flow_comp_m_x = flow_comp_m_x; + packet.flow_comp_m_y = flow_comp_m_y; + packet.ground_distance = ground_distance; + packet.flow_x = flow_x; + packet.flow_y = flow_y; + packet.sensor_id = sensor_id; + packet.quality = quality; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); +#endif + + msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26, 175); +} + +/** + * @brief Encode a optical_flow 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 optical_flow C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow) +{ + return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance); +} + +/** + * @brief Send a optical_flow message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (UNIX) + * @param sensor_id Sensor ID + * @param flow_x Flow in pixels in x-sensor direction + * @param flow_y Flow in pixels in y-sensor direction + * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated + * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated + * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality + * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[26]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, flow_comp_m_x); + _mav_put_float(buf, 12, flow_comp_m_y); + _mav_put_float(buf, 16, ground_distance); + _mav_put_int16_t(buf, 20, flow_x); + _mav_put_int16_t(buf, 22, flow_y); + _mav_put_uint8_t(buf, 24, sensor_id); + _mav_put_uint8_t(buf, 25, quality); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, 26, 175); +#else + mavlink_optical_flow_t packet; + packet.time_usec = time_usec; + packet.flow_comp_m_x = flow_comp_m_x; + packet.flow_comp_m_y = flow_comp_m_y; + packet.ground_distance = ground_distance; + packet.flow_x = flow_x; + packet.flow_y = flow_y; + packet.sensor_id = sensor_id; + packet.quality = quality; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, 26, 175); +#endif +} + +#endif + +// MESSAGE OPTICAL_FLOW UNPACKING + + +/** + * @brief Get field time_usec from optical_flow message + * + * @return Timestamp (UNIX) + */ +static inline uint64_t mavlink_msg_optical_flow_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field sensor_id from optical_flow message + * + * @return Sensor ID + */ +static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 24); +} + +/** + * @brief Get field flow_x from optical_flow message + * + * @return Flow in pixels in x-sensor direction + */ +static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Get field flow_y from optical_flow message + * + * @return Flow in pixels in y-sensor direction + */ +static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 22); +} + +/** + * @brief Get field flow_comp_m_x from optical_flow message + * + * @return Flow in meters in x-sensor direction, angular-speed compensated + */ +static inline float mavlink_msg_optical_flow_get_flow_comp_m_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field flow_comp_m_y from optical_flow message + * + * @return Flow in meters in y-sensor direction, angular-speed compensated + */ +static inline float mavlink_msg_optical_flow_get_flow_comp_m_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field quality from optical_flow message + * + * @return Optical flow quality / confidence. 0: bad, 255: maximum quality + */ +static inline uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 25); +} + +/** + * @brief Get field ground_distance from optical_flow message + * + * @return Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + */ +static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a optical_flow message into a struct + * + * @param msg The message to decode + * @param optical_flow C-struct to decode the message contents into + */ +static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* msg, mavlink_optical_flow_t* optical_flow) +{ +#if MAVLINK_NEED_BYTE_SWAP + optical_flow->time_usec = mavlink_msg_optical_flow_get_time_usec(msg); + optical_flow->flow_comp_m_x = mavlink_msg_optical_flow_get_flow_comp_m_x(msg); + optical_flow->flow_comp_m_y = mavlink_msg_optical_flow_get_flow_comp_m_y(msg); + optical_flow->ground_distance = mavlink_msg_optical_flow_get_ground_distance(msg); + optical_flow->flow_x = mavlink_msg_optical_flow_get_flow_x(msg); + optical_flow->flow_y = mavlink_msg_optical_flow_get_flow_y(msg); + optical_flow->sensor_id = mavlink_msg_optical_flow_get_sensor_id(msg); + optical_flow->quality = mavlink_msg_optical_flow_get_quality(msg); +#else + memcpy(optical_flow, _MAV_PAYLOAD(msg), 26); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h new file mode 100644 index 0000000000000000000000000000000000000000..125df80c85d7711c749e8f35ee7ea0366c9129e6 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h @@ -0,0 +1,166 @@ +// MESSAGE PARAM_REQUEST_LIST PACKING + +#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21 + +typedef struct __mavlink_param_request_list_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_param_request_list_t; + +#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN 2 +#define MAVLINK_MSG_ID_21_LEN 2 + + + +#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST { \ + "PARAM_REQUEST_LIST", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_list_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a param_request_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); +#else + mavlink_param_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; + return mavlink_finalize_message(msg, system_id, component_id, 2, 159); +} + +/** + * @brief Pack a param_request_list message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2); +#else + mavlink_param_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 159); +} + +/** + * @brief Encode a param_request_list struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param param_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list) +{ + return mavlink_msg_param_request_list_pack(system_id, component_id, msg, param_request_list->target_system, param_request_list->target_component); +} + +/** + * @brief Send a param_request_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, 2, 159); +#else + mavlink_param_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)&packet, 2, 159); +#endif +} + +#endif + +// MESSAGE PARAM_REQUEST_LIST UNPACKING + + +/** + * @brief Get field target_system from param_request_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_request_list_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from param_request_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_request_list_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a param_request_list message into a struct + * + * @param msg The message to decode + * @param param_request_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_request_list_decode(const mavlink_message_t* msg, mavlink_param_request_list_t* param_request_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + param_request_list->target_system = mavlink_msg_param_request_list_get_target_system(msg); + param_request_list->target_component = mavlink_msg_param_request_list_get_target_component(msg); +#else + memcpy(param_request_list, _MAV_PAYLOAD(msg), 2); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h new file mode 100644 index 0000000000000000000000000000000000000000..61d00f62d1bfd79ece9a9bfca9c2ed8ac759040c --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h @@ -0,0 +1,204 @@ +// MESSAGE PARAM_REQUEST_READ PACKING + +#define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20 + +typedef struct __mavlink_param_request_read_t +{ + int16_t param_index; ///< Parameter index. Send -1 to use the param ID field as identifier + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + char param_id[16]; ///< Onboard parameter id +} mavlink_param_request_read_t; + +#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20 +#define MAVLINK_MSG_ID_20_LEN 20 + +#define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN 16 + +#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \ + "PARAM_REQUEST_READ", \ + 4, \ + { { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \ + { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \ + } \ +} + + +/** + * @brief Pack a param_request_read 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 target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_index Parameter index. Send -1 to use the param ID field as identifier + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_int16_t(buf, 0, param_index); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_char_array(buf, 4, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); +#else + mavlink_param_request_read_t packet; + packet.param_index = param_index; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; + return mavlink_finalize_message(msg, system_id, component_id, 20, 214); +} + +/** + * @brief Pack a param_request_read 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 target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_index Parameter index. Send -1 to use the param ID field as identifier + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,const char *param_id,int16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_int16_t(buf, 0, param_index); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_char_array(buf, 4, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); +#else + mavlink_param_request_read_t packet; + packet.param_index = param_index; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 214); +} + +/** + * @brief Encode a param_request_read 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 param_request_read C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read) +{ + return mavlink_msg_param_request_read_pack(system_id, component_id, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); +} + +/** + * @brief Send a param_request_read message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_index Parameter index. Send -1 to use the param ID field as identifier + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_int16_t(buf, 0, param_index); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_char_array(buf, 4, param_id, 16); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, 20, 214); +#else + mavlink_param_request_read_t packet; + packet.param_index = param_index; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, 20, 214); +#endif +} + +#endif + +// MESSAGE PARAM_REQUEST_READ UNPACKING + + +/** + * @brief Get field target_system from param_request_read message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from param_request_read message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field param_id from param_request_read message + * + * @return Onboard parameter id + */ +static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, char *param_id) +{ + return _MAV_RETURN_char_array(msg, param_id, 16, 4); +} + +/** + * @brief Get field param_index from param_request_read message + * + * @return Parameter index. Send -1 to use the param ID field as identifier + */ +static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 0); +} + +/** + * @brief Decode a param_request_read message into a struct + * + * @param msg The message to decode + * @param param_request_read C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t* msg, mavlink_param_request_read_t* param_request_read) +{ +#if MAVLINK_NEED_BYTE_SWAP + param_request_read->param_index = mavlink_msg_param_request_read_get_param_index(msg); + param_request_read->target_system = mavlink_msg_param_request_read_get_target_system(msg); + param_request_read->target_component = mavlink_msg_param_request_read_get_target_component(msg); + mavlink_msg_param_request_read_get_param_id(msg, param_request_read->param_id); +#else + memcpy(param_request_read, _MAV_PAYLOAD(msg), 20); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h new file mode 100644 index 0000000000000000000000000000000000000000..a7e895f18d3fc9ee2104eac1029c1abf81f384a6 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h @@ -0,0 +1,226 @@ +// MESSAGE PARAM_SET PACKING + +#define MAVLINK_MSG_ID_PARAM_SET 23 + +typedef struct __mavlink_param_set_t +{ + float param_value; ///< Onboard parameter value + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + char param_id[16]; ///< Onboard parameter id + uint8_t param_type; ///< Onboard parameter type: see MAV_VAR enum +} mavlink_param_set_t; + +#define MAVLINK_MSG_ID_PARAM_SET_LEN 23 +#define MAVLINK_MSG_ID_23_LEN 23 + +#define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 16 + +#define MAVLINK_MESSAGE_INFO_PARAM_SET { \ + "PARAM_SET", \ + 5, \ + { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \ + { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \ + { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \ + } \ +} + + +/** + * @brief Pack a param_set 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 target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see MAV_VAR enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[23]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 22, param_type); + _mav_put_char_array(buf, 6, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 23); +#else + mavlink_param_set_t packet; + packet.param_value = param_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.param_type = param_type; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 23); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_SET; + return mavlink_finalize_message(msg, system_id, component_id, 23, 168); +} + +/** + * @brief Pack a param_set 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 target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see MAV_VAR enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,const char *param_id,float param_value,uint8_t param_type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[23]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 22, param_type); + _mav_put_char_array(buf, 6, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 23); +#else + mavlink_param_set_t packet; + packet.param_value = param_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.param_type = param_type; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 23); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_SET; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 23, 168); +} + +/** + * @brief Encode a param_set 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 param_set C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_set_t* param_set) +{ + return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type); +} + +/** + * @brief Send a param_set message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see MAV_VAR enum + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[23]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 22, param_type); + _mav_put_char_array(buf, 6, param_id, 16); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, 23, 168); +#else + mavlink_param_set_t packet; + packet.param_value = param_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.param_type = param_type; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, 23, 168); +#endif +} + +#endif + +// MESSAGE PARAM_SET UNPACKING + + +/** + * @brief Get field target_system from param_set message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field target_component from param_set message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field param_id from param_set message + * + * @return Onboard parameter id + */ +static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, char *param_id) +{ + return _MAV_RETURN_char_array(msg, param_id, 16, 6); +} + +/** + * @brief Get field param_value from param_set message + * + * @return Onboard parameter value + */ +static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param_type from param_set message + * + * @return Onboard parameter type: see MAV_VAR enum + */ +static inline uint8_t mavlink_msg_param_set_get_param_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 22); +} + +/** + * @brief Decode a param_set message into a struct + * + * @param msg The message to decode + * @param param_set C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_set_decode(const mavlink_message_t* msg, mavlink_param_set_t* param_set) +{ +#if MAVLINK_NEED_BYTE_SWAP + param_set->param_value = mavlink_msg_param_set_get_param_value(msg); + param_set->target_system = mavlink_msg_param_set_get_target_system(msg); + param_set->target_component = mavlink_msg_param_set_get_target_component(msg); + mavlink_msg_param_set_get_param_id(msg, param_set->param_id); + param_set->param_type = mavlink_msg_param_set_get_param_type(msg); +#else + memcpy(param_set, _MAV_PAYLOAD(msg), 23); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h new file mode 100644 index 0000000000000000000000000000000000000000..4e16a563186aa3151e53a1db690c08671578bf46 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h @@ -0,0 +1,226 @@ +// MESSAGE PARAM_VALUE PACKING + +#define MAVLINK_MSG_ID_PARAM_VALUE 22 + +typedef struct __mavlink_param_value_t +{ + float param_value; ///< Onboard parameter value + uint16_t param_count; ///< Total number of onboard parameters + uint16_t param_index; ///< Index of this onboard parameter + char param_id[16]; ///< Onboard parameter id + uint8_t param_type; ///< Onboard parameter type: see MAV_VAR enum +} mavlink_param_value_t; + +#define MAVLINK_MSG_ID_PARAM_VALUE_LEN 25 +#define MAVLINK_MSG_ID_22_LEN 25 + +#define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 16 + +#define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \ + "PARAM_VALUE", \ + 5, \ + { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \ + { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \ + { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \ + { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \ + { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \ + } \ +} + + +/** + * @brief Pack a param_value 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 param_id Onboard parameter id + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see MAV_VAR enum + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[25]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint16_t(buf, 4, param_count); + _mav_put_uint16_t(buf, 6, param_index); + _mav_put_uint8_t(buf, 24, param_type); + _mav_put_char_array(buf, 8, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25); +#else + mavlink_param_value_t packet; + packet.param_value = param_value; + packet.param_count = param_count; + packet.param_index = param_index; + packet.param_type = param_type; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; + return mavlink_finalize_message(msg, system_id, component_id, 25, 220); +} + +/** + * @brief Pack a param_value 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 param_id Onboard parameter id + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see MAV_VAR enum + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const char *param_id,float param_value,uint8_t param_type,uint16_t param_count,uint16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[25]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint16_t(buf, 4, param_count); + _mav_put_uint16_t(buf, 6, param_index); + _mav_put_uint8_t(buf, 24, param_type); + _mav_put_char_array(buf, 8, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25); +#else + mavlink_param_value_t packet; + packet.param_value = param_value; + packet.param_count = param_count; + packet.param_index = param_index; + packet.param_type = param_type; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 25, 220); +} + +/** + * @brief Encode a param_value 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 param_value C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_t* param_value) +{ + return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index); +} + +/** + * @brief Send a param_value message + * @param chan MAVLink channel to send the message + * + * @param param_id Onboard parameter id + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see MAV_VAR enum + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[25]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint16_t(buf, 4, param_count); + _mav_put_uint16_t(buf, 6, param_index); + _mav_put_uint8_t(buf, 24, param_type); + _mav_put_char_array(buf, 8, param_id, 16); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, 25, 220); +#else + mavlink_param_value_t packet; + packet.param_value = param_value; + packet.param_count = param_count; + packet.param_index = param_index; + packet.param_type = param_type; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet, 25, 220); +#endif +} + +#endif + +// MESSAGE PARAM_VALUE UNPACKING + + +/** + * @brief Get field param_id from param_value message + * + * @return Onboard parameter id + */ +static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, char *param_id) +{ + return _MAV_RETURN_char_array(msg, param_id, 16, 8); +} + +/** + * @brief Get field param_value from param_value message + * + * @return Onboard parameter value + */ +static inline float mavlink_msg_param_value_get_param_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param_type from param_value message + * + * @return Onboard parameter type: see MAV_VAR enum + */ +static inline uint8_t mavlink_msg_param_value_get_param_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 24); +} + +/** + * @brief Get field param_count from param_value message + * + * @return Total number of onboard parameters + */ +static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field param_index from param_value message + * + * @return Index of this onboard parameter + */ +static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Decode a param_value message into a struct + * + * @param msg The message to decode + * @param param_value C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value) +{ +#if MAVLINK_NEED_BYTE_SWAP + param_value->param_value = mavlink_msg_param_value_get_param_value(msg); + param_value->param_count = mavlink_msg_param_value_get_param_count(msg); + param_value->param_index = mavlink_msg_param_value_get_param_index(msg); + mavlink_msg_param_value_get_param_id(msg, param_value->param_id); + param_value->param_type = mavlink_msg_param_value_get_param_type(msg); +#else + memcpy(param_value, _MAV_PAYLOAD(msg), 25); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h new file mode 100644 index 0000000000000000000000000000000000000000..3ed1b9d7c46d07c46d1fb60d62a8feefed4c5b87 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h @@ -0,0 +1,210 @@ +// MESSAGE PING PACKING + +#define MAVLINK_MSG_ID_PING 4 + +typedef struct __mavlink_ping_t +{ + uint64_t time_usec; ///< Unix timestamp in microseconds + uint32_t seq; ///< PING sequence + uint8_t target_system; ///< 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + uint8_t target_component; ///< 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system +} mavlink_ping_t; + +#define MAVLINK_MSG_ID_PING_LEN 14 +#define MAVLINK_MSG_ID_4_LEN 14 + + + +#define MAVLINK_MESSAGE_INFO_PING { \ + "PING", \ + 4, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_t, time_usec) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_ping_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_ping_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_ping_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a ping message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Unix timestamp in microseconds + * @param seq PING sequence + * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[14]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); +#else + mavlink_ping_t packet; + packet.time_usec = time_usec; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); +#endif + + msg->msgid = MAVLINK_MSG_ID_PING; + return mavlink_finalize_message(msg, system_id, component_id, 14, 237); +} + +/** + * @brief Pack a ping message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Unix timestamp in microseconds + * @param seq PING sequence + * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint32_t seq,uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[14]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); +#else + mavlink_ping_t packet; + packet.time_usec = time_usec; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); +#endif + + msg->msgid = MAVLINK_MSG_ID_PING; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 237); +} + +/** + * @brief Encode a ping 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 ping C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_t* ping) +{ + return mavlink_msg_ping_pack(system_id, component_id, msg, ping->time_usec, ping->seq, ping->target_system, ping->target_component); +} + +/** + * @brief Send a ping message + * @param chan MAVLink channel to send the message + * + * @param time_usec Unix timestamp in microseconds + * @param seq PING sequence + * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[14]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, 14, 237); +#else + mavlink_ping_t packet; + packet.time_usec = time_usec; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, 14, 237); +#endif +} + +#endif + +// MESSAGE PING UNPACKING + + +/** + * @brief Get field time_usec from ping message + * + * @return Unix timestamp in microseconds + */ +static inline uint64_t mavlink_msg_ping_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field seq from ping message + * + * @return PING sequence + */ +static inline uint32_t mavlink_msg_ping_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field target_system from ping message + * + * @return 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + */ +static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field target_component from ping message + * + * @return 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + */ +static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 13); +} + +/** + * @brief Decode a ping message into a struct + * + * @param msg The message to decode + * @param ping C-struct to decode the message contents into + */ +static inline void mavlink_msg_ping_decode(const mavlink_message_t* msg, mavlink_ping_t* ping) +{ +#if MAVLINK_NEED_BYTE_SWAP + ping->time_usec = mavlink_msg_ping_get_time_usec(msg); + ping->seq = mavlink_msg_ping_get_seq(msg); + ping->target_system = mavlink_msg_ping_get_target_system(msg); + ping->target_component = mavlink_msg_ping_get_target_component(msg); +#else + memcpy(ping, _MAV_PAYLOAD(msg), 14); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h new file mode 100644 index 0000000000000000000000000000000000000000..1c1d4838867498580bad0031f86f7dfe21ece77c --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h @@ -0,0 +1,342 @@ +// MESSAGE RAW_IMU PACKING + +#define MAVLINK_MSG_ID_RAW_IMU 27 + +typedef struct __mavlink_raw_imu_t +{ + uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + int16_t xacc; ///< X acceleration (raw) + int16_t yacc; ///< Y acceleration (raw) + int16_t zacc; ///< Z acceleration (raw) + int16_t xgyro; ///< Angular speed around X axis (raw) + int16_t ygyro; ///< Angular speed around Y axis (raw) + int16_t zgyro; ///< Angular speed around Z axis (raw) + int16_t xmag; ///< X Magnetic field (raw) + int16_t ymag; ///< Y Magnetic field (raw) + int16_t zmag; ///< Z Magnetic field (raw) +} mavlink_raw_imu_t; + +#define MAVLINK_MSG_ID_RAW_IMU_LEN 26 +#define MAVLINK_MSG_ID_27_LEN 26 + + + +#define MAVLINK_MESSAGE_INFO_RAW_IMU { \ + "RAW_IMU", \ + 10, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, time_usec) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \ + } \ +} + + +/** + * @brief Pack a raw_imu message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param xacc X acceleration (raw) + * @param yacc Y acceleration (raw) + * @param zacc Z acceleration (raw) + * @param xgyro Angular speed around X axis (raw) + * @param ygyro Angular speed around Y axis (raw) + * @param zgyro Angular speed around Z axis (raw) + * @param xmag X Magnetic field (raw) + * @param ymag Y Magnetic field (raw) + * @param zmag Z Magnetic field (raw) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[26]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, xacc); + _mav_put_int16_t(buf, 10, yacc); + _mav_put_int16_t(buf, 12, zacc); + _mav_put_int16_t(buf, 14, xgyro); + _mav_put_int16_t(buf, 16, ygyro); + _mav_put_int16_t(buf, 18, zgyro); + _mav_put_int16_t(buf, 20, xmag); + _mav_put_int16_t(buf, 22, ymag); + _mav_put_int16_t(buf, 24, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); +#else + mavlink_raw_imu_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); +#endif + + msg->msgid = MAVLINK_MSG_ID_RAW_IMU; + return mavlink_finalize_message(msg, system_id, component_id, 26, 144); +} + +/** + * @brief Pack a raw_imu message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param xacc X acceleration (raw) + * @param yacc Y acceleration (raw) + * @param zacc Z acceleration (raw) + * @param xgyro Angular speed around X axis (raw) + * @param ygyro Angular speed around Y axis (raw) + * @param zgyro Angular speed around Z axis (raw) + * @param xmag X Magnetic field (raw) + * @param ymag Y Magnetic field (raw) + * @param zmag Z Magnetic field (raw) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[26]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, xacc); + _mav_put_int16_t(buf, 10, yacc); + _mav_put_int16_t(buf, 12, zacc); + _mav_put_int16_t(buf, 14, xgyro); + _mav_put_int16_t(buf, 16, ygyro); + _mav_put_int16_t(buf, 18, zgyro); + _mav_put_int16_t(buf, 20, xmag); + _mav_put_int16_t(buf, 22, ymag); + _mav_put_int16_t(buf, 24, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); +#else + mavlink_raw_imu_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); +#endif + + msg->msgid = MAVLINK_MSG_ID_RAW_IMU; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26, 144); +} + +/** + * @brief Encode a raw_imu 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 raw_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu) +{ + return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag); +} + +/** + * @brief Send a raw_imu message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param xacc X acceleration (raw) + * @param yacc Y acceleration (raw) + * @param zacc Z acceleration (raw) + * @param xgyro Angular speed around X axis (raw) + * @param ygyro Angular speed around Y axis (raw) + * @param zgyro Angular speed around Z axis (raw) + * @param xmag X Magnetic field (raw) + * @param ymag Y Magnetic field (raw) + * @param zmag Z Magnetic field (raw) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[26]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, xacc); + _mav_put_int16_t(buf, 10, yacc); + _mav_put_int16_t(buf, 12, zacc); + _mav_put_int16_t(buf, 14, xgyro); + _mav_put_int16_t(buf, 16, ygyro); + _mav_put_int16_t(buf, 18, zgyro); + _mav_put_int16_t(buf, 20, xmag); + _mav_put_int16_t(buf, 22, ymag); + _mav_put_int16_t(buf, 24, zmag); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, 26, 144); +#else + mavlink_raw_imu_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, 26, 144); +#endif +} + +#endif + +// MESSAGE RAW_IMU UNPACKING + + +/** + * @brief Get field time_usec from raw_imu message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_raw_imu_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field xacc from raw_imu message + * + * @return X acceleration (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field yacc from raw_imu message + * + * @return Y acceleration (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field zacc from raw_imu message + * + * @return Z acceleration (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field xgyro from raw_imu message + * + * @return Angular speed around X axis (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field ygyro from raw_imu message + * + * @return Angular speed around Y axis (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field zgyro from raw_imu message + * + * @return Angular speed around Z axis (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 18); +} + +/** + * @brief Get field xmag from raw_imu message + * + * @return X Magnetic field (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Get field ymag from raw_imu message + * + * @return Y Magnetic field (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 22); +} + +/** + * @brief Get field zmag from raw_imu message + * + * @return Z Magnetic field (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 24); +} + +/** + * @brief Decode a raw_imu message into a struct + * + * @param msg The message to decode + * @param raw_imu C-struct to decode the message contents into + */ +static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavlink_raw_imu_t* raw_imu) +{ +#if MAVLINK_NEED_BYTE_SWAP + raw_imu->time_usec = mavlink_msg_raw_imu_get_time_usec(msg); + raw_imu->xacc = mavlink_msg_raw_imu_get_xacc(msg); + raw_imu->yacc = mavlink_msg_raw_imu_get_yacc(msg); + raw_imu->zacc = mavlink_msg_raw_imu_get_zacc(msg); + raw_imu->xgyro = mavlink_msg_raw_imu_get_xgyro(msg); + raw_imu->ygyro = mavlink_msg_raw_imu_get_ygyro(msg); + raw_imu->zgyro = mavlink_msg_raw_imu_get_zgyro(msg); + raw_imu->xmag = mavlink_msg_raw_imu_get_xmag(msg); + raw_imu->ymag = mavlink_msg_raw_imu_get_ymag(msg); + raw_imu->zmag = mavlink_msg_raw_imu_get_zmag(msg); +#else + memcpy(raw_imu, _MAV_PAYLOAD(msg), 26); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h new file mode 100644 index 0000000000000000000000000000000000000000..f3e4e8404660a8215439d1fc345c58838117b029 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h @@ -0,0 +1,232 @@ +// MESSAGE RAW_PRESSURE PACKING + +#define MAVLINK_MSG_ID_RAW_PRESSURE 28 + +typedef struct __mavlink_raw_pressure_t +{ + uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + int16_t press_abs; ///< Absolute pressure (raw) + int16_t press_diff1; ///< Differential pressure 1 (raw) + int16_t press_diff2; ///< Differential pressure 2 (raw) + int16_t temperature; ///< Raw Temperature measurement (raw) +} mavlink_raw_pressure_t; + +#define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16 +#define MAVLINK_MSG_ID_28_LEN 16 + + + +#define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \ + "RAW_PRESSURE", \ + 5, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \ + { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \ + { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \ + { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \ + } \ +} + + +/** + * @brief Pack a raw_pressure message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (raw) + * @param press_diff1 Differential pressure 1 (raw) + * @param press_diff2 Differential pressure 2 (raw) + * @param temperature Raw Temperature measurement (raw) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[16]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, press_abs); + _mav_put_int16_t(buf, 10, press_diff1); + _mav_put_int16_t(buf, 12, press_diff2); + _mav_put_int16_t(buf, 14, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); +#else + mavlink_raw_pressure_t packet; + packet.time_usec = time_usec; + packet.press_abs = press_abs; + packet.press_diff1 = press_diff1; + packet.press_diff2 = press_diff2; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); +#endif + + msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; + return mavlink_finalize_message(msg, system_id, component_id, 16, 67); +} + +/** + * @brief Pack a raw_pressure message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (raw) + * @param press_diff1 Differential pressure 1 (raw) + * @param press_diff2 Differential pressure 2 (raw) + * @param temperature Raw Temperature measurement (raw) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,int16_t press_abs,int16_t press_diff1,int16_t press_diff2,int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[16]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, press_abs); + _mav_put_int16_t(buf, 10, press_diff1); + _mav_put_int16_t(buf, 12, press_diff2); + _mav_put_int16_t(buf, 14, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); +#else + mavlink_raw_pressure_t packet; + packet.time_usec = time_usec; + packet.press_abs = press_abs; + packet.press_diff1 = press_diff1; + packet.press_diff2 = press_diff2; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); +#endif + + msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16, 67); +} + +/** + * @brief Encode a raw_pressure 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 raw_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure) +{ + return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature); +} + +/** + * @brief Send a raw_pressure message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (raw) + * @param press_diff1 Differential pressure 1 (raw) + * @param press_diff2 Differential pressure 2 (raw) + * @param temperature Raw Temperature measurement (raw) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[16]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, press_abs); + _mav_put_int16_t(buf, 10, press_diff1); + _mav_put_int16_t(buf, 12, press_diff2); + _mav_put_int16_t(buf, 14, temperature); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, 16, 67); +#else + mavlink_raw_pressure_t packet; + packet.time_usec = time_usec; + packet.press_abs = press_abs; + packet.press_diff1 = press_diff1; + packet.press_diff2 = press_diff2; + packet.temperature = temperature; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, 16, 67); +#endif +} + +#endif + +// MESSAGE RAW_PRESSURE UNPACKING + + +/** + * @brief Get field time_usec from raw_pressure message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_raw_pressure_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field press_abs from raw_pressure message + * + * @return Absolute pressure (raw) + */ +static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field press_diff1 from raw_pressure message + * + * @return Differential pressure 1 (raw) + */ +static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field press_diff2 from raw_pressure message + * + * @return Differential pressure 2 (raw) + */ +static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field temperature from raw_pressure message + * + * @return Raw Temperature measurement (raw) + */ +static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Decode a raw_pressure message into a struct + * + * @param msg The message to decode + * @param raw_pressure C-struct to decode the message contents into + */ +static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, mavlink_raw_pressure_t* raw_pressure) +{ +#if MAVLINK_NEED_BYTE_SWAP + raw_pressure->time_usec = mavlink_msg_raw_pressure_get_time_usec(msg); + raw_pressure->press_abs = mavlink_msg_raw_pressure_get_press_abs(msg); + raw_pressure->press_diff1 = mavlink_msg_raw_pressure_get_press_diff1(msg); + raw_pressure->press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg); + raw_pressure->temperature = mavlink_msg_raw_pressure_get_temperature(msg); +#else + memcpy(raw_pressure, _MAV_PAYLOAD(msg), 16); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h new file mode 100644 index 0000000000000000000000000000000000000000..d719c7fca2c357a74684382e9be28186513490d3 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h @@ -0,0 +1,342 @@ +// MESSAGE RC_CHANNELS_OVERRIDE PACKING + +#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE 70 + +typedef struct __mavlink_rc_channels_override_t +{ + uint16_t chan1_raw; ///< RC channel 1 value, in microseconds + uint16_t chan2_raw; ///< RC channel 2 value, in microseconds + uint16_t chan3_raw; ///< RC channel 3 value, in microseconds + uint16_t chan4_raw; ///< RC channel 4 value, in microseconds + uint16_t chan5_raw; ///< RC channel 5 value, in microseconds + uint16_t chan6_raw; ///< RC channel 6 value, in microseconds + uint16_t chan7_raw; ///< RC channel 7 value, in microseconds + uint16_t chan8_raw; ///< RC channel 8 value, in microseconds + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_rc_channels_override_t; + +#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN 18 +#define MAVLINK_MSG_ID_70_LEN 18 + + + +#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \ + "RC_CHANNELS_OVERRIDE", \ + 10, \ + { { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \ + { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \ + { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \ + { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \ + { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_override_t, chan5_raw) }, \ + { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \ + { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \ + { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a rc_channels_override 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 target_system System ID + * @param target_component Component ID + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint16_t(buf, 0, chan1_raw); + _mav_put_uint16_t(buf, 2, chan2_raw); + _mav_put_uint16_t(buf, 4, chan3_raw); + _mav_put_uint16_t(buf, 6, chan4_raw); + _mav_put_uint16_t(buf, 8, chan5_raw); + _mav_put_uint16_t(buf, 10, chan6_raw); + _mav_put_uint16_t(buf, 12, chan7_raw); + _mav_put_uint16_t(buf, 14, chan8_raw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); +#else + mavlink_rc_channels_override_t packet; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE; + return mavlink_finalize_message(msg, system_id, component_id, 18, 124); +} + +/** + * @brief Pack a rc_channels_override 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 target_system System ID + * @param target_component Component ID + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint16_t(buf, 0, chan1_raw); + _mav_put_uint16_t(buf, 2, chan2_raw); + _mav_put_uint16_t(buf, 4, chan3_raw); + _mav_put_uint16_t(buf, 6, chan4_raw); + _mav_put_uint16_t(buf, 8, chan5_raw); + _mav_put_uint16_t(buf, 10, chan6_raw); + _mav_put_uint16_t(buf, 12, chan7_raw); + _mav_put_uint16_t(buf, 14, chan8_raw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); +#else + mavlink_rc_channels_override_t packet; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 124); +} + +/** + * @brief Encode a rc_channels_override 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 rc_channels_override C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_override_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override) +{ + return mavlink_msg_rc_channels_override_pack(system_id, component_id, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw); +} + +/** + * @brief Send a rc_channels_override message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rc_channels_override_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint16_t(buf, 0, chan1_raw); + _mav_put_uint16_t(buf, 2, chan2_raw); + _mav_put_uint16_t(buf, 4, chan3_raw); + _mav_put_uint16_t(buf, 6, chan4_raw); + _mav_put_uint16_t(buf, 8, chan5_raw); + _mav_put_uint16_t(buf, 10, chan6_raw); + _mav_put_uint16_t(buf, 12, chan7_raw); + _mav_put_uint16_t(buf, 14, chan8_raw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, 18, 124); +#else + mavlink_rc_channels_override_t packet; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)&packet, 18, 124); +#endif +} + +#endif + +// MESSAGE RC_CHANNELS_OVERRIDE UNPACKING + + +/** + * @brief Get field target_system from rc_channels_override message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_rc_channels_override_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field target_component from rc_channels_override message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_rc_channels_override_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field chan1_raw from rc_channels_override message + * + * @return RC channel 1 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan1_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field chan2_raw from rc_channels_override message + * + * @return RC channel 2 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan2_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Get field chan3_raw from rc_channels_override message + * + * @return RC channel 3 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan3_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field chan4_raw from rc_channels_override message + * + * @return RC channel 4 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan4_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field chan5_raw from rc_channels_override message + * + * @return RC channel 5 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan5_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field chan6_raw from rc_channels_override message + * + * @return RC channel 6 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan6_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field chan7_raw from rc_channels_override message + * + * @return RC channel 7 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan7_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field chan8_raw from rc_channels_override message + * + * @return RC channel 8 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan8_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Decode a rc_channels_override message into a struct + * + * @param msg The message to decode + * @param rc_channels_override C-struct to decode the message contents into + */ +static inline void mavlink_msg_rc_channels_override_decode(const mavlink_message_t* msg, mavlink_rc_channels_override_t* rc_channels_override) +{ +#if MAVLINK_NEED_BYTE_SWAP + rc_channels_override->chan1_raw = mavlink_msg_rc_channels_override_get_chan1_raw(msg); + rc_channels_override->chan2_raw = mavlink_msg_rc_channels_override_get_chan2_raw(msg); + rc_channels_override->chan3_raw = mavlink_msg_rc_channels_override_get_chan3_raw(msg); + rc_channels_override->chan4_raw = mavlink_msg_rc_channels_override_get_chan4_raw(msg); + rc_channels_override->chan5_raw = mavlink_msg_rc_channels_override_get_chan5_raw(msg); + rc_channels_override->chan6_raw = mavlink_msg_rc_channels_override_get_chan6_raw(msg); + rc_channels_override->chan7_raw = mavlink_msg_rc_channels_override_get_chan7_raw(msg); + rc_channels_override->chan8_raw = mavlink_msg_rc_channels_override_get_chan8_raw(msg); + rc_channels_override->target_system = mavlink_msg_rc_channels_override_get_target_system(msg); + rc_channels_override->target_component = mavlink_msg_rc_channels_override_get_target_component(msg); +#else + memcpy(rc_channels_override, _MAV_PAYLOAD(msg), 18); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h new file mode 100644 index 0000000000000000000000000000000000000000..a5b28021d5a5c8050b3a7e5d186b337b23746040 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h @@ -0,0 +1,364 @@ +// MESSAGE RC_CHANNELS_RAW PACKING + +#define MAVLINK_MSG_ID_RC_CHANNELS_RAW 35 + +typedef struct __mavlink_rc_channels_raw_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + uint16_t chan1_raw; ///< RC channel 1 value, in microseconds + uint16_t chan2_raw; ///< RC channel 2 value, in microseconds + uint16_t chan3_raw; ///< RC channel 3 value, in microseconds + uint16_t chan4_raw; ///< RC channel 4 value, in microseconds + uint16_t chan5_raw; ///< RC channel 5 value, in microseconds + uint16_t chan6_raw; ///< RC channel 6 value, in microseconds + uint16_t chan7_raw; ///< RC channel 7 value, in microseconds + uint16_t chan8_raw; ///< RC channel 8 value, in microseconds + uint8_t port; ///< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100% +} mavlink_rc_channels_raw_t; + +#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN 22 +#define MAVLINK_MSG_ID_35_LEN 22 + + + +#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW { \ + "RC_CHANNELS_RAW", \ + 11, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, time_boot_ms) }, \ + { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \ + { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \ + { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \ + { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_raw_t, chan4_raw) }, \ + { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_raw_t, chan5_raw) }, \ + { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \ + { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \ + { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \ + { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_raw_t, port) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_raw_t, rssi) }, \ + } \ +} + + +/** + * @brief Pack a rc_channels_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); +#else + mavlink_rc_channels_raw_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.port = port; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; + return mavlink_finalize_message(msg, system_id, component_id, 22, 244); +} + +/** + * @brief Pack a rc_channels_raw message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t port,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); +#else + mavlink_rc_channels_raw_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.port = port; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 244); +} + +/** + * @brief Encode a rc_channels_raw 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 rc_channels_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw) +{ + return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); +} + +/** + * @brief Send a rc_channels_raw message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, 22, 244); +#else + mavlink_rc_channels_raw_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.port = port; + packet.rssi = rssi; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, 22, 244); +#endif +} + +#endif + +// MESSAGE RC_CHANNELS_RAW UNPACKING + + +/** + * @brief Get field time_boot_ms from rc_channels_raw message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_rc_channels_raw_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field port from rc_channels_raw message + * + * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + */ +static inline uint8_t mavlink_msg_rc_channels_raw_get_port(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Get field chan1_raw from rc_channels_raw message + * + * @return RC channel 1 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field chan2_raw from rc_channels_raw message + * + * @return RC channel 2 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field chan3_raw from rc_channels_raw message + * + * @return RC channel 3 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field chan4_raw from rc_channels_raw message + * + * @return RC channel 4 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field chan5_raw from rc_channels_raw message + * + * @return RC channel 5 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field chan6_raw from rc_channels_raw message + * + * @return RC channel 6 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Get field chan7_raw from rc_channels_raw message + * + * @return RC channel 7 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field chan8_raw from rc_channels_raw message + * + * @return RC channel 8 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field rssi from rc_channels_raw message + * + * @return Receive signal strength indicator, 0: 0%, 255: 100% + */ +static inline uint8_t mavlink_msg_rc_channels_raw_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 21); +} + +/** + * @brief Decode a rc_channels_raw message into a struct + * + * @param msg The message to decode + * @param rc_channels_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t* msg, mavlink_rc_channels_raw_t* rc_channels_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP + rc_channels_raw->time_boot_ms = mavlink_msg_rc_channels_raw_get_time_boot_ms(msg); + rc_channels_raw->chan1_raw = mavlink_msg_rc_channels_raw_get_chan1_raw(msg); + rc_channels_raw->chan2_raw = mavlink_msg_rc_channels_raw_get_chan2_raw(msg); + rc_channels_raw->chan3_raw = mavlink_msg_rc_channels_raw_get_chan3_raw(msg); + rc_channels_raw->chan4_raw = mavlink_msg_rc_channels_raw_get_chan4_raw(msg); + rc_channels_raw->chan5_raw = mavlink_msg_rc_channels_raw_get_chan5_raw(msg); + rc_channels_raw->chan6_raw = mavlink_msg_rc_channels_raw_get_chan6_raw(msg); + rc_channels_raw->chan7_raw = mavlink_msg_rc_channels_raw_get_chan7_raw(msg); + rc_channels_raw->chan8_raw = mavlink_msg_rc_channels_raw_get_chan8_raw(msg); + rc_channels_raw->port = mavlink_msg_rc_channels_raw_get_port(msg); + rc_channels_raw->rssi = mavlink_msg_rc_channels_raw_get_rssi(msg); +#else + memcpy(rc_channels_raw, _MAV_PAYLOAD(msg), 22); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h new file mode 100644 index 0000000000000000000000000000000000000000..23c14c03d7a3b5c55a181c31f713e21a1f756b51 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h @@ -0,0 +1,364 @@ +// MESSAGE RC_CHANNELS_SCALED PACKING + +#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED 34 + +typedef struct __mavlink_rc_channels_scaled_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + int16_t chan1_scaled; ///< RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan2_scaled; ///< RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan3_scaled; ///< RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan4_scaled; ///< RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan5_scaled; ///< RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan6_scaled; ///< RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan7_scaled; ///< RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan8_scaled; ///< RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + uint8_t port; ///< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100% +} mavlink_rc_channels_scaled_t; + +#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN 22 +#define MAVLINK_MSG_ID_34_LEN 22 + + + +#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED { \ + "RC_CHANNELS_SCALED", \ + 11, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, time_boot_ms) }, \ + { "chan1_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \ + { "chan2_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \ + { "chan3_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \ + { "chan4_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rc_channels_scaled_t, chan4_scaled) }, \ + { "chan5_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_rc_channels_scaled_t, chan5_scaled) }, \ + { "chan6_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \ + { "chan7_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \ + { "chan8_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \ + { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_scaled_t, port) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \ + } \ +} + + +/** + * @brief Pack a rc_channels_scaled message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, chan1_scaled); + _mav_put_int16_t(buf, 6, chan2_scaled); + _mav_put_int16_t(buf, 8, chan3_scaled); + _mav_put_int16_t(buf, 10, chan4_scaled); + _mav_put_int16_t(buf, 12, chan5_scaled); + _mav_put_int16_t(buf, 14, chan6_scaled); + _mav_put_int16_t(buf, 16, chan7_scaled); + _mav_put_int16_t(buf, 18, chan8_scaled); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); +#else + mavlink_rc_channels_scaled_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_scaled = chan1_scaled; + packet.chan2_scaled = chan2_scaled; + packet.chan3_scaled = chan3_scaled; + packet.chan4_scaled = chan4_scaled; + packet.chan5_scaled = chan5_scaled; + packet.chan6_scaled = chan6_scaled; + packet.chan7_scaled = chan7_scaled; + packet.chan8_scaled = chan8_scaled; + packet.port = port; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; + return mavlink_finalize_message(msg, system_id, component_id, 22, 237); +} + +/** + * @brief Pack a rc_channels_scaled message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t port,int16_t chan1_scaled,int16_t chan2_scaled,int16_t chan3_scaled,int16_t chan4_scaled,int16_t chan5_scaled,int16_t chan6_scaled,int16_t chan7_scaled,int16_t chan8_scaled,uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, chan1_scaled); + _mav_put_int16_t(buf, 6, chan2_scaled); + _mav_put_int16_t(buf, 8, chan3_scaled); + _mav_put_int16_t(buf, 10, chan4_scaled); + _mav_put_int16_t(buf, 12, chan5_scaled); + _mav_put_int16_t(buf, 14, chan6_scaled); + _mav_put_int16_t(buf, 16, chan7_scaled); + _mav_put_int16_t(buf, 18, chan8_scaled); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); +#else + mavlink_rc_channels_scaled_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_scaled = chan1_scaled; + packet.chan2_scaled = chan2_scaled; + packet.chan3_scaled = chan3_scaled; + packet.chan4_scaled = chan4_scaled; + packet.chan5_scaled = chan5_scaled; + packet.chan6_scaled = chan6_scaled; + packet.chan7_scaled = chan7_scaled; + packet.chan8_scaled = chan8_scaled; + packet.port = port; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 237); +} + +/** + * @brief Encode a rc_channels_scaled 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 rc_channels_scaled C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled) +{ + return mavlink_msg_rc_channels_scaled_pack(system_id, component_id, msg, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); +} + +/** + * @brief Send a rc_channels_scaled message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, chan1_scaled); + _mav_put_int16_t(buf, 6, chan2_scaled); + _mav_put_int16_t(buf, 8, chan3_scaled); + _mav_put_int16_t(buf, 10, chan4_scaled); + _mav_put_int16_t(buf, 12, chan5_scaled); + _mav_put_int16_t(buf, 14, chan6_scaled); + _mav_put_int16_t(buf, 16, chan7_scaled); + _mav_put_int16_t(buf, 18, chan8_scaled); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, 22, 237); +#else + mavlink_rc_channels_scaled_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_scaled = chan1_scaled; + packet.chan2_scaled = chan2_scaled; + packet.chan3_scaled = chan3_scaled; + packet.chan4_scaled = chan4_scaled; + packet.chan5_scaled = chan5_scaled; + packet.chan6_scaled = chan6_scaled; + packet.chan7_scaled = chan7_scaled; + packet.chan8_scaled = chan8_scaled; + packet.port = port; + packet.rssi = rssi; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, 22, 237); +#endif +} + +#endif + +// MESSAGE RC_CHANNELS_SCALED UNPACKING + + +/** + * @brief Get field time_boot_ms from rc_channels_scaled message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_rc_channels_scaled_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field port from rc_channels_scaled message + * + * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + */ +static inline uint8_t mavlink_msg_rc_channels_scaled_get_port(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Get field chan1_scaled from rc_channels_scaled message + * + * @return RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 4); +} + +/** + * @brief Get field chan2_scaled from rc_channels_scaled message + * + * @return RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 6); +} + +/** + * @brief Get field chan3_scaled from rc_channels_scaled message + * + * @return RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field chan4_scaled from rc_channels_scaled message + * + * @return RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field chan5_scaled from rc_channels_scaled message + * + * @return RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field chan6_scaled from rc_channels_scaled message + * + * @return RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field chan7_scaled from rc_channels_scaled message + * + * @return RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field chan8_scaled from rc_channels_scaled message + * + * @return RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 18); +} + +/** + * @brief Get field rssi from rc_channels_scaled message + * + * @return Receive signal strength indicator, 0: 0%, 255: 100% + */ +static inline uint8_t mavlink_msg_rc_channels_scaled_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 21); +} + +/** + * @brief Decode a rc_channels_scaled message into a struct + * + * @param msg The message to decode + * @param rc_channels_scaled C-struct to decode the message contents into + */ +static inline void mavlink_msg_rc_channels_scaled_decode(const mavlink_message_t* msg, mavlink_rc_channels_scaled_t* rc_channels_scaled) +{ +#if MAVLINK_NEED_BYTE_SWAP + rc_channels_scaled->time_boot_ms = mavlink_msg_rc_channels_scaled_get_time_boot_ms(msg); + rc_channels_scaled->chan1_scaled = mavlink_msg_rc_channels_scaled_get_chan1_scaled(msg); + rc_channels_scaled->chan2_scaled = mavlink_msg_rc_channels_scaled_get_chan2_scaled(msg); + rc_channels_scaled->chan3_scaled = mavlink_msg_rc_channels_scaled_get_chan3_scaled(msg); + rc_channels_scaled->chan4_scaled = mavlink_msg_rc_channels_scaled_get_chan4_scaled(msg); + rc_channels_scaled->chan5_scaled = mavlink_msg_rc_channels_scaled_get_chan5_scaled(msg); + rc_channels_scaled->chan6_scaled = mavlink_msg_rc_channels_scaled_get_chan6_scaled(msg); + rc_channels_scaled->chan7_scaled = mavlink_msg_rc_channels_scaled_get_chan7_scaled(msg); + rc_channels_scaled->chan8_scaled = mavlink_msg_rc_channels_scaled_get_chan8_scaled(msg); + rc_channels_scaled->port = mavlink_msg_rc_channels_scaled_get_port(msg); + rc_channels_scaled->rssi = mavlink_msg_rc_channels_scaled_get_rssi(msg); +#else + memcpy(rc_channels_scaled, _MAV_PAYLOAD(msg), 22); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h new file mode 100644 index 0000000000000000000000000000000000000000..d8653ad1095f292b744d72ea070d351bffa59bf9 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h @@ -0,0 +1,232 @@ +// MESSAGE REQUEST_DATA_STREAM PACKING + +#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66 + +typedef struct __mavlink_request_data_stream_t +{ + uint16_t req_message_rate; ///< The requested interval between two messages of this type + uint8_t target_system; ///< The target requested to send the message stream. + uint8_t target_component; ///< The target requested to send the message stream. + uint8_t req_stream_id; ///< The ID of the requested data stream + uint8_t start_stop; ///< 1 to start sending, 0 to stop sending. +} mavlink_request_data_stream_t; + +#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6 +#define MAVLINK_MSG_ID_66_LEN 6 + + + +#define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \ + "REQUEST_DATA_STREAM", \ + 5, \ + { { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_request_data_stream_t, target_component) }, \ + { "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \ + { "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \ + } \ +} + + +/** + * @brief Pack a request_data_stream 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 target_system The target requested to send the message stream. + * @param target_component The target requested to send the message stream. + * @param req_stream_id The ID of the requested data stream + * @param req_message_rate The requested interval between two messages of this type + * @param start_stop 1 to start sending, 0 to stop sending. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_uint16_t(buf, 0, req_message_rate); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_uint8_t(buf, 4, req_stream_id); + _mav_put_uint8_t(buf, 5, start_stop); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); +#else + mavlink_request_data_stream_t packet; + packet.req_message_rate = req_message_rate; + packet.target_system = target_system; + packet.target_component = target_component; + packet.req_stream_id = req_stream_id; + packet.start_stop = start_stop; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); +#endif + + msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM; + return mavlink_finalize_message(msg, system_id, component_id, 6, 148); +} + +/** + * @brief Pack a request_data_stream 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 target_system The target requested to send the message stream. + * @param target_component The target requested to send the message stream. + * @param req_stream_id The ID of the requested data stream + * @param req_message_rate The requested interval between two messages of this type + * @param start_stop 1 to start sending, 0 to stop sending. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_request_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t req_stream_id,uint16_t req_message_rate,uint8_t start_stop) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_uint16_t(buf, 0, req_message_rate); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_uint8_t(buf, 4, req_stream_id); + _mav_put_uint8_t(buf, 5, start_stop); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); +#else + mavlink_request_data_stream_t packet; + packet.req_message_rate = req_message_rate; + packet.target_system = target_system; + packet.target_component = target_component; + packet.req_stream_id = req_stream_id; + packet.start_stop = start_stop; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); +#endif + + msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 148); +} + +/** + * @brief Encode a request_data_stream 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 request_data_stream C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream) +{ + return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); +} + +/** + * @brief Send a request_data_stream message + * @param chan MAVLink channel to send the message + * + * @param target_system The target requested to send the message stream. + * @param target_component The target requested to send the message stream. + * @param req_stream_id The ID of the requested data stream + * @param req_message_rate The requested interval between two messages of this type + * @param start_stop 1 to start sending, 0 to stop sending. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_request_data_stream_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_uint16_t(buf, 0, req_message_rate); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_uint8_t(buf, 4, req_stream_id); + _mav_put_uint8_t(buf, 5, start_stop); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, 6, 148); +#else + mavlink_request_data_stream_t packet; + packet.req_message_rate = req_message_rate; + packet.target_system = target_system; + packet.target_component = target_component; + packet.req_stream_id = req_stream_id; + packet.start_stop = start_stop; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, 6, 148); +#endif +} + +#endif + +// MESSAGE REQUEST_DATA_STREAM UNPACKING + + +/** + * @brief Get field target_system from request_data_stream message + * + * @return The target requested to send the message stream. + */ +static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from request_data_stream message + * + * @return The target requested to send the message stream. + */ +static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field req_stream_id from request_data_stream message + * + * @return The ID of the requested data stream + */ +static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field req_message_rate from request_data_stream message + * + * @return The requested interval between two messages of this type + */ +static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field start_stop from request_data_stream message + * + * @return 1 to start sending, 0 to stop sending. + */ +static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Decode a request_data_stream message into a struct + * + * @param msg The message to decode + * @param request_data_stream C-struct to decode the message contents into + */ +static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_t* msg, mavlink_request_data_stream_t* request_data_stream) +{ +#if MAVLINK_NEED_BYTE_SWAP + request_data_stream->req_message_rate = mavlink_msg_request_data_stream_get_req_message_rate(msg); + request_data_stream->target_system = mavlink_msg_request_data_stream_get_target_system(msg); + request_data_stream->target_component = mavlink_msg_request_data_stream_get_target_component(msg); + request_data_stream->req_stream_id = mavlink_msg_request_data_stream_get_req_stream_id(msg); + request_data_stream->start_stop = mavlink_msg_request_data_stream_get_start_stop(msg); +#else + memcpy(request_data_stream, _MAV_PAYLOAD(msg), 6); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h new file mode 100644 index 0000000000000000000000000000000000000000..5751badc3e2bde36cddcbb4de14a33f2a6335ba3 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h @@ -0,0 +1,232 @@ +// MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT PACKING + +#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT 59 + +typedef struct __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t +{ + uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot + float roll_speed; ///< Desired roll angular speed in rad/s + float pitch_speed; ///< Desired pitch angular speed in rad/s + float yaw_speed; ///< Desired yaw angular speed in rad/s + float thrust; ///< Collective thrust, normalized to 0 .. 1 +} mavlink_roll_pitch_yaw_speed_thrust_setpoint_t; + +#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN 20 +#define MAVLINK_MSG_ID_59_LEN 20 + + + +#define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT { \ + "ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT", \ + 5, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, time_boot_ms) }, \ + { "roll_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, roll_speed) }, \ + { "pitch_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, pitch_speed) }, \ + { "yaw_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, yaw_speed) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, thrust) }, \ + } \ +} + + +/** + * @brief Pack a roll_pitch_yaw_speed_thrust_setpoint message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll_speed Desired roll angular speed in rad/s + * @param pitch_speed Desired pitch angular speed in rad/s + * @param yaw_speed Desired yaw angular speed in rad/s + * @param thrust Collective thrust, normalized to 0 .. 1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float roll_speed, float pitch_speed, float yaw_speed, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll_speed); + _mav_put_float(buf, 8, pitch_speed); + _mav_put_float(buf, 12, yaw_speed); + _mav_put_float(buf, 16, thrust); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); +#else + mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll_speed = roll_speed; + packet.pitch_speed = pitch_speed; + packet.yaw_speed = yaw_speed; + packet.thrust = thrust; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT; + return mavlink_finalize_message(msg, system_id, component_id, 20, 238); +} + +/** + * @brief Pack a roll_pitch_yaw_speed_thrust_setpoint message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll_speed Desired roll angular speed in rad/s + * @param pitch_speed Desired pitch angular speed in rad/s + * @param yaw_speed Desired yaw angular speed in rad/s + * @param thrust Collective thrust, normalized to 0 .. 1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float roll_speed,float pitch_speed,float yaw_speed,float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll_speed); + _mav_put_float(buf, 8, pitch_speed); + _mav_put_float(buf, 12, yaw_speed); + _mav_put_float(buf, 16, thrust); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); +#else + mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll_speed = roll_speed; + packet.pitch_speed = pitch_speed; + packet.yaw_speed = yaw_speed; + packet.thrust = thrust; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 238); +} + +/** + * @brief Encode a roll_pitch_yaw_speed_thrust_setpoint struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param roll_pitch_yaw_speed_thrust_setpoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint) +{ + return mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_speed_thrust_setpoint->time_boot_ms, roll_pitch_yaw_speed_thrust_setpoint->roll_speed, roll_pitch_yaw_speed_thrust_setpoint->pitch_speed, roll_pitch_yaw_speed_thrust_setpoint->yaw_speed, roll_pitch_yaw_speed_thrust_setpoint->thrust); +} + +/** + * @brief Send a roll_pitch_yaw_speed_thrust_setpoint message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll_speed Desired roll angular speed in rad/s + * @param pitch_speed Desired pitch angular speed in rad/s + * @param yaw_speed Desired yaw angular speed in rad/s + * @param thrust Collective thrust, normalized to 0 .. 1 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll_speed, float pitch_speed, float yaw_speed, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll_speed); + _mav_put_float(buf, 8, pitch_speed); + _mav_put_float(buf, 12, yaw_speed); + _mav_put_float(buf, 16, thrust); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, buf, 20, 238); +#else + mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll_speed = roll_speed; + packet.pitch_speed = pitch_speed; + packet.yaw_speed = yaw_speed; + packet.thrust = thrust; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, (const char *)&packet, 20, 238); +#endif +} + +#endif + +// MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT UNPACKING + + +/** + * @brief Get field time_boot_ms from roll_pitch_yaw_speed_thrust_setpoint message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint32_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field roll_speed from roll_pitch_yaw_speed_thrust_setpoint message + * + * @return Desired roll angular speed in rad/s + */ +static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_roll_speed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field pitch_speed from roll_pitch_yaw_speed_thrust_setpoint message + * + * @return Desired pitch angular speed in rad/s + */ +static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_pitch_speed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw_speed from roll_pitch_yaw_speed_thrust_setpoint message + * + * @return Desired yaw angular speed in rad/s + */ +static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field thrust from roll_pitch_yaw_speed_thrust_setpoint message + * + * @return Collective thrust, normalized to 0 .. 1 + */ +static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a roll_pitch_yaw_speed_thrust_setpoint message into a struct + * + * @param msg The message to decode + * @param roll_pitch_yaw_speed_thrust_setpoint C-struct to decode the message contents into + */ +static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint) +{ +#if MAVLINK_NEED_BYTE_SWAP + roll_pitch_yaw_speed_thrust_setpoint->time_boot_ms = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_time_boot_ms(msg); + roll_pitch_yaw_speed_thrust_setpoint->roll_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_roll_speed(msg); + roll_pitch_yaw_speed_thrust_setpoint->pitch_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_pitch_speed(msg); + roll_pitch_yaw_speed_thrust_setpoint->yaw_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(msg); + roll_pitch_yaw_speed_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(msg); +#else + memcpy(roll_pitch_yaw_speed_thrust_setpoint, _MAV_PAYLOAD(msg), 20); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h new file mode 100644 index 0000000000000000000000000000000000000000..a9f6ad0caa61a1fcfc9d951a0b52b7a5112ee826 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h @@ -0,0 +1,232 @@ +// MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT PACKING + +#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT 58 + +typedef struct __mavlink_roll_pitch_yaw_thrust_setpoint_t +{ + uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot + float roll; ///< Desired roll angle in radians + float pitch; ///< Desired pitch angle in radians + float yaw; ///< Desired yaw angle in radians + float thrust; ///< Collective thrust, normalized to 0 .. 1 +} mavlink_roll_pitch_yaw_thrust_setpoint_t; + +#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN 20 +#define MAVLINK_MSG_ID_58_LEN 20 + + + +#define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT { \ + "ROLL_PITCH_YAW_THRUST_SETPOINT", \ + 5, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, time_boot_ms) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, yaw) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, thrust) }, \ + } \ +} + + +/** + * @brief Pack a roll_pitch_yaw_thrust_setpoint message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll Desired roll angle in radians + * @param pitch Desired pitch angle in radians + * @param yaw Desired yaw angle in radians + * @param thrust Collective thrust, normalized to 0 .. 1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, thrust); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); +#else + mavlink_roll_pitch_yaw_thrust_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT; + return mavlink_finalize_message(msg, system_id, component_id, 20, 239); +} + +/** + * @brief Pack a roll_pitch_yaw_thrust_setpoint message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll Desired roll angle in radians + * @param pitch Desired pitch angle in radians + * @param yaw Desired yaw angle in radians + * @param thrust Collective thrust, normalized to 0 .. 1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float roll,float pitch,float yaw,float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, thrust); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); +#else + mavlink_roll_pitch_yaw_thrust_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 239); +} + +/** + * @brief Encode a roll_pitch_yaw_thrust_setpoint struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param roll_pitch_yaw_thrust_setpoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_thrust_setpoint_t* roll_pitch_yaw_thrust_setpoint) +{ + return mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_thrust_setpoint->time_boot_ms, roll_pitch_yaw_thrust_setpoint->roll, roll_pitch_yaw_thrust_setpoint->pitch, roll_pitch_yaw_thrust_setpoint->yaw, roll_pitch_yaw_thrust_setpoint->thrust); +} + +/** + * @brief Send a roll_pitch_yaw_thrust_setpoint message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll Desired roll angle in radians + * @param pitch Desired pitch angle in radians + * @param yaw Desired yaw angle in radians + * @param thrust Collective thrust, normalized to 0 .. 1 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, thrust); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, buf, 20, 239); +#else + mavlink_roll_pitch_yaw_thrust_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, (const char *)&packet, 20, 239); +#endif +} + +#endif + +// MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT UNPACKING + + +/** + * @brief Get field time_boot_ms from roll_pitch_yaw_thrust_setpoint message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint32_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field roll from roll_pitch_yaw_thrust_setpoint message + * + * @return Desired roll angle in radians + */ +static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field pitch from roll_pitch_yaw_thrust_setpoint message + * + * @return Desired pitch angle in radians + */ +static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw from roll_pitch_yaw_thrust_setpoint message + * + * @return Desired yaw angle in radians + */ +static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field thrust from roll_pitch_yaw_thrust_setpoint message + * + * @return Collective thrust, normalized to 0 .. 1 + */ +static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a roll_pitch_yaw_thrust_setpoint message into a struct + * + * @param msg The message to decode + * @param roll_pitch_yaw_thrust_setpoint C-struct to decode the message contents into + */ +static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_thrust_setpoint_t* roll_pitch_yaw_thrust_setpoint) +{ +#if MAVLINK_NEED_BYTE_SWAP + roll_pitch_yaw_thrust_setpoint->time_boot_ms = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_time_boot_ms(msg); + roll_pitch_yaw_thrust_setpoint->roll = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_roll(msg); + roll_pitch_yaw_thrust_setpoint->pitch = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_pitch(msg); + roll_pitch_yaw_thrust_setpoint->yaw = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_yaw(msg); + roll_pitch_yaw_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_thrust(msg); +#else + memcpy(roll_pitch_yaw_thrust_setpoint, _MAV_PAYLOAD(msg), 20); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h new file mode 100644 index 0000000000000000000000000000000000000000..aae6fd206ae9910aad8dd98ac000e67af3035b12 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h @@ -0,0 +1,276 @@ +// MESSAGE SAFETY_ALLOWED_AREA PACKING + +#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 55 + +typedef struct __mavlink_safety_allowed_area_t +{ + float p1x; ///< x position 1 / Latitude 1 + float p1y; ///< y position 1 / Longitude 1 + float p1z; ///< z position 1 / Altitude 1 + float p2x; ///< x position 2 / Latitude 2 + float p2y; ///< y position 2 / Longitude 2 + float p2z; ///< z position 2 / Altitude 2 + uint8_t frame; ///< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. +} mavlink_safety_allowed_area_t; + +#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25 +#define MAVLINK_MSG_ID_55_LEN 25 + + + +#define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \ + "SAFETY_ALLOWED_AREA", \ + 7, \ + { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \ + { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_allowed_area_t, p1y) }, \ + { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_allowed_area_t, p1z) }, \ + { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_allowed_area_t, p2x) }, \ + { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_allowed_area_t, p2y) }, \ + { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_allowed_area_t, p2z) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \ + } \ +} + + +/** + * @brief Pack a safety_allowed_area 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 frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[25]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25); +#else + mavlink_safety_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25); +#endif + + msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; + return mavlink_finalize_message(msg, system_id, component_id, 25, 3); +} + +/** + * @brief Pack a safety_allowed_area 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 frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[25]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25); +#else + mavlink_safety_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25); +#endif + + msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 25, 3); +} + +/** + * @brief Encode a safety_allowed_area 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 safety_allowed_area C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_safety_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area) +{ + return mavlink_msg_safety_allowed_area_pack(system_id, component_id, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); +} + +/** + * @brief Send a safety_allowed_area message + * @param chan MAVLink channel to send the message + * + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_safety_allowed_area_send(mavlink_channel_t chan, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[25]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, frame); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, 25, 3); +#else + mavlink_safety_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.frame = frame; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, 25, 3); +#endif +} + +#endif + +// MESSAGE SAFETY_ALLOWED_AREA UNPACKING + + +/** + * @brief Get field frame from safety_allowed_area message + * + * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + */ +static inline uint8_t mavlink_msg_safety_allowed_area_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 24); +} + +/** + * @brief Get field p1x from safety_allowed_area message + * + * @return x position 1 / Latitude 1 + */ +static inline float mavlink_msg_safety_allowed_area_get_p1x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field p1y from safety_allowed_area message + * + * @return y position 1 / Longitude 1 + */ +static inline float mavlink_msg_safety_allowed_area_get_p1y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field p1z from safety_allowed_area message + * + * @return z position 1 / Altitude 1 + */ +static inline float mavlink_msg_safety_allowed_area_get_p1z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field p2x from safety_allowed_area message + * + * @return x position 2 / Latitude 2 + */ +static inline float mavlink_msg_safety_allowed_area_get_p2x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field p2y from safety_allowed_area message + * + * @return y position 2 / Longitude 2 + */ +static inline float mavlink_msg_safety_allowed_area_get_p2y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field p2z from safety_allowed_area message + * + * @return z position 2 / Altitude 2 + */ +static inline float mavlink_msg_safety_allowed_area_get_p2z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Decode a safety_allowed_area message into a struct + * + * @param msg The message to decode + * @param safety_allowed_area C-struct to decode the message contents into + */ +static inline void mavlink_msg_safety_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_allowed_area_t* safety_allowed_area) +{ +#if MAVLINK_NEED_BYTE_SWAP + safety_allowed_area->p1x = mavlink_msg_safety_allowed_area_get_p1x(msg); + safety_allowed_area->p1y = mavlink_msg_safety_allowed_area_get_p1y(msg); + safety_allowed_area->p1z = mavlink_msg_safety_allowed_area_get_p1z(msg); + safety_allowed_area->p2x = mavlink_msg_safety_allowed_area_get_p2x(msg); + safety_allowed_area->p2y = mavlink_msg_safety_allowed_area_get_p2y(msg); + safety_allowed_area->p2z = mavlink_msg_safety_allowed_area_get_p2z(msg); + safety_allowed_area->frame = mavlink_msg_safety_allowed_area_get_frame(msg); +#else + memcpy(safety_allowed_area, _MAV_PAYLOAD(msg), 25); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h new file mode 100644 index 0000000000000000000000000000000000000000..8fb410c2d63969636d2d2cf4f1c4c84b33988d6b --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h @@ -0,0 +1,320 @@ +// MESSAGE SAFETY_SET_ALLOWED_AREA PACKING + +#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 54 + +typedef struct __mavlink_safety_set_allowed_area_t +{ + float p1x; ///< x position 1 / Latitude 1 + float p1y; ///< y position 1 / Longitude 1 + float p1z; ///< z position 1 / Altitude 1 + float p2x; ///< x position 2 / Latitude 2 + float p2y; ///< y position 2 / Longitude 2 + float p2z; ///< z position 2 / Altitude 2 + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t frame; ///< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. +} mavlink_safety_set_allowed_area_t; + +#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27 +#define MAVLINK_MSG_ID_54_LEN 27 + + + +#define MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA { \ + "SAFETY_SET_ALLOWED_AREA", \ + 9, \ + { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \ + { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \ + { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \ + { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \ + { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \ + { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \ + } \ +} + + +/** + * @brief Pack a safety_set_allowed_area 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 target_system System ID + * @param target_component Component ID + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[27]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, target_system); + _mav_put_uint8_t(buf, 25, target_component); + _mav_put_uint8_t(buf, 26, frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 27); +#else + mavlink_safety_set_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 27); +#endif + + msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA; + return mavlink_finalize_message(msg, system_id, component_id, 27, 15); +} + +/** + * @brief Pack a safety_set_allowed_area 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 target_system System ID + * @param target_component Component ID + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_set_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[27]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, target_system); + _mav_put_uint8_t(buf, 25, target_component); + _mav_put_uint8_t(buf, 26, frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 27); +#else + mavlink_safety_set_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 27); +#endif + + msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 27, 15); +} + +/** + * @brief Encode a safety_set_allowed_area 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 safety_set_allowed_area C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_safety_set_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area) +{ + return mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z); +} + +/** + * @brief Send a safety_set_allowed_area message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_safety_set_allowed_area_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[27]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, target_system); + _mav_put_uint8_t(buf, 25, target_component); + _mav_put_uint8_t(buf, 26, frame); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, 27, 15); +#else + mavlink_safety_set_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, 27, 15); +#endif +} + +#endif + +// MESSAGE SAFETY_SET_ALLOWED_AREA UNPACKING + + +/** + * @brief Get field target_system from safety_set_allowed_area message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 24); +} + +/** + * @brief Get field target_component from safety_set_allowed_area message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 25); +} + +/** + * @brief Get field frame from safety_set_allowed_area message + * + * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + */ +static inline uint8_t mavlink_msg_safety_set_allowed_area_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 26); +} + +/** + * @brief Get field p1x from safety_set_allowed_area message + * + * @return x position 1 / Latitude 1 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p1x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field p1y from safety_set_allowed_area message + * + * @return y position 1 / Longitude 1 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p1y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field p1z from safety_set_allowed_area message + * + * @return z position 1 / Altitude 1 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p1z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field p2x from safety_set_allowed_area message + * + * @return x position 2 / Latitude 2 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p2x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field p2y from safety_set_allowed_area message + * + * @return y position 2 / Longitude 2 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p2y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field p2z from safety_set_allowed_area message + * + * @return z position 2 / Altitude 2 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p2z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Decode a safety_set_allowed_area message into a struct + * + * @param msg The message to decode + * @param safety_set_allowed_area C-struct to decode the message contents into + */ +static inline void mavlink_msg_safety_set_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_set_allowed_area_t* safety_set_allowed_area) +{ +#if MAVLINK_NEED_BYTE_SWAP + safety_set_allowed_area->p1x = mavlink_msg_safety_set_allowed_area_get_p1x(msg); + safety_set_allowed_area->p1y = mavlink_msg_safety_set_allowed_area_get_p1y(msg); + safety_set_allowed_area->p1z = mavlink_msg_safety_set_allowed_area_get_p1z(msg); + safety_set_allowed_area->p2x = mavlink_msg_safety_set_allowed_area_get_p2x(msg); + safety_set_allowed_area->p2y = mavlink_msg_safety_set_allowed_area_get_p2y(msg); + safety_set_allowed_area->p2z = mavlink_msg_safety_set_allowed_area_get_p2z(msg); + safety_set_allowed_area->target_system = mavlink_msg_safety_set_allowed_area_get_target_system(msg); + safety_set_allowed_area->target_component = mavlink_msg_safety_set_allowed_area_get_target_component(msg); + safety_set_allowed_area->frame = mavlink_msg_safety_set_allowed_area_get_frame(msg); +#else + memcpy(safety_set_allowed_area, _MAV_PAYLOAD(msg), 27); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h new file mode 100644 index 0000000000000000000000000000000000000000..8ff098f39f6714c1b60e5c21ca67f547b586b0f2 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h @@ -0,0 +1,342 @@ +// MESSAGE SCALED_IMU PACKING + +#define MAVLINK_MSG_ID_SCALED_IMU 26 + +typedef struct __mavlink_scaled_imu_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + int16_t xacc; ///< X acceleration (mg) + int16_t yacc; ///< Y acceleration (mg) + int16_t zacc; ///< Z acceleration (mg) + int16_t xgyro; ///< Angular speed around X axis (millirad /sec) + int16_t ygyro; ///< Angular speed around Y axis (millirad /sec) + int16_t zgyro; ///< Angular speed around Z axis (millirad /sec) + int16_t xmag; ///< X Magnetic field (milli tesla) + int16_t ymag; ///< Y Magnetic field (milli tesla) + int16_t zmag; ///< Z Magnetic field (milli tesla) +} mavlink_scaled_imu_t; + +#define MAVLINK_MSG_ID_SCALED_IMU_LEN 22 +#define MAVLINK_MSG_ID_26_LEN 22 + + + +#define MAVLINK_MESSAGE_INFO_SCALED_IMU { \ + "SCALED_IMU", \ + 10, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu_t, time_boot_ms) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, zmag) }, \ + } \ +} + + +/** + * @brief Pack a scaled_imu message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); +#else + mavlink_scaled_imu_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU; + return mavlink_finalize_message(msg, system_id, component_id, 22, 170); +} + +/** + * @brief Pack a scaled_imu message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); +#else + mavlink_scaled_imu_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 170); +} + +/** + * @brief Encode a scaled_imu 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 scaled_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu) +{ + return mavlink_msg_scaled_imu_pack(system_id, component_id, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag); +} + +/** + * @brief Send a scaled_imu message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_imu_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, 22, 170); +#else + mavlink_scaled_imu_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, 22, 170); +#endif +} + +#endif + +// MESSAGE SCALED_IMU UNPACKING + + +/** + * @brief Get field time_boot_ms from scaled_imu message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_scaled_imu_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field xacc from scaled_imu message + * + * @return X acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 4); +} + +/** + * @brief Get field yacc from scaled_imu message + * + * @return Y acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 6); +} + +/** + * @brief Get field zacc from scaled_imu message + * + * @return Z acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field xgyro from scaled_imu message + * + * @return Angular speed around X axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field ygyro from scaled_imu message + * + * @return Angular speed around Y axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field zgyro from scaled_imu message + * + * @return Angular speed around Z axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field xmag from scaled_imu message + * + * @return X Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field ymag from scaled_imu message + * + * @return Y Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 18); +} + +/** + * @brief Get field zmag from scaled_imu message + * + * @return Z Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Decode a scaled_imu message into a struct + * + * @param msg The message to decode + * @param scaled_imu C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_imu_decode(const mavlink_message_t* msg, mavlink_scaled_imu_t* scaled_imu) +{ +#if MAVLINK_NEED_BYTE_SWAP + scaled_imu->time_boot_ms = mavlink_msg_scaled_imu_get_time_boot_ms(msg); + scaled_imu->xacc = mavlink_msg_scaled_imu_get_xacc(msg); + scaled_imu->yacc = mavlink_msg_scaled_imu_get_yacc(msg); + scaled_imu->zacc = mavlink_msg_scaled_imu_get_zacc(msg); + scaled_imu->xgyro = mavlink_msg_scaled_imu_get_xgyro(msg); + scaled_imu->ygyro = mavlink_msg_scaled_imu_get_ygyro(msg); + scaled_imu->zgyro = mavlink_msg_scaled_imu_get_zgyro(msg); + scaled_imu->xmag = mavlink_msg_scaled_imu_get_xmag(msg); + scaled_imu->ymag = mavlink_msg_scaled_imu_get_ymag(msg); + scaled_imu->zmag = mavlink_msg_scaled_imu_get_zmag(msg); +#else + memcpy(scaled_imu, _MAV_PAYLOAD(msg), 22); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h new file mode 100644 index 0000000000000000000000000000000000000000..dac1e0b9a6569e8a1af06a2f63ecfe430ce3de7e --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h @@ -0,0 +1,210 @@ +// MESSAGE SCALED_PRESSURE PACKING + +#define MAVLINK_MSG_ID_SCALED_PRESSURE 29 + +typedef struct __mavlink_scaled_pressure_t +{ + uint32_t time_boot_ms; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + float press_abs; ///< Absolute pressure (hectopascal) + float press_diff; ///< Differential pressure 1 (hectopascal) + int16_t temperature; ///< Temperature measurement (0.01 degrees celsius) +} mavlink_scaled_pressure_t; + +#define MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 14 +#define MAVLINK_MSG_ID_29_LEN 14 + + + +#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \ + "SCALED_PRESSURE", \ + 4, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure_t, time_boot_ms) }, \ + { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure_t, press_abs) }, \ + { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_diff) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure_t, temperature) }, \ + } \ +} + + +/** + * @brief Pack a scaled_pressure message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[14]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); +#else + mavlink_scaled_pressure_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE; + return mavlink_finalize_message(msg, system_id, component_id, 14, 115); +} + +/** + * @brief Pack a scaled_pressure message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[14]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14); +#else + mavlink_scaled_pressure_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 115); +} + +/** + * @brief Encode a scaled_pressure 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 scaled_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure) +{ + return mavlink_msg_scaled_pressure_pack(system_id, component_id, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature); +} + +/** + * @brief Send a scaled_pressure message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_pressure_send(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[14]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, 14, 115); +#else + mavlink_scaled_pressure_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, 14, 115); +#endif +} + +#endif + +// MESSAGE SCALED_PRESSURE UNPACKING + + +/** + * @brief Get field time_boot_ms from scaled_pressure message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint32_t mavlink_msg_scaled_pressure_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field press_abs from scaled_pressure message + * + * @return Absolute pressure (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure_get_press_abs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field press_diff from scaled_pressure message + * + * @return Differential pressure 1 (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure_get_press_diff(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field temperature from scaled_pressure message + * + * @return Temperature measurement (0.01 degrees celsius) + */ +static inline int16_t mavlink_msg_scaled_pressure_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Decode a scaled_pressure message into a struct + * + * @param msg The message to decode + * @param scaled_pressure C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_pressure_decode(const mavlink_message_t* msg, mavlink_scaled_pressure_t* scaled_pressure) +{ +#if MAVLINK_NEED_BYTE_SWAP + scaled_pressure->time_boot_ms = mavlink_msg_scaled_pressure_get_time_boot_ms(msg); + scaled_pressure->press_abs = mavlink_msg_scaled_pressure_get_press_abs(msg); + scaled_pressure->press_diff = mavlink_msg_scaled_pressure_get_press_diff(msg); + scaled_pressure->temperature = mavlink_msg_scaled_pressure_get_temperature(msg); +#else + memcpy(scaled_pressure, _MAV_PAYLOAD(msg), 14); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h new file mode 100644 index 0000000000000000000000000000000000000000..34a58cd76342cf46a7dc21df1ce1226af95ff914 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h @@ -0,0 +1,342 @@ +// MESSAGE SERVO_OUTPUT_RAW PACKING + +#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW 36 + +typedef struct __mavlink_servo_output_raw_t +{ + uint32_t time_usec; ///< Timestamp (since UNIX epoch or microseconds since system boot) + uint16_t servo1_raw; ///< Servo output 1 value, in microseconds + uint16_t servo2_raw; ///< Servo output 2 value, in microseconds + uint16_t servo3_raw; ///< Servo output 3 value, in microseconds + uint16_t servo4_raw; ///< Servo output 4 value, in microseconds + uint16_t servo5_raw; ///< Servo output 5 value, in microseconds + uint16_t servo6_raw; ///< Servo output 6 value, in microseconds + uint16_t servo7_raw; ///< Servo output 7 value, in microseconds + uint16_t servo8_raw; ///< Servo output 8 value, in microseconds + uint8_t port; ///< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. +} mavlink_servo_output_raw_t; + +#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN 21 +#define MAVLINK_MSG_ID_36_LEN 21 + + + +#define MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW { \ + "SERVO_OUTPUT_RAW", \ + 10, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_servo_output_raw_t, time_usec) }, \ + { "servo1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \ + { "servo2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \ + { "servo3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \ + { "servo4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_servo_output_raw_t, servo4_raw) }, \ + { "servo5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_servo_output_raw_t, servo5_raw) }, \ + { "servo6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_servo_output_raw_t, servo6_raw) }, \ + { "servo7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_servo_output_raw_t, servo7_raw) }, \ + { "servo8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_servo_output_raw_t, servo8_raw) }, \ + { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_servo_output_raw_t, port) }, \ + } \ +} + + +/** + * @brief Pack a servo_output_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (since UNIX epoch or microseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param servo1_raw Servo output 1 value, in microseconds + * @param servo2_raw Servo output 2 value, in microseconds + * @param servo3_raw Servo output 3 value, in microseconds + * @param servo4_raw Servo output 4 value, in microseconds + * @param servo5_raw Servo output 5 value, in microseconds + * @param servo6_raw Servo output 6 value, in microseconds + * @param servo7_raw Servo output 7 value, in microseconds + * @param servo8_raw Servo output 8 value, in microseconds + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[21]; + _mav_put_uint32_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 4, servo1_raw); + _mav_put_uint16_t(buf, 6, servo2_raw); + _mav_put_uint16_t(buf, 8, servo3_raw); + _mav_put_uint16_t(buf, 10, servo4_raw); + _mav_put_uint16_t(buf, 12, servo5_raw); + _mav_put_uint16_t(buf, 14, servo6_raw); + _mav_put_uint16_t(buf, 16, servo7_raw); + _mav_put_uint16_t(buf, 18, servo8_raw); + _mav_put_uint8_t(buf, 20, port); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21); +#else + mavlink_servo_output_raw_t packet; + packet.time_usec = time_usec; + packet.servo1_raw = servo1_raw; + packet.servo2_raw = servo2_raw; + packet.servo3_raw = servo3_raw; + packet.servo4_raw = servo4_raw; + packet.servo5_raw = servo5_raw; + packet.servo6_raw = servo6_raw; + packet.servo7_raw = servo7_raw; + packet.servo8_raw = servo8_raw; + packet.port = port; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21); +#endif + + msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; + return mavlink_finalize_message(msg, system_id, component_id, 21, 222); +} + +/** + * @brief Pack a servo_output_raw message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (since UNIX epoch or microseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param servo1_raw Servo output 1 value, in microseconds + * @param servo2_raw Servo output 2 value, in microseconds + * @param servo3_raw Servo output 3 value, in microseconds + * @param servo4_raw Servo output 4 value, in microseconds + * @param servo5_raw Servo output 5 value, in microseconds + * @param servo6_raw Servo output 6 value, in microseconds + * @param servo7_raw Servo output 7 value, in microseconds + * @param servo8_raw Servo output 8 value, in microseconds + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_usec,uint8_t port,uint16_t servo1_raw,uint16_t servo2_raw,uint16_t servo3_raw,uint16_t servo4_raw,uint16_t servo5_raw,uint16_t servo6_raw,uint16_t servo7_raw,uint16_t servo8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[21]; + _mav_put_uint32_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 4, servo1_raw); + _mav_put_uint16_t(buf, 6, servo2_raw); + _mav_put_uint16_t(buf, 8, servo3_raw); + _mav_put_uint16_t(buf, 10, servo4_raw); + _mav_put_uint16_t(buf, 12, servo5_raw); + _mav_put_uint16_t(buf, 14, servo6_raw); + _mav_put_uint16_t(buf, 16, servo7_raw); + _mav_put_uint16_t(buf, 18, servo8_raw); + _mav_put_uint8_t(buf, 20, port); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21); +#else + mavlink_servo_output_raw_t packet; + packet.time_usec = time_usec; + packet.servo1_raw = servo1_raw; + packet.servo2_raw = servo2_raw; + packet.servo3_raw = servo3_raw; + packet.servo4_raw = servo4_raw; + packet.servo5_raw = servo5_raw; + packet.servo6_raw = servo6_raw; + packet.servo7_raw = servo7_raw; + packet.servo8_raw = servo8_raw; + packet.port = port; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21); +#endif + + msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 21, 222); +} + +/** + * @brief Encode a servo_output_raw 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 servo_output_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_servo_output_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw) +{ + return mavlink_msg_servo_output_raw_pack(system_id, component_id, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw); +} + +/** + * @brief Send a servo_output_raw message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (since UNIX epoch or microseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param servo1_raw Servo output 1 value, in microseconds + * @param servo2_raw Servo output 2 value, in microseconds + * @param servo3_raw Servo output 3 value, in microseconds + * @param servo4_raw Servo output 4 value, in microseconds + * @param servo5_raw Servo output 5 value, in microseconds + * @param servo6_raw Servo output 6 value, in microseconds + * @param servo7_raw Servo output 7 value, in microseconds + * @param servo8_raw Servo output 8 value, in microseconds + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[21]; + _mav_put_uint32_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 4, servo1_raw); + _mav_put_uint16_t(buf, 6, servo2_raw); + _mav_put_uint16_t(buf, 8, servo3_raw); + _mav_put_uint16_t(buf, 10, servo4_raw); + _mav_put_uint16_t(buf, 12, servo5_raw); + _mav_put_uint16_t(buf, 14, servo6_raw); + _mav_put_uint16_t(buf, 16, servo7_raw); + _mav_put_uint16_t(buf, 18, servo8_raw); + _mav_put_uint8_t(buf, 20, port); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, 21, 222); +#else + mavlink_servo_output_raw_t packet; + packet.time_usec = time_usec; + packet.servo1_raw = servo1_raw; + packet.servo2_raw = servo2_raw; + packet.servo3_raw = servo3_raw; + packet.servo4_raw = servo4_raw; + packet.servo5_raw = servo5_raw; + packet.servo6_raw = servo6_raw; + packet.servo7_raw = servo7_raw; + packet.servo8_raw = servo8_raw; + packet.port = port; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, 21, 222); +#endif +} + +#endif + +// MESSAGE SERVO_OUTPUT_RAW UNPACKING + + +/** + * @brief Get field time_usec from servo_output_raw message + * + * @return Timestamp (since UNIX epoch or microseconds since system boot) + */ +static inline uint32_t mavlink_msg_servo_output_raw_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field port from servo_output_raw message + * + * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + */ +static inline uint8_t mavlink_msg_servo_output_raw_get_port(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Get field servo1_raw from servo_output_raw message + * + * @return Servo output 1 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo1_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field servo2_raw from servo_output_raw message + * + * @return Servo output 2 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo2_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field servo3_raw from servo_output_raw message + * + * @return Servo output 3 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo3_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field servo4_raw from servo_output_raw message + * + * @return Servo output 4 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo4_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field servo5_raw from servo_output_raw message + * + * @return Servo output 5 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo5_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field servo6_raw from servo_output_raw message + * + * @return Servo output 6 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo6_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Get field servo7_raw from servo_output_raw message + * + * @return Servo output 7 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo7_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field servo8_raw from servo_output_raw message + * + * @return Servo output 8 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo8_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Decode a servo_output_raw message into a struct + * + * @param msg The message to decode + * @param servo_output_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_servo_output_raw_decode(const mavlink_message_t* msg, mavlink_servo_output_raw_t* servo_output_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP + servo_output_raw->time_usec = mavlink_msg_servo_output_raw_get_time_usec(msg); + servo_output_raw->servo1_raw = mavlink_msg_servo_output_raw_get_servo1_raw(msg); + servo_output_raw->servo2_raw = mavlink_msg_servo_output_raw_get_servo2_raw(msg); + servo_output_raw->servo3_raw = mavlink_msg_servo_output_raw_get_servo3_raw(msg); + servo_output_raw->servo4_raw = mavlink_msg_servo_output_raw_get_servo4_raw(msg); + servo_output_raw->servo5_raw = mavlink_msg_servo_output_raw_get_servo5_raw(msg); + servo_output_raw->servo6_raw = mavlink_msg_servo_output_raw_get_servo6_raw(msg); + servo_output_raw->servo7_raw = mavlink_msg_servo_output_raw_get_servo7_raw(msg); + servo_output_raw->servo8_raw = mavlink_msg_servo_output_raw_get_servo8_raw(msg); + servo_output_raw->port = mavlink_msg_servo_output_raw_get_port(msg); +#else + memcpy(servo_output_raw, _MAV_PAYLOAD(msg), 21); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h new file mode 100644 index 0000000000000000000000000000000000000000..5b706fb506747617c639ef2a8bef12eeb6bde629 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h @@ -0,0 +1,232 @@ +// MESSAGE SET_GLOBAL_POSITION_SETPOINT_INT PACKING + +#define MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT 53 + +typedef struct __mavlink_set_global_position_setpoint_int_t +{ + int32_t latitude; ///< WGS84 Latitude position in degrees * 1E7 + int32_t longitude; ///< WGS84 Longitude position in degrees * 1E7 + int32_t altitude; ///< WGS84 Altitude in meters * 1000 (positive for up) + int16_t yaw; ///< Desired yaw angle in degrees * 100 + uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT +} mavlink_set_global_position_setpoint_int_t; + +#define MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN 15 +#define MAVLINK_MSG_ID_53_LEN 15 + + + +#define MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT { \ + "SET_GLOBAL_POSITION_SETPOINT_INT", \ + 5, \ + { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_global_position_setpoint_int_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_global_position_setpoint_int_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_global_position_setpoint_int_t, altitude) }, \ + { "yaw", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_set_global_position_setpoint_int_t, yaw) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_set_global_position_setpoint_int_t, coordinate_frame) }, \ + } \ +} + + +/** + * @brief Pack a set_global_position_setpoint_int 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 coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT + * @param latitude WGS84 Latitude position in degrees * 1E7 + * @param longitude WGS84 Longitude position in degrees * 1E7 + * @param altitude WGS84 Altitude in meters * 1000 (positive for up) + * @param yaw Desired yaw angle in degrees * 100 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_global_position_setpoint_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[15]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_int16_t(buf, 12, yaw); + _mav_put_uint8_t(buf, 14, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); +#else + mavlink_set_global_position_setpoint_int_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.yaw = yaw; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT; + return mavlink_finalize_message(msg, system_id, component_id, 15, 33); +} + +/** + * @brief Pack a set_global_position_setpoint_int 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 coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT + * @param latitude WGS84 Latitude position in degrees * 1E7 + * @param longitude WGS84 Longitude position in degrees * 1E7 + * @param altitude WGS84 Altitude in meters * 1000 (positive for up) + * @param yaw Desired yaw angle in degrees * 100 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_global_position_setpoint_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t coordinate_frame,int32_t latitude,int32_t longitude,int32_t altitude,int16_t yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[15]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_int16_t(buf, 12, yaw); + _mav_put_uint8_t(buf, 14, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15); +#else + mavlink_set_global_position_setpoint_int_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.yaw = yaw; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 15, 33); +} + +/** + * @brief Encode a set_global_position_setpoint_int 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 set_global_position_setpoint_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_global_position_setpoint_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_global_position_setpoint_int_t* set_global_position_setpoint_int) +{ + return mavlink_msg_set_global_position_setpoint_int_pack(system_id, component_id, msg, set_global_position_setpoint_int->coordinate_frame, set_global_position_setpoint_int->latitude, set_global_position_setpoint_int->longitude, set_global_position_setpoint_int->altitude, set_global_position_setpoint_int->yaw); +} + +/** + * @brief Send a set_global_position_setpoint_int message + * @param chan MAVLink channel to send the message + * + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT + * @param latitude WGS84 Latitude position in degrees * 1E7 + * @param longitude WGS84 Longitude position in degrees * 1E7 + * @param altitude WGS84 Altitude in meters * 1000 (positive for up) + * @param yaw Desired yaw angle in degrees * 100 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_global_position_setpoint_int_send(mavlink_channel_t chan, uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[15]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_int16_t(buf, 12, yaw); + _mav_put_uint8_t(buf, 14, coordinate_frame); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, buf, 15, 33); +#else + mavlink_set_global_position_setpoint_int_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.yaw = yaw; + packet.coordinate_frame = coordinate_frame; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, 15, 33); +#endif +} + +#endif + +// MESSAGE SET_GLOBAL_POSITION_SETPOINT_INT UNPACKING + + +/** + * @brief Get field coordinate_frame from set_global_position_setpoint_int message + * + * @return Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT + */ +static inline uint8_t mavlink_msg_set_global_position_setpoint_int_get_coordinate_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 14); +} + +/** + * @brief Get field latitude from set_global_position_setpoint_int message + * + * @return WGS84 Latitude position in degrees * 1E7 + */ +static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_latitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field longitude from set_global_position_setpoint_int message + * + * @return WGS84 Longitude position in degrees * 1E7 + */ +static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_longitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field altitude from set_global_position_setpoint_int message + * + * @return WGS84 Altitude in meters * 1000 (positive for up) + */ +static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field yaw from set_global_position_setpoint_int message + * + * @return Desired yaw angle in degrees * 100 + */ +static inline int16_t mavlink_msg_set_global_position_setpoint_int_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Decode a set_global_position_setpoint_int message into a struct + * + * @param msg The message to decode + * @param set_global_position_setpoint_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_global_position_setpoint_int_decode(const mavlink_message_t* msg, mavlink_set_global_position_setpoint_int_t* set_global_position_setpoint_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_global_position_setpoint_int->latitude = mavlink_msg_set_global_position_setpoint_int_get_latitude(msg); + set_global_position_setpoint_int->longitude = mavlink_msg_set_global_position_setpoint_int_get_longitude(msg); + set_global_position_setpoint_int->altitude = mavlink_msg_set_global_position_setpoint_int_get_altitude(msg); + set_global_position_setpoint_int->yaw = mavlink_msg_set_global_position_setpoint_int_get_yaw(msg); + set_global_position_setpoint_int->coordinate_frame = mavlink_msg_set_global_position_setpoint_int_get_coordinate_frame(msg); +#else + memcpy(set_global_position_setpoint_int, _MAV_PAYLOAD(msg), 15); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h new file mode 100644 index 0000000000000000000000000000000000000000..af404b1108e720c47f6f7ee85c96fd477f5c6751 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h @@ -0,0 +1,210 @@ +// MESSAGE SET_GPS_GLOBAL_ORIGIN PACKING + +#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN 48 + +typedef struct __mavlink_set_gps_global_origin_t +{ + int32_t latitude; ///< global position * 1E7 + int32_t longitude; ///< global position * 1E7 + int32_t altitude; ///< global position * 1000 + uint8_t target_system; ///< System ID +} mavlink_set_gps_global_origin_t; + +#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN 13 +#define MAVLINK_MSG_ID_48_LEN 13 + + + +#define MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN { \ + "SET_GPS_GLOBAL_ORIGIN", \ + 4, \ + { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_gps_global_origin_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_gps_global_origin_t, altitude) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \ + } \ +} + + +/** + * @brief Pack a set_gps_global_origin 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 target_system System ID + * @param latitude global position * 1E7 + * @param longitude global position * 1E7 + * @param altitude global position * 1000 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[13]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_uint8_t(buf, 12, target_system); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13); +#else + mavlink_set_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.target_system = target_system; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN; + return mavlink_finalize_message(msg, system_id, component_id, 13, 41); +} + +/** + * @brief Pack a set_gps_global_origin 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 target_system System ID + * @param latitude global position * 1E7 + * @param longitude global position * 1E7 + * @param altitude global position * 1000 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,int32_t latitude,int32_t longitude,int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[13]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_uint8_t(buf, 12, target_system); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13); +#else + mavlink_set_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.target_system = target_system; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 13, 41); +} + +/** + * @brief Encode a set_gps_global_origin 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 set_gps_global_origin C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_gps_global_origin_t* set_gps_global_origin) +{ + return mavlink_msg_set_gps_global_origin_pack(system_id, component_id, msg, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude); +} + +/** + * @brief Send a set_gps_global_origin message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param latitude global position * 1E7 + * @param longitude global position * 1E7 + * @param altitude global position * 1000 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_gps_global_origin_send(mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[13]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_uint8_t(buf, 12, target_system); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, 13, 41); +#else + mavlink_set_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.target_system = target_system; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)&packet, 13, 41); +#endif +} + +#endif + +// MESSAGE SET_GPS_GLOBAL_ORIGIN UNPACKING + + +/** + * @brief Get field target_system from set_gps_global_origin message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_gps_global_origin_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field latitude from set_gps_global_origin message + * + * @return global position * 1E7 + */ +static inline int32_t mavlink_msg_set_gps_global_origin_get_latitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field longitude from set_gps_global_origin message + * + * @return global position * 1E7 + */ +static inline int32_t mavlink_msg_set_gps_global_origin_get_longitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field altitude from set_gps_global_origin message + * + * @return global position * 1000 + */ +static inline int32_t mavlink_msg_set_gps_global_origin_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Decode a set_gps_global_origin message into a struct + * + * @param msg The message to decode + * @param set_gps_global_origin C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_set_gps_global_origin_t* set_gps_global_origin) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_gps_global_origin->latitude = mavlink_msg_set_gps_global_origin_get_latitude(msg); + set_gps_global_origin->longitude = mavlink_msg_set_gps_global_origin_get_longitude(msg); + set_gps_global_origin->altitude = mavlink_msg_set_gps_global_origin_get_altitude(msg); + set_gps_global_origin->target_system = mavlink_msg_set_gps_global_origin_get_target_system(msg); +#else + memcpy(set_gps_global_origin, _MAV_PAYLOAD(msg), 13); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h new file mode 100644 index 0000000000000000000000000000000000000000..233e07d65cc9aa8c79f90830e81c4377c69934c0 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h @@ -0,0 +1,276 @@ +// MESSAGE SET_LOCAL_POSITION_SETPOINT PACKING + +#define MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT 50 + +typedef struct __mavlink_set_local_position_setpoint_t +{ + float x; ///< x position + float y; ///< y position + float z; ///< z position + float yaw; ///< Desired yaw angle + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU +} mavlink_set_local_position_setpoint_t; + +#define MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN 19 +#define MAVLINK_MSG_ID_50_LEN 19 + + + +#define MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT { \ + "SET_LOCAL_POSITION_SETPOINT", \ + 7, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_local_position_setpoint_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_local_position_setpoint_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_local_position_setpoint_t, z) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_local_position_setpoint_t, yaw) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_set_local_position_setpoint_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_set_local_position_setpoint_t, target_component) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_set_local_position_setpoint_t, coordinate_frame) }, \ + } \ +} + + +/** + * @brief Pack a set_local_position_setpoint message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU + * @param x x position + * @param y y position + * @param z z position + * @param yaw Desired yaw angle + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_local_position_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, float x, float y, float z, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[19]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + _mav_put_uint8_t(buf, 18, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 19); +#else + mavlink_set_local_position_setpoint_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 19); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT; + return mavlink_finalize_message(msg, system_id, component_id, 19, 214); +} + +/** + * @brief Pack a set_local_position_setpoint message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU + * @param x x position + * @param y y position + * @param z z position + * @param yaw Desired yaw angle + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_local_position_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,float x,float y,float z,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[19]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + _mav_put_uint8_t(buf, 18, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 19); +#else + mavlink_set_local_position_setpoint_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 19); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 19, 214); +} + +/** + * @brief Encode a set_local_position_setpoint struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_local_position_setpoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_local_position_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_local_position_setpoint_t* set_local_position_setpoint) +{ + return mavlink_msg_set_local_position_setpoint_pack(system_id, component_id, msg, set_local_position_setpoint->target_system, set_local_position_setpoint->target_component, set_local_position_setpoint->coordinate_frame, set_local_position_setpoint->x, set_local_position_setpoint->y, set_local_position_setpoint->z, set_local_position_setpoint->yaw); +} + +/** + * @brief Send a set_local_position_setpoint message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU + * @param x x position + * @param y y position + * @param z z position + * @param yaw Desired yaw angle + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_local_position_setpoint_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, float x, float y, float z, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[19]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + _mav_put_uint8_t(buf, 18, coordinate_frame); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, buf, 19, 214); +#else + mavlink_set_local_position_setpoint_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, (const char *)&packet, 19, 214); +#endif +} + +#endif + +// MESSAGE SET_LOCAL_POSITION_SETPOINT UNPACKING + + +/** + * @brief Get field target_system from set_local_position_setpoint message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_local_position_setpoint_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field target_component from set_local_position_setpoint message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_local_position_setpoint_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field coordinate_frame from set_local_position_setpoint message + * + * @return Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU + */ +static inline uint8_t mavlink_msg_set_local_position_setpoint_get_coordinate_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 18); +} + +/** + * @brief Get field x from set_local_position_setpoint message + * + * @return x position + */ +static inline float mavlink_msg_set_local_position_setpoint_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field y from set_local_position_setpoint message + * + * @return y position + */ +static inline float mavlink_msg_set_local_position_setpoint_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field z from set_local_position_setpoint message + * + * @return z position + */ +static inline float mavlink_msg_set_local_position_setpoint_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw from set_local_position_setpoint message + * + * @return Desired yaw angle + */ +static inline float mavlink_msg_set_local_position_setpoint_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a set_local_position_setpoint message into a struct + * + * @param msg The message to decode + * @param set_local_position_setpoint C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_local_position_setpoint_decode(const mavlink_message_t* msg, mavlink_set_local_position_setpoint_t* set_local_position_setpoint) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_local_position_setpoint->x = mavlink_msg_set_local_position_setpoint_get_x(msg); + set_local_position_setpoint->y = mavlink_msg_set_local_position_setpoint_get_y(msg); + set_local_position_setpoint->z = mavlink_msg_set_local_position_setpoint_get_z(msg); + set_local_position_setpoint->yaw = mavlink_msg_set_local_position_setpoint_get_yaw(msg); + set_local_position_setpoint->target_system = mavlink_msg_set_local_position_setpoint_get_target_system(msg); + set_local_position_setpoint->target_component = mavlink_msg_set_local_position_setpoint_get_target_component(msg); + set_local_position_setpoint->coordinate_frame = mavlink_msg_set_local_position_setpoint_get_coordinate_frame(msg); +#else + memcpy(set_local_position_setpoint, _MAV_PAYLOAD(msg), 19); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h new file mode 100644 index 0000000000000000000000000000000000000000..fec21ab13791a0a20706423fb387bf1469b772fb --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h @@ -0,0 +1,188 @@ +// MESSAGE SET_MODE PACKING + +#define MAVLINK_MSG_ID_SET_MODE 11 + +typedef struct __mavlink_set_mode_t +{ + uint32_t custom_mode; ///< The new autopilot-specific mode. This field can be ignored by an autopilot. + uint8_t target_system; ///< The system setting the mode + uint8_t base_mode; ///< The new base mode +} mavlink_set_mode_t; + +#define MAVLINK_MSG_ID_SET_MODE_LEN 6 +#define MAVLINK_MSG_ID_11_LEN 6 + + + +#define MAVLINK_MESSAGE_INFO_SET_MODE { \ + "SET_MODE", \ + 3, \ + { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \ + { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \ + } \ +} + + +/** + * @brief Pack a set_mode 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 target_system The system setting the mode + * @param base_mode The new base mode + * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, base_mode); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); +#else + mavlink_set_mode_t packet; + packet.custom_mode = custom_mode; + packet.target_system = target_system; + packet.base_mode = base_mode; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_MODE; + return mavlink_finalize_message(msg, system_id, component_id, 6, 89); +} + +/** + * @brief Pack a set_mode 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 target_system The system setting the mode + * @param base_mode The new base mode + * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t base_mode,uint32_t custom_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, base_mode); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); +#else + mavlink_set_mode_t packet; + packet.custom_mode = custom_mode; + packet.target_system = target_system; + packet.base_mode = base_mode; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_MODE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 89); +} + +/** + * @brief Encode a set_mode 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 set_mode C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode) +{ + return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode); +} + +/** + * @brief Send a set_mode message + * @param chan MAVLink channel to send the message + * + * @param target_system The system setting the mode + * @param base_mode The new base mode + * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, base_mode); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, 6, 89); +#else + mavlink_set_mode_t packet; + packet.custom_mode = custom_mode; + packet.target_system = target_system; + packet.base_mode = base_mode; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)&packet, 6, 89); +#endif +} + +#endif + +// MESSAGE SET_MODE UNPACKING + + +/** + * @brief Get field target_system from set_mode message + * + * @return The system setting the mode + */ +static inline uint8_t mavlink_msg_set_mode_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field base_mode from set_mode message + * + * @return The new base mode + */ +static inline uint8_t mavlink_msg_set_mode_get_base_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field custom_mode from set_mode message + * + * @return The new autopilot-specific mode. This field can be ignored by an autopilot. + */ +static inline uint32_t mavlink_msg_set_mode_get_custom_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Decode a set_mode message into a struct + * + * @param msg The message to decode + * @param set_mode C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_mode_decode(const mavlink_message_t* msg, mavlink_set_mode_t* set_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_mode->custom_mode = mavlink_msg_set_mode_get_custom_mode(msg); + set_mode->target_system = mavlink_msg_set_mode_get_target_system(msg); + set_mode->base_mode = mavlink_msg_set_mode_get_base_mode(msg); +#else + memcpy(set_mode, _MAV_PAYLOAD(msg), 6); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h new file mode 100644 index 0000000000000000000000000000000000000000..40ff8998ec46367418e6cf28a61f21b740d7a2d4 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h @@ -0,0 +1,232 @@ +// MESSAGE SET_QUAD_MOTORS_SETPOINT PACKING + +#define MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT 60 + +typedef struct __mavlink_set_quad_motors_setpoint_t +{ + uint16_t motor_front_nw; ///< Front motor in + configuration, front left motor in x configuration + uint16_t motor_right_ne; ///< Right motor in + configuration, front right motor in x configuration + uint16_t motor_back_se; ///< Back motor in + configuration, back right motor in x configuration + uint16_t motor_left_sw; ///< Left motor in + configuration, back left motor in x configuration + uint8_t target_system; ///< System ID of the system that should set these motor commands +} mavlink_set_quad_motors_setpoint_t; + +#define MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN 9 +#define MAVLINK_MSG_ID_60_LEN 9 + + + +#define MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT { \ + "SET_QUAD_MOTORS_SETPOINT", \ + 5, \ + { { "motor_front_nw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_set_quad_motors_setpoint_t, motor_front_nw) }, \ + { "motor_right_ne", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_set_quad_motors_setpoint_t, motor_right_ne) }, \ + { "motor_back_se", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_set_quad_motors_setpoint_t, motor_back_se) }, \ + { "motor_left_sw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_set_quad_motors_setpoint_t, motor_left_sw) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_set_quad_motors_setpoint_t, target_system) }, \ + } \ +} + + +/** + * @brief Pack a set_quad_motors_setpoint message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID of the system that should set these motor commands + * @param motor_front_nw Front motor in + configuration, front left motor in x configuration + * @param motor_right_ne Right motor in + configuration, front right motor in x configuration + * @param motor_back_se Back motor in + configuration, back right motor in x configuration + * @param motor_left_sw Left motor in + configuration, back left motor in x configuration + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_quad_motors_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint16_t motor_front_nw, uint16_t motor_right_ne, uint16_t motor_back_se, uint16_t motor_left_sw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint16_t(buf, 0, motor_front_nw); + _mav_put_uint16_t(buf, 2, motor_right_ne); + _mav_put_uint16_t(buf, 4, motor_back_se); + _mav_put_uint16_t(buf, 6, motor_left_sw); + _mav_put_uint8_t(buf, 8, target_system); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); +#else + mavlink_set_quad_motors_setpoint_t packet; + packet.motor_front_nw = motor_front_nw; + packet.motor_right_ne = motor_right_ne; + packet.motor_back_se = motor_back_se; + packet.motor_left_sw = motor_left_sw; + packet.target_system = target_system; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT; + return mavlink_finalize_message(msg, system_id, component_id, 9, 30); +} + +/** + * @brief Pack a set_quad_motors_setpoint message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID of the system that should set these motor commands + * @param motor_front_nw Front motor in + configuration, front left motor in x configuration + * @param motor_right_ne Right motor in + configuration, front right motor in x configuration + * @param motor_back_se Back motor in + configuration, back right motor in x configuration + * @param motor_left_sw Left motor in + configuration, back left motor in x configuration + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_quad_motors_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint16_t motor_front_nw,uint16_t motor_right_ne,uint16_t motor_back_se,uint16_t motor_left_sw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint16_t(buf, 0, motor_front_nw); + _mav_put_uint16_t(buf, 2, motor_right_ne); + _mav_put_uint16_t(buf, 4, motor_back_se); + _mav_put_uint16_t(buf, 6, motor_left_sw); + _mav_put_uint8_t(buf, 8, target_system); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); +#else + mavlink_set_quad_motors_setpoint_t packet; + packet.motor_front_nw = motor_front_nw; + packet.motor_right_ne = motor_right_ne; + packet.motor_back_se = motor_back_se; + packet.motor_left_sw = motor_left_sw; + packet.target_system = target_system; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 30); +} + +/** + * @brief Encode a set_quad_motors_setpoint struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_quad_motors_setpoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_quad_motors_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_quad_motors_setpoint_t* set_quad_motors_setpoint) +{ + return mavlink_msg_set_quad_motors_setpoint_pack(system_id, component_id, msg, set_quad_motors_setpoint->target_system, set_quad_motors_setpoint->motor_front_nw, set_quad_motors_setpoint->motor_right_ne, set_quad_motors_setpoint->motor_back_se, set_quad_motors_setpoint->motor_left_sw); +} + +/** + * @brief Send a set_quad_motors_setpoint message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID of the system that should set these motor commands + * @param motor_front_nw Front motor in + configuration, front left motor in x configuration + * @param motor_right_ne Right motor in + configuration, front right motor in x configuration + * @param motor_back_se Back motor in + configuration, back right motor in x configuration + * @param motor_left_sw Left motor in + configuration, back left motor in x configuration + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_quad_motors_setpoint_send(mavlink_channel_t chan, uint8_t target_system, uint16_t motor_front_nw, uint16_t motor_right_ne, uint16_t motor_back_se, uint16_t motor_left_sw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint16_t(buf, 0, motor_front_nw); + _mav_put_uint16_t(buf, 2, motor_right_ne); + _mav_put_uint16_t(buf, 4, motor_back_se); + _mav_put_uint16_t(buf, 6, motor_left_sw); + _mav_put_uint8_t(buf, 8, target_system); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, buf, 9, 30); +#else + mavlink_set_quad_motors_setpoint_t packet; + packet.motor_front_nw = motor_front_nw; + packet.motor_right_ne = motor_right_ne; + packet.motor_back_se = motor_back_se; + packet.motor_left_sw = motor_left_sw; + packet.target_system = target_system; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, (const char *)&packet, 9, 30); +#endif +} + +#endif + +// MESSAGE SET_QUAD_MOTORS_SETPOINT UNPACKING + + +/** + * @brief Get field target_system from set_quad_motors_setpoint message + * + * @return System ID of the system that should set these motor commands + */ +static inline uint8_t mavlink_msg_set_quad_motors_setpoint_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Get field motor_front_nw from set_quad_motors_setpoint message + * + * @return Front motor in + configuration, front left motor in x configuration + */ +static inline uint16_t mavlink_msg_set_quad_motors_setpoint_get_motor_front_nw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field motor_right_ne from set_quad_motors_setpoint message + * + * @return Right motor in + configuration, front right motor in x configuration + */ +static inline uint16_t mavlink_msg_set_quad_motors_setpoint_get_motor_right_ne(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Get field motor_back_se from set_quad_motors_setpoint message + * + * @return Back motor in + configuration, back right motor in x configuration + */ +static inline uint16_t mavlink_msg_set_quad_motors_setpoint_get_motor_back_se(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field motor_left_sw from set_quad_motors_setpoint message + * + * @return Left motor in + configuration, back left motor in x configuration + */ +static inline uint16_t mavlink_msg_set_quad_motors_setpoint_get_motor_left_sw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Decode a set_quad_motors_setpoint message into a struct + * + * @param msg The message to decode + * @param set_quad_motors_setpoint C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_quad_motors_setpoint_decode(const mavlink_message_t* msg, mavlink_set_quad_motors_setpoint_t* set_quad_motors_setpoint) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_quad_motors_setpoint->motor_front_nw = mavlink_msg_set_quad_motors_setpoint_get_motor_front_nw(msg); + set_quad_motors_setpoint->motor_right_ne = mavlink_msg_set_quad_motors_setpoint_get_motor_right_ne(msg); + set_quad_motors_setpoint->motor_back_se = mavlink_msg_set_quad_motors_setpoint_get_motor_back_se(msg); + set_quad_motors_setpoint->motor_left_sw = mavlink_msg_set_quad_motors_setpoint_get_motor_left_sw(msg); + set_quad_motors_setpoint->target_system = mavlink_msg_set_quad_motors_setpoint_get_target_system(msg); +#else + memcpy(set_quad_motors_setpoint, _MAV_PAYLOAD(msg), 9); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h new file mode 100644 index 0000000000000000000000000000000000000000..c3ea8de408cd4a9aac96f756b5c84dbf3b78c9ff --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h @@ -0,0 +1,236 @@ +// MESSAGE SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST PACKING + +#define MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST 61 + +typedef struct __mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t +{ + int16_t roll[6]; ///< Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5 + int16_t pitch[6]; ///< Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5 + int16_t yaw[6]; ///< Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5 + uint16_t thrust[6]; ///< Collective thrust, scaled to uint16 for 6 quadrotors: 0..5 + uint8_t target_systems[6]; ///< System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs +} mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t; + +#define MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN 54 +#define MAVLINK_MSG_ID_61_LEN 54 + +#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_ROLL_LEN 6 +#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_PITCH_LEN 6 +#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_YAW_LEN 6 +#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_THRUST_LEN 6 +#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_TARGET_SYSTEMS_LEN 6 + +#define MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST { \ + "SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST", \ + 5, \ + { { "roll", NULL, MAVLINK_TYPE_INT16_T, 6, 0, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_INT16_T, 6, 12, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_INT16_T, 6, 24, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, yaw) }, \ + { "thrust", NULL, MAVLINK_TYPE_UINT16_T, 6, 36, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, thrust) }, \ + { "target_systems", NULL, MAVLINK_TYPE_UINT8_T, 6, 48, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, target_systems) }, \ + } \ +} + + +/** + * @brief Pack a set_quad_swarm_roll_pitch_yaw_thrust 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 target_systems System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs + * @param roll Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5 + * @param pitch Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5 + * @param yaw Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5 + * @param thrust Collective thrust, scaled to uint16 for 6 quadrotors: 0..5 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const uint8_t *target_systems, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[54]; + + _mav_put_int16_t_array(buf, 0, roll, 6); + _mav_put_int16_t_array(buf, 12, pitch, 6); + _mav_put_int16_t_array(buf, 24, yaw, 6); + _mav_put_uint16_t_array(buf, 36, thrust, 6); + _mav_put_uint8_t_array(buf, 48, target_systems, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 54); +#else + mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet; + + mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*6); + mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*6); + mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*6); + mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*6); + mav_array_memcpy(packet.target_systems, target_systems, sizeof(uint8_t)*6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 54); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST; + return mavlink_finalize_message(msg, system_id, component_id, 54, 200); +} + +/** + * @brief Pack a set_quad_swarm_roll_pitch_yaw_thrust 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 target_systems System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs + * @param roll Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5 + * @param pitch Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5 + * @param yaw Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5 + * @param thrust Collective thrust, scaled to uint16 for 6 quadrotors: 0..5 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const uint8_t *target_systems,const int16_t *roll,const int16_t *pitch,const int16_t *yaw,const uint16_t *thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[54]; + + _mav_put_int16_t_array(buf, 0, roll, 6); + _mav_put_int16_t_array(buf, 12, pitch, 6); + _mav_put_int16_t_array(buf, 24, yaw, 6); + _mav_put_uint16_t_array(buf, 36, thrust, 6); + _mav_put_uint8_t_array(buf, 48, target_systems, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 54); +#else + mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet; + + mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*6); + mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*6); + mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*6); + mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*6); + mav_array_memcpy(packet.target_systems, target_systems, sizeof(uint8_t)*6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 54); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 54, 200); +} + +/** + * @brief Encode a set_quad_swarm_roll_pitch_yaw_thrust 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 set_quad_swarm_roll_pitch_yaw_thrust C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t* set_quad_swarm_roll_pitch_yaw_thrust) +{ + return mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack(system_id, component_id, msg, set_quad_swarm_roll_pitch_yaw_thrust->target_systems, set_quad_swarm_roll_pitch_yaw_thrust->roll, set_quad_swarm_roll_pitch_yaw_thrust->pitch, set_quad_swarm_roll_pitch_yaw_thrust->yaw, set_quad_swarm_roll_pitch_yaw_thrust->thrust); +} + +/** + * @brief Send a set_quad_swarm_roll_pitch_yaw_thrust message + * @param chan MAVLink channel to send the message + * + * @param target_systems System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs + * @param roll Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5 + * @param pitch Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5 + * @param yaw Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5 + * @param thrust Collective thrust, scaled to uint16 for 6 quadrotors: 0..5 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_send(mavlink_channel_t chan, const uint8_t *target_systems, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[54]; + + _mav_put_int16_t_array(buf, 0, roll, 6); + _mav_put_int16_t_array(buf, 12, pitch, 6); + _mav_put_int16_t_array(buf, 24, yaw, 6); + _mav_put_uint16_t_array(buf, 36, thrust, 6); + _mav_put_uint8_t_array(buf, 48, target_systems, 6); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, buf, 54, 200); +#else + mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet; + + mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*6); + mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*6); + mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*6); + mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*6); + mav_array_memcpy(packet.target_systems, target_systems, sizeof(uint8_t)*6); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, (const char *)&packet, 54, 200); +#endif +} + +#endif + +// MESSAGE SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST UNPACKING + + +/** + * @brief Get field target_systems from set_quad_swarm_roll_pitch_yaw_thrust message + * + * @return System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs + */ +static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_target_systems(const mavlink_message_t* msg, uint8_t *target_systems) +{ + return _MAV_RETURN_uint8_t_array(msg, target_systems, 6, 48); +} + +/** + * @brief Get field roll from set_quad_swarm_roll_pitch_yaw_thrust message + * + * @return Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5 + */ +static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_roll(const mavlink_message_t* msg, int16_t *roll) +{ + return _MAV_RETURN_int16_t_array(msg, roll, 6, 0); +} + +/** + * @brief Get field pitch from set_quad_swarm_roll_pitch_yaw_thrust message + * + * @return Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5 + */ +static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_pitch(const mavlink_message_t* msg, int16_t *pitch) +{ + return _MAV_RETURN_int16_t_array(msg, pitch, 6, 12); +} + +/** + * @brief Get field yaw from set_quad_swarm_roll_pitch_yaw_thrust message + * + * @return Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5 + */ +static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_yaw(const mavlink_message_t* msg, int16_t *yaw) +{ + return _MAV_RETURN_int16_t_array(msg, yaw, 6, 24); +} + +/** + * @brief Get field thrust from set_quad_swarm_roll_pitch_yaw_thrust message + * + * @return Collective thrust, scaled to uint16 for 6 quadrotors: 0..5 + */ +static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_thrust(const mavlink_message_t* msg, uint16_t *thrust) +{ + return _MAV_RETURN_uint16_t_array(msg, thrust, 6, 36); +} + +/** + * @brief Decode a set_quad_swarm_roll_pitch_yaw_thrust message into a struct + * + * @param msg The message to decode + * @param set_quad_swarm_roll_pitch_yaw_thrust C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(const mavlink_message_t* msg, mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t* set_quad_swarm_roll_pitch_yaw_thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP + mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_roll(msg, set_quad_swarm_roll_pitch_yaw_thrust->roll); + mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_pitch(msg, set_quad_swarm_roll_pitch_yaw_thrust->pitch); + mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_yaw(msg, set_quad_swarm_roll_pitch_yaw_thrust->yaw); + mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_thrust(msg, set_quad_swarm_roll_pitch_yaw_thrust->thrust); + mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_target_systems(msg, set_quad_swarm_roll_pitch_yaw_thrust->target_systems); +#else + memcpy(set_quad_swarm_roll_pitch_yaw_thrust, _MAV_PAYLOAD(msg), 54); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h new file mode 100644 index 0000000000000000000000000000000000000000..b79a7e9f2fd3bb519d36acf0d70b65e74e9604b7 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h @@ -0,0 +1,254 @@ +// MESSAGE SET_ROLL_PITCH_YAW_SPEED_THRUST PACKING + +#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST 57 + +typedef struct __mavlink_set_roll_pitch_yaw_speed_thrust_t +{ + float roll_speed; ///< Desired roll angular speed in rad/s + float pitch_speed; ///< Desired pitch angular speed in rad/s + float yaw_speed; ///< Desired yaw angular speed in rad/s + float thrust; ///< Collective thrust, normalized to 0 .. 1 + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_set_roll_pitch_yaw_speed_thrust_t; + +#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN 18 +#define MAVLINK_MSG_ID_57_LEN 18 + + + +#define MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST { \ + "SET_ROLL_PITCH_YAW_SPEED_THRUST", \ + 6, \ + { { "roll_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, roll_speed) }, \ + { "pitch_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, pitch_speed) }, \ + { "yaw_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, yaw_speed) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, thrust) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a set_roll_pitch_yaw_speed_thrust 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 target_system System ID + * @param target_component Component ID + * @param roll_speed Desired roll angular speed in rad/s + * @param pitch_speed Desired pitch angular speed in rad/s + * @param yaw_speed Desired yaw angular speed in rad/s + * @param thrust Collective thrust, normalized to 0 .. 1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, roll_speed); + _mav_put_float(buf, 4, pitch_speed); + _mav_put_float(buf, 8, yaw_speed); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); +#else + mavlink_set_roll_pitch_yaw_speed_thrust_t packet; + packet.roll_speed = roll_speed; + packet.pitch_speed = pitch_speed; + packet.yaw_speed = yaw_speed; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST; + return mavlink_finalize_message(msg, system_id, component_id, 18, 24); +} + +/** + * @brief Pack a set_roll_pitch_yaw_speed_thrust 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 target_system System ID + * @param target_component Component ID + * @param roll_speed Desired roll angular speed in rad/s + * @param pitch_speed Desired pitch angular speed in rad/s + * @param yaw_speed Desired yaw angular speed in rad/s + * @param thrust Collective thrust, normalized to 0 .. 1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,float roll_speed,float pitch_speed,float yaw_speed,float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, roll_speed); + _mav_put_float(buf, 4, pitch_speed); + _mav_put_float(buf, 8, yaw_speed); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); +#else + mavlink_set_roll_pitch_yaw_speed_thrust_t packet; + packet.roll_speed = roll_speed; + packet.pitch_speed = pitch_speed; + packet.yaw_speed = yaw_speed; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 24); +} + +/** + * @brief Encode a set_roll_pitch_yaw_speed_thrust 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 set_roll_pitch_yaw_speed_thrust C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_speed_thrust_t* set_roll_pitch_yaw_speed_thrust) +{ + return mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(system_id, component_id, msg, set_roll_pitch_yaw_speed_thrust->target_system, set_roll_pitch_yaw_speed_thrust->target_component, set_roll_pitch_yaw_speed_thrust->roll_speed, set_roll_pitch_yaw_speed_thrust->pitch_speed, set_roll_pitch_yaw_speed_thrust->yaw_speed, set_roll_pitch_yaw_speed_thrust->thrust); +} + +/** + * @brief Send a set_roll_pitch_yaw_speed_thrust message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param roll_speed Desired roll angular speed in rad/s + * @param pitch_speed Desired pitch angular speed in rad/s + * @param yaw_speed Desired yaw angular speed in rad/s + * @param thrust Collective thrust, normalized to 0 .. 1 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, roll_speed); + _mav_put_float(buf, 4, pitch_speed); + _mav_put_float(buf, 8, yaw_speed); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, buf, 18, 24); +#else + mavlink_set_roll_pitch_yaw_speed_thrust_t packet; + packet.roll_speed = roll_speed; + packet.pitch_speed = pitch_speed; + packet.yaw_speed = yaw_speed; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, (const char *)&packet, 18, 24); +#endif +} + +#endif + +// MESSAGE SET_ROLL_PITCH_YAW_SPEED_THRUST UNPACKING + + +/** + * @brief Get field target_system from set_roll_pitch_yaw_speed_thrust message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field target_component from set_roll_pitch_yaw_speed_thrust message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field roll_speed from set_roll_pitch_yaw_speed_thrust message + * + * @return Desired roll angular speed in rad/s + */ +static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_roll_speed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field pitch_speed from set_roll_pitch_yaw_speed_thrust message + * + * @return Desired pitch angular speed in rad/s + */ +static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_pitch_speed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field yaw_speed from set_roll_pitch_yaw_speed_thrust message + * + * @return Desired yaw angular speed in rad/s + */ +static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_yaw_speed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field thrust from set_roll_pitch_yaw_speed_thrust message + * + * @return Collective thrust, normalized to 0 .. 1 + */ +static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a set_roll_pitch_yaw_speed_thrust message into a struct + * + * @param msg The message to decode + * @param set_roll_pitch_yaw_speed_thrust C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_speed_thrust_t* set_roll_pitch_yaw_speed_thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_roll_pitch_yaw_speed_thrust->roll_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_roll_speed(msg); + set_roll_pitch_yaw_speed_thrust->pitch_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_pitch_speed(msg); + set_roll_pitch_yaw_speed_thrust->yaw_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_yaw_speed(msg); + set_roll_pitch_yaw_speed_thrust->thrust = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_thrust(msg); + set_roll_pitch_yaw_speed_thrust->target_system = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_system(msg); + set_roll_pitch_yaw_speed_thrust->target_component = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_component(msg); +#else + memcpy(set_roll_pitch_yaw_speed_thrust, _MAV_PAYLOAD(msg), 18); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h new file mode 100644 index 0000000000000000000000000000000000000000..8cd573a26c561e658bcdb255873dbac00a3983ab --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h @@ -0,0 +1,254 @@ +// MESSAGE SET_ROLL_PITCH_YAW_THRUST PACKING + +#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST 56 + +typedef struct __mavlink_set_roll_pitch_yaw_thrust_t +{ + float roll; ///< Desired roll angle in radians + float pitch; ///< Desired pitch angle in radians + float yaw; ///< Desired yaw angle in radians + float thrust; ///< Collective thrust, normalized to 0 .. 1 + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_set_roll_pitch_yaw_thrust_t; + +#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN 18 +#define MAVLINK_MSG_ID_56_LEN 18 + + + +#define MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST { \ + "SET_ROLL_PITCH_YAW_THRUST", \ + 6, \ + { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, yaw) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, thrust) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a set_roll_pitch_yaw_thrust 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 target_system System ID + * @param target_component Component ID + * @param roll Desired roll angle in radians + * @param pitch Desired pitch angle in radians + * @param yaw Desired yaw angle in radians + * @param thrust Collective thrust, normalized to 0 .. 1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); +#else + mavlink_set_roll_pitch_yaw_thrust_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST; + return mavlink_finalize_message(msg, system_id, component_id, 18, 100); +} + +/** + * @brief Pack a set_roll_pitch_yaw_thrust 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 target_system System ID + * @param target_component Component ID + * @param roll Desired roll angle in radians + * @param pitch Desired pitch angle in radians + * @param yaw Desired yaw angle in radians + * @param thrust Collective thrust, normalized to 0 .. 1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,float roll,float pitch,float yaw,float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); +#else + mavlink_set_roll_pitch_yaw_thrust_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 100); +} + +/** + * @brief Encode a set_roll_pitch_yaw_thrust 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 set_roll_pitch_yaw_thrust C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_thrust_t* set_roll_pitch_yaw_thrust) +{ + return mavlink_msg_set_roll_pitch_yaw_thrust_pack(system_id, component_id, msg, set_roll_pitch_yaw_thrust->target_system, set_roll_pitch_yaw_thrust->target_component, set_roll_pitch_yaw_thrust->roll, set_roll_pitch_yaw_thrust->pitch, set_roll_pitch_yaw_thrust->yaw, set_roll_pitch_yaw_thrust->thrust); +} + +/** + * @brief Send a set_roll_pitch_yaw_thrust message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param roll Desired roll angle in radians + * @param pitch Desired pitch angle in radians + * @param yaw Desired yaw angle in radians + * @param thrust Collective thrust, normalized to 0 .. 1 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_roll_pitch_yaw_thrust_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, buf, 18, 100); +#else + mavlink_set_roll_pitch_yaw_thrust_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, (const char *)&packet, 18, 100); +#endif +} + +#endif + +// MESSAGE SET_ROLL_PITCH_YAW_THRUST UNPACKING + + +/** + * @brief Get field target_system from set_roll_pitch_yaw_thrust message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_roll_pitch_yaw_thrust_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field target_component from set_roll_pitch_yaw_thrust message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_roll_pitch_yaw_thrust_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field roll from set_roll_pitch_yaw_thrust message + * + * @return Desired roll angle in radians + */ +static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field pitch from set_roll_pitch_yaw_thrust message + * + * @return Desired pitch angle in radians + */ +static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field yaw from set_roll_pitch_yaw_thrust message + * + * @return Desired yaw angle in radians + */ +static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field thrust from set_roll_pitch_yaw_thrust message + * + * @return Collective thrust, normalized to 0 .. 1 + */ +static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a set_roll_pitch_yaw_thrust message into a struct + * + * @param msg The message to decode + * @param set_roll_pitch_yaw_thrust C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_roll_pitch_yaw_thrust_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_thrust_t* set_roll_pitch_yaw_thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_roll_pitch_yaw_thrust->roll = mavlink_msg_set_roll_pitch_yaw_thrust_get_roll(msg); + set_roll_pitch_yaw_thrust->pitch = mavlink_msg_set_roll_pitch_yaw_thrust_get_pitch(msg); + set_roll_pitch_yaw_thrust->yaw = mavlink_msg_set_roll_pitch_yaw_thrust_get_yaw(msg); + set_roll_pitch_yaw_thrust->thrust = mavlink_msg_set_roll_pitch_yaw_thrust_get_thrust(msg); + set_roll_pitch_yaw_thrust->target_system = mavlink_msg_set_roll_pitch_yaw_thrust_get_target_system(msg); + set_roll_pitch_yaw_thrust->target_component = mavlink_msg_set_roll_pitch_yaw_thrust_get_target_component(msg); +#else + memcpy(set_roll_pitch_yaw_thrust, _MAV_PAYLOAD(msg), 18); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h new file mode 100644 index 0000000000000000000000000000000000000000..0f4f1f5e22bff94c46af0c96dd5210ceaf67b2ec --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h @@ -0,0 +1,320 @@ +// MESSAGE STATE_CORRECTION PACKING + +#define MAVLINK_MSG_ID_STATE_CORRECTION 64 + +typedef struct __mavlink_state_correction_t +{ + float xErr; ///< x position error + float yErr; ///< y position error + float zErr; ///< z position error + float rollErr; ///< roll error (radians) + float pitchErr; ///< pitch error (radians) + float yawErr; ///< yaw error (radians) + float vxErr; ///< x velocity + float vyErr; ///< y velocity + float vzErr; ///< z velocity +} mavlink_state_correction_t; + +#define MAVLINK_MSG_ID_STATE_CORRECTION_LEN 36 +#define MAVLINK_MSG_ID_64_LEN 36 + + + +#define MAVLINK_MESSAGE_INFO_STATE_CORRECTION { \ + "STATE_CORRECTION", \ + 9, \ + { { "xErr", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_state_correction_t, xErr) }, \ + { "yErr", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_state_correction_t, yErr) }, \ + { "zErr", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_state_correction_t, zErr) }, \ + { "rollErr", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_state_correction_t, rollErr) }, \ + { "pitchErr", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_state_correction_t, pitchErr) }, \ + { "yawErr", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_state_correction_t, yawErr) }, \ + { "vxErr", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_state_correction_t, vxErr) }, \ + { "vyErr", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_state_correction_t, vyErr) }, \ + { "vzErr", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_state_correction_t, vzErr) }, \ + } \ +} + + +/** + * @brief Pack a state_correction 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 xErr x position error + * @param yErr y position error + * @param zErr z position error + * @param rollErr roll error (radians) + * @param pitchErr pitch error (radians) + * @param yawErr yaw error (radians) + * @param vxErr x velocity + * @param vyErr y velocity + * @param vzErr z velocity + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_state_correction_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_float(buf, 0, xErr); + _mav_put_float(buf, 4, yErr); + _mav_put_float(buf, 8, zErr); + _mav_put_float(buf, 12, rollErr); + _mav_put_float(buf, 16, pitchErr); + _mav_put_float(buf, 20, yawErr); + _mav_put_float(buf, 24, vxErr); + _mav_put_float(buf, 28, vyErr); + _mav_put_float(buf, 32, vzErr); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); +#else + mavlink_state_correction_t packet; + packet.xErr = xErr; + packet.yErr = yErr; + packet.zErr = zErr; + packet.rollErr = rollErr; + packet.pitchErr = pitchErr; + packet.yawErr = yawErr; + packet.vxErr = vxErr; + packet.vyErr = vyErr; + packet.vzErr = vzErr; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); +#endif + + msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION; + return mavlink_finalize_message(msg, system_id, component_id, 36, 130); +} + +/** + * @brief Pack a state_correction 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 xErr x position error + * @param yErr y position error + * @param zErr z position error + * @param rollErr roll error (radians) + * @param pitchErr pitch error (radians) + * @param yawErr yaw error (radians) + * @param vxErr x velocity + * @param vyErr y velocity + * @param vzErr z velocity + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_state_correction_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float xErr,float yErr,float zErr,float rollErr,float pitchErr,float yawErr,float vxErr,float vyErr,float vzErr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_float(buf, 0, xErr); + _mav_put_float(buf, 4, yErr); + _mav_put_float(buf, 8, zErr); + _mav_put_float(buf, 12, rollErr); + _mav_put_float(buf, 16, pitchErr); + _mav_put_float(buf, 20, yawErr); + _mav_put_float(buf, 24, vxErr); + _mav_put_float(buf, 28, vyErr); + _mav_put_float(buf, 32, vzErr); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); +#else + mavlink_state_correction_t packet; + packet.xErr = xErr; + packet.yErr = yErr; + packet.zErr = zErr; + packet.rollErr = rollErr; + packet.pitchErr = pitchErr; + packet.yawErr = yawErr; + packet.vxErr = vxErr; + packet.vyErr = vyErr; + packet.vzErr = vzErr; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); +#endif + + msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36, 130); +} + +/** + * @brief Encode a state_correction 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 state_correction C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_state_correction_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_state_correction_t* state_correction) +{ + return mavlink_msg_state_correction_pack(system_id, component_id, msg, state_correction->xErr, state_correction->yErr, state_correction->zErr, state_correction->rollErr, state_correction->pitchErr, state_correction->yawErr, state_correction->vxErr, state_correction->vyErr, state_correction->vzErr); +} + +/** + * @brief Send a state_correction message + * @param chan MAVLink channel to send the message + * + * @param xErr x position error + * @param yErr y position error + * @param zErr z position error + * @param rollErr roll error (radians) + * @param pitchErr pitch error (radians) + * @param yawErr yaw error (radians) + * @param vxErr x velocity + * @param vyErr y velocity + * @param vzErr z velocity + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_state_correction_send(mavlink_channel_t chan, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_float(buf, 0, xErr); + _mav_put_float(buf, 4, yErr); + _mav_put_float(buf, 8, zErr); + _mav_put_float(buf, 12, rollErr); + _mav_put_float(buf, 16, pitchErr); + _mav_put_float(buf, 20, yawErr); + _mav_put_float(buf, 24, vxErr); + _mav_put_float(buf, 28, vyErr); + _mav_put_float(buf, 32, vzErr); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, buf, 36, 130); +#else + mavlink_state_correction_t packet; + packet.xErr = xErr; + packet.yErr = yErr; + packet.zErr = zErr; + packet.rollErr = rollErr; + packet.pitchErr = pitchErr; + packet.yawErr = yawErr; + packet.vxErr = vxErr; + packet.vyErr = vyErr; + packet.vzErr = vzErr; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, (const char *)&packet, 36, 130); +#endif +} + +#endif + +// MESSAGE STATE_CORRECTION UNPACKING + + +/** + * @brief Get field xErr from state_correction message + * + * @return x position error + */ +static inline float mavlink_msg_state_correction_get_xErr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field yErr from state_correction message + * + * @return y position error + */ +static inline float mavlink_msg_state_correction_get_yErr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field zErr from state_correction message + * + * @return z position error + */ +static inline float mavlink_msg_state_correction_get_zErr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field rollErr from state_correction message + * + * @return roll error (radians) + */ +static inline float mavlink_msg_state_correction_get_rollErr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field pitchErr from state_correction message + * + * @return pitch error (radians) + */ +static inline float mavlink_msg_state_correction_get_pitchErr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field yawErr from state_correction message + * + * @return yaw error (radians) + */ +static inline float mavlink_msg_state_correction_get_yawErr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vxErr from state_correction message + * + * @return x velocity + */ +static inline float mavlink_msg_state_correction_get_vxErr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field vyErr from state_correction message + * + * @return y velocity + */ +static inline float mavlink_msg_state_correction_get_vyErr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field vzErr from state_correction message + * + * @return z velocity + */ +static inline float mavlink_msg_state_correction_get_vzErr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Decode a state_correction message into a struct + * + * @param msg The message to decode + * @param state_correction C-struct to decode the message contents into + */ +static inline void mavlink_msg_state_correction_decode(const mavlink_message_t* msg, mavlink_state_correction_t* state_correction) +{ +#if MAVLINK_NEED_BYTE_SWAP + state_correction->xErr = mavlink_msg_state_correction_get_xErr(msg); + state_correction->yErr = mavlink_msg_state_correction_get_yErr(msg); + state_correction->zErr = mavlink_msg_state_correction_get_zErr(msg); + state_correction->rollErr = mavlink_msg_state_correction_get_rollErr(msg); + state_correction->pitchErr = mavlink_msg_state_correction_get_pitchErr(msg); + state_correction->yawErr = mavlink_msg_state_correction_get_yawErr(msg); + state_correction->vxErr = mavlink_msg_state_correction_get_vxErr(msg); + state_correction->vyErr = mavlink_msg_state_correction_get_vyErr(msg); + state_correction->vzErr = mavlink_msg_state_correction_get_vzErr(msg); +#else + memcpy(state_correction, _MAV_PAYLOAD(msg), 36); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h new file mode 100644 index 0000000000000000000000000000000000000000..7c65d448f436d7331bb52d0f84293d1695982c55 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h @@ -0,0 +1,160 @@ +// MESSAGE STATUSTEXT PACKING + +#define MAVLINK_MSG_ID_STATUSTEXT 253 + +typedef struct __mavlink_statustext_t +{ + uint8_t severity; ///< Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + char text[50]; ///< Status text message, without null termination character +} mavlink_statustext_t; + +#define MAVLINK_MSG_ID_STATUSTEXT_LEN 51 +#define MAVLINK_MSG_ID_253_LEN 51 + +#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 50 + +#define MAVLINK_MESSAGE_INFO_STATUSTEXT { \ + "STATUSTEXT", \ + 2, \ + { { "severity", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_statustext_t, severity) }, \ + { "text", NULL, MAVLINK_TYPE_CHAR, 50, 1, offsetof(mavlink_statustext_t, text) }, \ + } \ +} + + +/** + * @brief Pack a statustext 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 severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + * @param text Status text message, without null termination character + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t severity, const char *text) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[51]; + _mav_put_uint8_t(buf, 0, severity); + _mav_put_char_array(buf, 1, text, 50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 51); +#else + mavlink_statustext_t packet; + packet.severity = severity; + mav_array_memcpy(packet.text, text, sizeof(char)*50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 51); +#endif + + msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; + return mavlink_finalize_message(msg, system_id, component_id, 51, 83); +} + +/** + * @brief Pack a statustext 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 severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + * @param text Status text message, without null termination character + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t severity,const char *text) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[51]; + _mav_put_uint8_t(buf, 0, severity); + _mav_put_char_array(buf, 1, text, 50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 51); +#else + mavlink_statustext_t packet; + packet.severity = severity; + mav_array_memcpy(packet.text, text, sizeof(char)*50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 51); +#endif + + msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 51, 83); +} + +/** + * @brief Encode a statustext 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 statustext C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_statustext_t* statustext) +{ + return mavlink_msg_statustext_pack(system_id, component_id, msg, statustext->severity, statustext->text); +} + +/** + * @brief Send a statustext message + * @param chan MAVLink channel to send the message + * + * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + * @param text Status text message, without null termination character + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const char *text) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[51]; + _mav_put_uint8_t(buf, 0, severity); + _mav_put_char_array(buf, 1, text, 50); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, 51, 83); +#else + mavlink_statustext_t packet; + packet.severity = severity; + mav_array_memcpy(packet.text, text, sizeof(char)*50); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, 51, 83); +#endif +} + +#endif + +// MESSAGE STATUSTEXT UNPACKING + + +/** + * @brief Get field severity from statustext message + * + * @return Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + */ +static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field text from statustext message + * + * @return Status text message, without null termination character + */ +static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, char *text) +{ + return _MAV_RETURN_char_array(msg, text, 50, 1); +} + +/** + * @brief Decode a statustext message into a struct + * + * @param msg The message to decode + * @param statustext C-struct to decode the message contents into + */ +static inline void mavlink_msg_statustext_decode(const mavlink_message_t* msg, mavlink_statustext_t* statustext) +{ +#if MAVLINK_NEED_BYTE_SWAP + statustext->severity = mavlink_msg_statustext_get_severity(msg); + mavlink_msg_statustext_get_text(msg, statustext->text); +#else + memcpy(statustext, _MAV_PAYLOAD(msg), 51); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h new file mode 100644 index 0000000000000000000000000000000000000000..ef09a652f8bce55bf3866775a6d0d9483a9036da --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h @@ -0,0 +1,408 @@ +// MESSAGE SYS_STATUS PACKING + +#define MAVLINK_MSG_ID_SYS_STATUS 1 + +typedef struct __mavlink_sys_status_t +{ + uint32_t onboard_control_sensors_present; ///< Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + uint32_t onboard_control_sensors_enabled; ///< Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + uint32_t onboard_control_sensors_health; ///< Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + uint16_t load; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + uint16_t voltage_battery; ///< Battery voltage, in millivolts (1 = 1 millivolt) + int16_t current_battery; ///< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + uint16_t drop_rate_comm; ///< Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + uint16_t errors_comm; ///< Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + uint16_t errors_count1; ///< Autopilot-specific errors + uint16_t errors_count2; ///< Autopilot-specific errors + uint16_t errors_count3; ///< Autopilot-specific errors + uint16_t errors_count4; ///< Autopilot-specific errors + int8_t battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery +} mavlink_sys_status_t; + +#define MAVLINK_MSG_ID_SYS_STATUS_LEN 31 +#define MAVLINK_MSG_ID_1_LEN 31 + + + +#define MAVLINK_MESSAGE_INFO_SYS_STATUS { \ + "SYS_STATUS", \ + 13, \ + { { "onboard_control_sensors_present", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \ + { "onboard_control_sensors_enabled", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \ + { "onboard_control_sensors_health", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \ + { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \ + { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \ + { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \ + { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \ + { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \ + { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \ + { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \ + { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \ + { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \ + { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \ + } \ +} + + +/** + * @brief Pack a sys_status 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 onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) + * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_count1 Autopilot-specific errors + * @param errors_count2 Autopilot-specific errors + * @param errors_count3 Autopilot-specific errors + * @param errors_count4 Autopilot-specific errors + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[31]; + _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); + _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); + _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); + _mav_put_uint16_t(buf, 12, load); + _mav_put_uint16_t(buf, 14, voltage_battery); + _mav_put_int16_t(buf, 16, current_battery); + _mav_put_uint16_t(buf, 18, drop_rate_comm); + _mav_put_uint16_t(buf, 20, errors_comm); + _mav_put_uint16_t(buf, 22, errors_count1); + _mav_put_uint16_t(buf, 24, errors_count2); + _mav_put_uint16_t(buf, 26, errors_count3); + _mav_put_uint16_t(buf, 28, errors_count4); + _mav_put_int8_t(buf, 30, battery_remaining); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 31); +#else + mavlink_sys_status_t packet; + packet.onboard_control_sensors_present = onboard_control_sensors_present; + packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; + packet.onboard_control_sensors_health = onboard_control_sensors_health; + packet.load = load; + packet.voltage_battery = voltage_battery; + packet.current_battery = current_battery; + packet.drop_rate_comm = drop_rate_comm; + packet.errors_comm = errors_comm; + packet.errors_count1 = errors_count1; + packet.errors_count2 = errors_count2; + packet.errors_count3 = errors_count3; + packet.errors_count4 = errors_count4; + packet.battery_remaining = battery_remaining; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 31); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; + return mavlink_finalize_message(msg, system_id, component_id, 31, 124); +} + +/** + * @brief Pack a sys_status 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 onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) + * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_count1 Autopilot-specific errors + * @param errors_count2 Autopilot-specific errors + * @param errors_count3 Autopilot-specific errors + * @param errors_count4 Autopilot-specific errors + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t onboard_control_sensors_present,uint32_t onboard_control_sensors_enabled,uint32_t onboard_control_sensors_health,uint16_t load,uint16_t voltage_battery,int16_t current_battery,int8_t battery_remaining,uint16_t drop_rate_comm,uint16_t errors_comm,uint16_t errors_count1,uint16_t errors_count2,uint16_t errors_count3,uint16_t errors_count4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[31]; + _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); + _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); + _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); + _mav_put_uint16_t(buf, 12, load); + _mav_put_uint16_t(buf, 14, voltage_battery); + _mav_put_int16_t(buf, 16, current_battery); + _mav_put_uint16_t(buf, 18, drop_rate_comm); + _mav_put_uint16_t(buf, 20, errors_comm); + _mav_put_uint16_t(buf, 22, errors_count1); + _mav_put_uint16_t(buf, 24, errors_count2); + _mav_put_uint16_t(buf, 26, errors_count3); + _mav_put_uint16_t(buf, 28, errors_count4); + _mav_put_int8_t(buf, 30, battery_remaining); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 31); +#else + mavlink_sys_status_t packet; + packet.onboard_control_sensors_present = onboard_control_sensors_present; + packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; + packet.onboard_control_sensors_health = onboard_control_sensors_health; + packet.load = load; + packet.voltage_battery = voltage_battery; + packet.current_battery = current_battery; + packet.drop_rate_comm = drop_rate_comm; + packet.errors_comm = errors_comm; + packet.errors_count1 = errors_count1; + packet.errors_count2 = errors_count2; + packet.errors_count3 = errors_count3; + packet.errors_count4 = errors_count4; + packet.battery_remaining = battery_remaining; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 31); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 31, 124); +} + +/** + * @brief Encode a sys_status 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 sys_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status) +{ + return mavlink_msg_sys_status_pack(system_id, component_id, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4); +} + +/** + * @brief Send a sys_status message + * @param chan MAVLink channel to send the message + * + * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) + * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_count1 Autopilot-specific errors + * @param errors_count2 Autopilot-specific errors + * @param errors_count3 Autopilot-specific errors + * @param errors_count4 Autopilot-specific errors + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[31]; + _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); + _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); + _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); + _mav_put_uint16_t(buf, 12, load); + _mav_put_uint16_t(buf, 14, voltage_battery); + _mav_put_int16_t(buf, 16, current_battery); + _mav_put_uint16_t(buf, 18, drop_rate_comm); + _mav_put_uint16_t(buf, 20, errors_comm); + _mav_put_uint16_t(buf, 22, errors_count1); + _mav_put_uint16_t(buf, 24, errors_count2); + _mav_put_uint16_t(buf, 26, errors_count3); + _mav_put_uint16_t(buf, 28, errors_count4); + _mav_put_int8_t(buf, 30, battery_remaining); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, 31, 124); +#else + mavlink_sys_status_t packet; + packet.onboard_control_sensors_present = onboard_control_sensors_present; + packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; + packet.onboard_control_sensors_health = onboard_control_sensors_health; + packet.load = load; + packet.voltage_battery = voltage_battery; + packet.current_battery = current_battery; + packet.drop_rate_comm = drop_rate_comm; + packet.errors_comm = errors_comm; + packet.errors_count1 = errors_count1; + packet.errors_count2 = errors_count2; + packet.errors_count3 = errors_count3; + packet.errors_count4 = errors_count4; + packet.battery_remaining = battery_remaining; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, 31, 124); +#endif +} + +#endif + +// MESSAGE SYS_STATUS UNPACKING + + +/** + * @brief Get field onboard_control_sensors_present from sys_status message + * + * @return Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + */ +static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_present(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field onboard_control_sensors_enabled from sys_status message + * + * @return Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + */ +static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enabled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 4); +} + +/** + * @brief Get field onboard_control_sensors_health from sys_status message + * + * @return Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + */ +static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field load from sys_status message + * + * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + */ +static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field voltage_battery from sys_status message + * + * @return Battery voltage, in millivolts (1 = 1 millivolt) + */ +static inline uint16_t mavlink_msg_sys_status_get_voltage_battery(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Get field current_battery from sys_status message + * + * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + */ +static inline int16_t mavlink_msg_sys_status_get_current_battery(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field battery_remaining from sys_status message + * + * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + */ +static inline int8_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 30); +} + +/** + * @brief Get field drop_rate_comm from sys_status message + * + * @return Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + */ +static inline uint16_t mavlink_msg_sys_status_get_drop_rate_comm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field errors_comm from sys_status message + * + * @return Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_comm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Get field errors_count1 from sys_status message + * + * @return Autopilot-specific errors + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_count1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field errors_count2 from sys_status message + * + * @return Autopilot-specific errors + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_count2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field errors_count3 from sys_status message + * + * @return Autopilot-specific errors + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_count3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Get field errors_count4 from sys_status message + * + * @return Autopilot-specific errors + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_count4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Decode a sys_status message into a struct + * + * @param msg The message to decode + * @param sys_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + sys_status->onboard_control_sensors_present = mavlink_msg_sys_status_get_onboard_control_sensors_present(msg); + sys_status->onboard_control_sensors_enabled = mavlink_msg_sys_status_get_onboard_control_sensors_enabled(msg); + sys_status->onboard_control_sensors_health = mavlink_msg_sys_status_get_onboard_control_sensors_health(msg); + sys_status->load = mavlink_msg_sys_status_get_load(msg); + sys_status->voltage_battery = mavlink_msg_sys_status_get_voltage_battery(msg); + sys_status->current_battery = mavlink_msg_sys_status_get_current_battery(msg); + sys_status->drop_rate_comm = mavlink_msg_sys_status_get_drop_rate_comm(msg); + sys_status->errors_comm = mavlink_msg_sys_status_get_errors_comm(msg); + sys_status->errors_count1 = mavlink_msg_sys_status_get_errors_count1(msg); + sys_status->errors_count2 = mavlink_msg_sys_status_get_errors_count2(msg); + sys_status->errors_count3 = mavlink_msg_sys_status_get_errors_count3(msg); + sys_status->errors_count4 = mavlink_msg_sys_status_get_errors_count4(msg); + sys_status->battery_remaining = mavlink_msg_sys_status_get_battery_remaining(msg); +#else + memcpy(sys_status, _MAV_PAYLOAD(msg), 31); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h new file mode 100644 index 0000000000000000000000000000000000000000..c24808d1a2c180e1eb12190e959bfbc344d187b9 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h @@ -0,0 +1,166 @@ +// MESSAGE SYSTEM_TIME PACKING + +#define MAVLINK_MSG_ID_SYSTEM_TIME 2 + +typedef struct __mavlink_system_time_t +{ + uint64_t time_unix_usec; ///< Timestamp of the master clock in microseconds since UNIX epoch. + uint32_t time_boot_ms; ///< Timestamp of the component clock since boot time in milliseconds. +} mavlink_system_time_t; + +#define MAVLINK_MSG_ID_SYSTEM_TIME_LEN 12 +#define MAVLINK_MSG_ID_2_LEN 12 + + + +#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \ + "SYSTEM_TIME", \ + 2, \ + { { "time_unix_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_unix_usec) }, \ + { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_system_time_t, time_boot_ms) }, \ + } \ +} + + +/** + * @brief Pack a system_time message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. + * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_unix_usec, uint32_t time_boot_ms) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_uint64_t(buf, 0, time_unix_usec); + _mav_put_uint32_t(buf, 8, time_boot_ms); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_system_time_t packet; + packet.time_unix_usec = time_unix_usec; + packet.time_boot_ms = time_boot_ms; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; + return mavlink_finalize_message(msg, system_id, component_id, 12, 137); +} + +/** + * @brief Pack a system_time message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. + * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_unix_usec,uint32_t time_boot_ms) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_uint64_t(buf, 0, time_unix_usec); + _mav_put_uint32_t(buf, 8, time_boot_ms); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_system_time_t packet; + packet.time_unix_usec = time_unix_usec; + packet.time_boot_ms = time_boot_ms; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 137); +} + +/** + * @brief Encode a system_time 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 system_time C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_t* system_time) +{ + return mavlink_msg_system_time_pack(system_id, component_id, msg, system_time->time_unix_usec, system_time->time_boot_ms); +} + +/** + * @brief Send a system_time message + * @param chan MAVLink channel to send the message + * + * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. + * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_system_time_send(mavlink_channel_t chan, uint64_t time_unix_usec, uint32_t time_boot_ms) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_uint64_t(buf, 0, time_unix_usec); + _mav_put_uint32_t(buf, 8, time_boot_ms); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, 12, 137); +#else + mavlink_system_time_t packet; + packet.time_unix_usec = time_unix_usec; + packet.time_boot_ms = time_boot_ms; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)&packet, 12, 137); +#endif +} + +#endif + +// MESSAGE SYSTEM_TIME UNPACKING + + +/** + * @brief Get field time_unix_usec from system_time message + * + * @return Timestamp of the master clock in microseconds since UNIX epoch. + */ +static inline uint64_t mavlink_msg_system_time_get_time_unix_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field time_boot_ms from system_time message + * + * @return Timestamp of the component clock since boot time in milliseconds. + */ +static inline uint32_t mavlink_msg_system_time_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Decode a system_time message into a struct + * + * @param msg The message to decode + * @param system_time C-struct to decode the message contents into + */ +static inline void mavlink_msg_system_time_decode(const mavlink_message_t* msg, mavlink_system_time_t* system_time) +{ +#if MAVLINK_NEED_BYTE_SWAP + system_time->time_unix_usec = mavlink_msg_system_time_get_time_unix_usec(msg); + system_time->time_boot_ms = mavlink_msg_system_time_get_time_boot_ms(msg); +#else + memcpy(system_time, _MAV_PAYLOAD(msg), 12); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h new file mode 100644 index 0000000000000000000000000000000000000000..d7c1afe410727f890e7d392c565084013a9d536c --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h @@ -0,0 +1,254 @@ +// MESSAGE VFR_HUD PACKING + +#define MAVLINK_MSG_ID_VFR_HUD 74 + +typedef struct __mavlink_vfr_hud_t +{ + float airspeed; ///< Current airspeed in m/s + float groundspeed; ///< Current ground speed in m/s + float alt; ///< Current altitude (MSL), in meters + float climb; ///< Current climb rate in meters/second + int16_t heading; ///< Current heading in degrees, in compass units (0..360, 0=north) + uint16_t throttle; ///< Current throttle setting in integer percent, 0 to 100 +} mavlink_vfr_hud_t; + +#define MAVLINK_MSG_ID_VFR_HUD_LEN 20 +#define MAVLINK_MSG_ID_74_LEN 20 + + + +#define MAVLINK_MESSAGE_INFO_VFR_HUD { \ + "VFR_HUD", \ + 6, \ + { { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \ + { "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \ + { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \ + { "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vfr_hud_t, heading) }, \ + { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vfr_hud_t, throttle) }, \ + } \ +} + + +/** + * @brief Pack a vfr_hud 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 airspeed Current airspeed in m/s + * @param groundspeed Current ground speed in m/s + * @param heading Current heading in degrees, in compass units (0..360, 0=north) + * @param throttle Current throttle setting in integer percent, 0 to 100 + * @param alt Current altitude (MSL), in meters + * @param climb Current climb rate in meters/second + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_float(buf, 0, airspeed); + _mav_put_float(buf, 4, groundspeed); + _mav_put_float(buf, 8, alt); + _mav_put_float(buf, 12, climb); + _mav_put_int16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, throttle); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); +#else + mavlink_vfr_hud_t packet; + packet.airspeed = airspeed; + packet.groundspeed = groundspeed; + packet.alt = alt; + packet.climb = climb; + packet.heading = heading; + packet.throttle = throttle; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_VFR_HUD; + return mavlink_finalize_message(msg, system_id, component_id, 20, 20); +} + +/** + * @brief Pack a vfr_hud 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 airspeed Current airspeed in m/s + * @param groundspeed Current ground speed in m/s + * @param heading Current heading in degrees, in compass units (0..360, 0=north) + * @param throttle Current throttle setting in integer percent, 0 to 100 + * @param alt Current altitude (MSL), in meters + * @param climb Current climb rate in meters/second + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float airspeed,float groundspeed,int16_t heading,uint16_t throttle,float alt,float climb) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_float(buf, 0, airspeed); + _mav_put_float(buf, 4, groundspeed); + _mav_put_float(buf, 8, alt); + _mav_put_float(buf, 12, climb); + _mav_put_int16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, throttle); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); +#else + mavlink_vfr_hud_t packet; + packet.airspeed = airspeed; + packet.groundspeed = groundspeed; + packet.alt = alt; + packet.climb = climb; + packet.heading = heading; + packet.throttle = throttle; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_VFR_HUD; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 20); +} + +/** + * @brief Encode a vfr_hud 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 vfr_hud C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vfr_hud_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud) +{ + return mavlink_msg_vfr_hud_pack(system_id, component_id, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb); +} + +/** + * @brief Send a vfr_hud message + * @param chan MAVLink channel to send the message + * + * @param airspeed Current airspeed in m/s + * @param groundspeed Current ground speed in m/s + * @param heading Current heading in degrees, in compass units (0..360, 0=north) + * @param throttle Current throttle setting in integer percent, 0 to 100 + * @param alt Current altitude (MSL), in meters + * @param climb Current climb rate in meters/second + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vfr_hud_send(mavlink_channel_t chan, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_float(buf, 0, airspeed); + _mav_put_float(buf, 4, groundspeed); + _mav_put_float(buf, 8, alt); + _mav_put_float(buf, 12, climb); + _mav_put_int16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, throttle); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, 20, 20); +#else + mavlink_vfr_hud_t packet; + packet.airspeed = airspeed; + packet.groundspeed = groundspeed; + packet.alt = alt; + packet.climb = climb; + packet.heading = heading; + packet.throttle = throttle; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)&packet, 20, 20); +#endif +} + +#endif + +// MESSAGE VFR_HUD UNPACKING + + +/** + * @brief Get field airspeed from vfr_hud message + * + * @return Current airspeed in m/s + */ +static inline float mavlink_msg_vfr_hud_get_airspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field groundspeed from vfr_hud message + * + * @return Current ground speed in m/s + */ +static inline float mavlink_msg_vfr_hud_get_groundspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field heading from vfr_hud message + * + * @return Current heading in degrees, in compass units (0..360, 0=north) + */ +static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field throttle from vfr_hud message + * + * @return Current throttle setting in integer percent, 0 to 100 + */ +static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field alt from vfr_hud message + * + * @return Current altitude (MSL), in meters + */ +static inline float mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field climb from vfr_hud message + * + * @return Current climb rate in meters/second + */ +static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a vfr_hud message into a struct + * + * @param msg The message to decode + * @param vfr_hud C-struct to decode the message contents into + */ +static inline void mavlink_msg_vfr_hud_decode(const mavlink_message_t* msg, mavlink_vfr_hud_t* vfr_hud) +{ +#if MAVLINK_NEED_BYTE_SWAP + vfr_hud->airspeed = mavlink_msg_vfr_hud_get_airspeed(msg); + vfr_hud->groundspeed = mavlink_msg_vfr_hud_get_groundspeed(msg); + vfr_hud->alt = mavlink_msg_vfr_hud_get_alt(msg); + vfr_hud->climb = mavlink_msg_vfr_hud_get_climb(msg); + vfr_hud->heading = mavlink_msg_vfr_hud_get_heading(msg); + vfr_hud->throttle = mavlink_msg_vfr_hud_get_throttle(msg); +#else + memcpy(vfr_hud, _MAV_PAYLOAD(msg), 20); +#endif +} diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_vicon_position_estimate.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h similarity index 95% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_vicon_position_estimate.h rename to mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h index 0df8174924fb58436dfacffa12150077f317155e..ecb565684d6f8adce15a92cdc4969d2892b37dbc 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_vicon_position_estimate.h +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h @@ -1,6 +1,6 @@ // MESSAGE VICON_POSITION_ESTIMATE PACKING -#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 157 +#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 104 typedef struct __mavlink_vicon_position_estimate_t { @@ -14,7 +14,7 @@ typedef struct __mavlink_vicon_position_estimate_t } mavlink_vicon_position_estimate_t; #define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN 32 -#define MAVLINK_MSG_ID_157_LEN 32 +#define MAVLINK_MSG_ID_104_LEN 32 @@ -60,7 +60,7 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_i _mav_put_float(buf, 24, pitch); _mav_put_float(buf, 28, yaw); - memcpy(_MAV_PAYLOAD(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); #else mavlink_vicon_position_estimate_t packet; packet.usec = usec; @@ -71,11 +71,11 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_i packet.pitch = pitch; packet.yaw = yaw; - memcpy(_MAV_PAYLOAD(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); #endif msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; - return mavlink_finalize_message(msg, system_id, component_id, 32); + return mavlink_finalize_message(msg, system_id, component_id, 32, 56); } /** @@ -107,7 +107,7 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t sys _mav_put_float(buf, 24, pitch); _mav_put_float(buf, 28, yaw); - memcpy(_MAV_PAYLOAD(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); #else mavlink_vicon_position_estimate_t packet; packet.usec = usec; @@ -118,11 +118,11 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t sys packet.pitch = pitch; packet.yaw = yaw; - memcpy(_MAV_PAYLOAD(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); #endif msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 56); } /** @@ -164,7 +164,7 @@ static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t ch _mav_put_float(buf, 24, pitch); _mav_put_float(buf, 28, yaw); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, 32); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, 32, 56); #else mavlink_vicon_position_estimate_t packet; packet.usec = usec; @@ -175,7 +175,7 @@ static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t ch packet.pitch = pitch; packet.yaw = yaw; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)&packet, 32); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)&packet, 32, 56); #endif } diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_vision_position_estimate.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h similarity index 95% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_vision_position_estimate.h rename to mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h index ac186fbc0dcda2a3410f98ddc2e658d2497b773a..041caf7a073cbe71cf888ee89ce02da51c3dd6c1 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_vision_position_estimate.h +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h @@ -1,6 +1,6 @@ // MESSAGE VISION_POSITION_ESTIMATE PACKING -#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 156 +#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 102 typedef struct __mavlink_vision_position_estimate_t { @@ -14,7 +14,7 @@ typedef struct __mavlink_vision_position_estimate_t } mavlink_vision_position_estimate_t; #define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN 32 -#define MAVLINK_MSG_ID_156_LEN 32 +#define MAVLINK_MSG_ID_102_LEN 32 @@ -60,7 +60,7 @@ static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_ _mav_put_float(buf, 24, pitch); _mav_put_float(buf, 28, yaw); - memcpy(_MAV_PAYLOAD(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); #else mavlink_vision_position_estimate_t packet; packet.usec = usec; @@ -71,11 +71,11 @@ static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_ packet.pitch = pitch; packet.yaw = yaw; - memcpy(_MAV_PAYLOAD(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); #endif msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; - return mavlink_finalize_message(msg, system_id, component_id, 32); + return mavlink_finalize_message(msg, system_id, component_id, 32, 158); } /** @@ -107,7 +107,7 @@ static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t sy _mav_put_float(buf, 24, pitch); _mav_put_float(buf, 28, yaw); - memcpy(_MAV_PAYLOAD(msg), buf, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); #else mavlink_vision_position_estimate_t packet; packet.usec = usec; @@ -118,11 +118,11 @@ static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t sy packet.pitch = pitch; packet.yaw = yaw; - memcpy(_MAV_PAYLOAD(msg), &packet, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); #endif msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 158); } /** @@ -164,7 +164,7 @@ static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t c _mav_put_float(buf, 24, pitch); _mav_put_float(buf, 28, yaw); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, 32); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, 32, 158); #else mavlink_vision_position_estimate_t packet; packet.usec = usec; @@ -175,7 +175,7 @@ static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t c packet.pitch = pitch; packet.yaw = yaw; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, 32); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, 32, 158); #endif } diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_vision_speed_estimate.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h similarity index 93% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_vision_speed_estimate.h rename to mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h index 17c7809ea6356bed589db4e11940f57df44c994c..3e30b9247ac9479e19b10b047b40e0c92883efe4 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_vision_speed_estimate.h +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h @@ -1,6 +1,6 @@ // MESSAGE VISION_SPEED_ESTIMATE PACKING -#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 158 +#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103 typedef struct __mavlink_vision_speed_estimate_t { @@ -11,7 +11,7 @@ typedef struct __mavlink_vision_speed_estimate_t } mavlink_vision_speed_estimate_t; #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20 -#define MAVLINK_MSG_ID_158_LEN 20 +#define MAVLINK_MSG_ID_103_LEN 20 @@ -48,7 +48,7 @@ static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, _mav_put_float(buf, 12, y); _mav_put_float(buf, 16, z); - memcpy(_MAV_PAYLOAD(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); #else mavlink_vision_speed_estimate_t packet; packet.usec = usec; @@ -56,11 +56,11 @@ static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, packet.y = y; packet.z = z; - memcpy(_MAV_PAYLOAD(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); #endif msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; - return mavlink_finalize_message(msg, system_id, component_id, 20); + return mavlink_finalize_message(msg, system_id, component_id, 20, 208); } /** @@ -86,7 +86,7 @@ static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t syste _mav_put_float(buf, 12, y); _mav_put_float(buf, 16, z); - memcpy(_MAV_PAYLOAD(msg), buf, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); #else mavlink_vision_speed_estimate_t packet; packet.usec = usec; @@ -94,11 +94,11 @@ static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t syste packet.y = y; packet.z = z; - memcpy(_MAV_PAYLOAD(msg), &packet, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); #endif msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 208); } /** @@ -134,7 +134,7 @@ static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan _mav_put_float(buf, 12, y); _mav_put_float(buf, 16, z); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, 20); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, 20, 208); #else mavlink_vision_speed_estimate_t packet; packet.usec = usec; @@ -142,7 +142,7 @@ static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan packet.y = y; packet.z = z; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, 20); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, 20, 208); #endif } diff --git a/mavlink/include/mavlink/v1.0/common/testsuite.h b/mavlink/include/mavlink/v1.0/common/testsuite.h new file mode 100644 index 0000000000000000000000000000000000000000..5459a61a5adab2e4d00e37715f3ccfc2ace4989e --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/testsuite.h @@ -0,0 +1,4024 @@ +/** @file + * @brief MAVLink comm protocol testsuite generated from common.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef COMMON_TESTSUITE_H +#define COMMON_TESTSUITE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef MAVLINK_TEST_ALL +#define MAVLINK_TEST_ALL + +static void mavlink_test_common(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_common(system_id, component_id, last_msg); +} +#endif + + + + +static void mavlink_test_heartbeat(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_heartbeat_t packet_in = { + 963497464, + 17, + 84, + 151, + 218, + 3, + }; + mavlink_heartbeat_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.custom_mode = packet_in.custom_mode; + packet1.type = packet_in.type; + packet1.autopilot = packet_in.autopilot; + packet1.base_mode = packet_in.base_mode; + packet1.system_status = packet_in.system_status; + packet1.mavlink_version = packet_in.mavlink_version; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_heartbeat_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_heartbeat_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_heartbeat_pack(system_id, component_id, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); + mavlink_msg_heartbeat_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); + mavlink_msg_heartbeat_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 msg(new px::GLOverlay); + registerType(msg); + } + + // register ObstacleList + { + std::tr1::shared_ptr msg(new px::ObstacleList); + registerType(msg); + } + + // register ObstacleMap + { + std::tr1::shared_ptr msg(new px::ObstacleMap); + registerType(msg); + } + + // register Path + { + std::tr1::shared_ptr msg(new px::Path); + registerType(msg); + } + // register PointCloudXYZI { std::tr1::shared_ptr msg(new px::PointCloudXYZI); @@ -144,7 +168,7 @@ public: if (typecode >= mTypeMap.size()) { std::cout << "# WARNING: Protobuf message with type code " - << typecode << " is not registered." << std::endl; + << static_cast(typecode) << " is not registered." << std::endl; return false; } @@ -186,6 +210,11 @@ public: if (offset == 0) { queue.push_back(msg); + + if ((flags & 0x1) != 0x1) + { + reassemble = true; + } } else { diff --git a/files/mavlink_generator/generator/C/include_v1.0/mavlink_types.h b/mavlink/include/mavlink/v1.0/mavlink_types.h similarity index 100% rename from files/mavlink_generator/generator/C/include_v1.0/mavlink_types.h rename to mavlink/include/mavlink/v1.0/mavlink_types.h diff --git a/mavlink/include/v1.0/minimal/mavlink.h b/mavlink/include/mavlink/v1.0/minimal/mavlink.h similarity index 100% rename from mavlink/include/v1.0/minimal/mavlink.h rename to mavlink/include/mavlink/v1.0/minimal/mavlink.h diff --git a/mavlink/include/v1.0/minimal/mavlink_msg_heartbeat.h b/mavlink/include/mavlink/v1.0/minimal/mavlink_msg_heartbeat.h similarity index 86% rename from mavlink/include/v1.0/minimal/mavlink_msg_heartbeat.h rename to mavlink/include/mavlink/v1.0/minimal/mavlink_msg_heartbeat.h index 39668d82311a4fcf8075868fabe79cba40baa0cc..35033870706cd2de54218832037861ab9949d4d2 100644 --- a/mavlink/include/v1.0/minimal/mavlink_msg_heartbeat.h +++ b/mavlink/include/mavlink/v1.0/minimal/mavlink_msg_heartbeat.h @@ -4,11 +4,11 @@ typedef struct __mavlink_heartbeat_t { - uint32_t custom_mode; ///< Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. + uint32_t custom_mode; ///< A bitfield for use for autopilot-specific flags. uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - uint8_t autopilot; ///< Autopilot type / class. defined in MAV_CLASS ENUM + uint8_t autopilot; ///< Autopilot type / class. defined in MAV_AUTOPILOT ENUM uint8_t base_mode; ///< System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h - uint8_t system_status; ///< System status flag, see MAV_STATUS ENUM + uint8_t system_status; ///< System status flag, see MAV_STATE ENUM uint8_t mavlink_version; ///< MAVLink version } mavlink_heartbeat_t; @@ -37,10 +37,10 @@ typedef struct __mavlink_heartbeat_t * @param msg The MAVLink message to compress the data into * * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM + * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h - * @param custom_mode Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. - * @param system_status System status flag, see MAV_STATUS ENUM + * @param custom_mode A bitfield for use for autopilot-specific flags. + * @param system_status System status flag, see MAV_STATE ENUM * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -79,10 +79,10 @@ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t com * @param chan The MAVLink channel this message was sent over * @param msg The MAVLink message to compress the data into * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM + * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h - * @param custom_mode Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. - * @param system_status System status flag, see MAV_STATUS ENUM + * @param custom_mode A bitfield for use for autopilot-specific flags. + * @param system_status System status flag, see MAV_STATE ENUM * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -133,10 +133,10 @@ static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t c * @param chan MAVLink channel to send the message * * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM + * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h - * @param custom_mode Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. - * @param system_status System status flag, see MAV_STATUS ENUM + * @param custom_mode A bitfield for use for autopilot-specific flags. + * @param system_status System status flag, see MAV_STATE ENUM */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -183,7 +183,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* ms /** * @brief Get field autopilot from heartbeat message * - * @return Autopilot type / class. defined in MAV_CLASS ENUM + * @return Autopilot type / class. defined in MAV_AUTOPILOT ENUM */ static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg) { @@ -203,7 +203,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_ /** * @brief Get field custom_mode from heartbeat message * - * @return Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. + * @return A bitfield for use for autopilot-specific flags. */ static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg) { @@ -213,7 +213,7 @@ static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_messa /** * @brief Get field system_status from heartbeat message * - * @return System status flag, see MAV_STATUS ENUM + * @return System status flag, see MAV_STATE ENUM */ static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg) { diff --git a/mavlink/include/mavlink/v1.0/minimal/minimal.h b/mavlink/include/mavlink/v1.0/minimal/minimal.h new file mode 100644 index 0000000000000000000000000000000000000000..30c6c1cdc64d45f9c0d99dc4638ee73ae626dfeb --- /dev/null +++ b/mavlink/include/mavlink/v1.0/minimal/minimal.h @@ -0,0 +1,150 @@ +/** @file + * @brief MAVLink comm protocol generated from minimal.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef MINIMAL_H +#define MINIMAL_H + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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 {50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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_HEARTBEAT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_MINIMAL + + + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +// ENUM DEFINITIONS + + +/** @brief Micro air vehicle / autopilot classes. This identifies the individual model. */ +#ifndef HAVE_ENUM_MAV_AUTOPILOT +#define HAVE_ENUM_MAV_AUTOPILOT +enum MAV_AUTOPILOT +{ + MAV_AUTOPILOT_GENERIC=0, /* Generic autopilot, full support for everything | */ + MAV_AUTOPILOT_PIXHAWK=1, /* PIXHAWK autopilot, http://pixhawk.ethz.ch | */ + MAV_AUTOPILOT_SLUGS=2, /* SLUGS autopilot, http://slugsuav.soe.ucsc.edu | */ + MAV_AUTOPILOT_ARDUPILOTMEGA=3, /* ArduPilotMega / ArduCopter, http://diydrones.com | */ + MAV_AUTOPILOT_OPENPILOT=4, /* OpenPilot, http://openpilot.org | */ + MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY=5, /* Generic autopilot only supporting simple waypoints | */ + MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY=6, /* Generic autopilot supporting waypoints and other simple navigation commands | */ + MAV_AUTOPILOT_GENERIC_MISSION_FULL=7, /* Generic autopilot supporting the full mission command set | */ + MAV_AUTOPILOT_INVALID=8, /* No valid autopilot, e.g. a GCS or other MAVLink component | */ + MAV_AUTOPILOT_PPZ=9, /* PPZ UAV - http://nongnu.org/paparazzi | */ + MAV_AUTOPILOT_UDB=10, /* UAV Dev Board | */ + MAV_AUTOPILOT_FP=11, /* FlexiPilot | */ + MAV_AUTOPILOT_ENUM_END=12, /* | */ +}; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_TYPE +#define HAVE_ENUM_MAV_TYPE +enum MAV_TYPE +{ + MAV_TYPE_GENERIC=0, /* Generic micro air vehicle. | */ + MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */ + MAV_TYPE_QUADROTOR=2, /* Quadrotor | */ + MAV_TYPE_COAXIAL=3, /* Coaxial helicopter | */ + MAV_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */ + MAV_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */ + MAV_TYPE_GCS=6, /* Operator control unit / ground control station | */ + MAV_TYPE_AIRSHIP=7, /* Airship, controlled | */ + MAV_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */ + MAV_TYPE_ROCKET=9, /* Rocket | */ + MAV_TYPE_GROUND_ROVER=10, /* Ground rover | */ + MAV_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */ + MAV_TYPE_SUBMARINE=12, /* Submarine | */ + MAV_TYPE_HEXAROTOR=13, /* Hexarotor | */ + MAV_TYPE_OCTOROTOR=14, /* Octorotor | */ + MAV_TYPE_TRICOPTER=15, /* Octorotor | */ + MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */ + MAV_TYPE_ENUM_END=17, /* | */ +}; +#endif + +/** @brief These flags encode the MAV mode. */ +#ifndef HAVE_ENUM_MAV_MODE_FLAG +#define HAVE_ENUM_MAV_MODE_FLAG +enum MAV_MODE_FLAG +{ + MAV_MODE_FLAG_CUSTOM_MODE_ENABLED=1, /* 0b00000001 Reserved for future use. | */ + MAV_MODE_FLAG_TEST_ENABLED=2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */ + MAV_MODE_FLAG_AUTO_ENABLED=4, /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */ + MAV_MODE_FLAG_GUIDED_ENABLED=8, /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */ + MAV_MODE_FLAG_STABILIZE_ENABLED=16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */ + MAV_MODE_FLAG_HIL_ENABLED=32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */ + MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64, /* 0b01000000 remote control input is enabled. | */ + MAV_MODE_FLAG_SAFETY_ARMED=128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */ + MAV_MODE_FLAG_ENUM_END=129, /* | */ +}; +#endif + +/** @brief These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. */ +#ifndef HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION +#define HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION +enum MAV_MODE_FLAG_DECODE_POSITION +{ + MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE=1, /* Eighth bit: 00000001 | */ + MAV_MODE_FLAG_DECODE_POSITION_TEST=2, /* Seventh bit: 00000010 | */ + MAV_MODE_FLAG_DECODE_POSITION_AUTO=4, /* Sixt bit: 00000100 | */ + MAV_MODE_FLAG_DECODE_POSITION_GUIDED=8, /* Fifth bit: 00001000 | */ + MAV_MODE_FLAG_DECODE_POSITION_STABILIZE=16, /* Fourth bit: 00010000 | */ + MAV_MODE_FLAG_DECODE_POSITION_HIL=32, /* Third bit: 00100000 | */ + MAV_MODE_FLAG_DECODE_POSITION_MANUAL=64, /* Second bit: 01000000 | */ + MAV_MODE_FLAG_DECODE_POSITION_SAFETY=128, /* First bit: 10000000 | */ + MAV_MODE_FLAG_DECODE_POSITION_ENUM_END=129, /* | */ +}; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_STATE +#define HAVE_ENUM_MAV_STATE +enum MAV_STATE +{ + MAV_STATE_UNINIT=0, /* Uninitialized system, state is unknown. | */ + MAV_STATE_BOOT=1, /* System is booting up. | */ + MAV_STATE_CALIBRATING=2, /* System is calibrating and not flight-ready. | */ + MAV_STATE_STANDBY=3, /* System is grounded and on standby. It can be launched any time. | */ + MAV_STATE_ACTIVE=4, /* System is active and might be already airborne. Motors are engaged. | */ + MAV_STATE_CRITICAL=5, /* System is in a non-normal flight mode. It can however still navigate. | */ + MAV_STATE_EMERGENCY=6, /* System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | */ + MAV_STATE_POWEROFF=7, /* System just initialized its power-down sequence, will shut down now. | */ + MAV_STATE_ENUM_END=8, /* | */ +}; +#endif + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_heartbeat.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // MINIMAL_H diff --git a/mavlink/include/v1.0/minimal/testsuite.h b/mavlink/include/mavlink/v1.0/minimal/testsuite.h similarity index 100% rename from mavlink/include/v1.0/minimal/testsuite.h rename to mavlink/include/mavlink/v1.0/minimal/testsuite.h diff --git a/mavlink/include/v1.0/minimal/version.h b/mavlink/include/mavlink/v1.0/minimal/version.h similarity index 84% rename from mavlink/include/v1.0/minimal/version.h rename to mavlink/include/mavlink/v1.0/minimal/version.h index 366fcc1eb69b90138e6d74246b8a7012f18b5711..d3d86c54324eede5433c37b4e72b25c07c338789 100644 --- a/mavlink/include/v1.0/minimal/version.h +++ b/mavlink/include/mavlink/v1.0/minimal/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Feb 9 16:35:36 2012" +#define MAVLINK_BUILD_DATE "Thu Apr 19 19:42:34 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 9 diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink.h new file mode 100644 index 0000000000000000000000000000000000000000..f062233708c922aed09cdfafd4f63f5010575371 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink.h @@ -0,0 +1,27 @@ +/** @file + * @brief MAVLink comm protocol built from pixhawk.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 "pixhawk.h" + +#endif // MAVLINK_H diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_attitude_control.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h similarity index 87% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_attitude_control.h rename to mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h index 32d9763efb52382e522328c5b7fc58917d8800be..819c45bf27307d395e8e0f9d074e7d13e7495135 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_attitude_control.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h @@ -4,11 +4,11 @@ typedef struct __mavlink_attitude_control_t { - uint8_t target; ///< The system to be controlled float roll; ///< roll float pitch; ///< pitch float yaw; ///< yaw float thrust; ///< thrust + uint8_t target; ///< The system to be controlled uint8_t roll_manual; ///< roll control enabled auto:0, manual:1 uint8_t pitch_manual; ///< pitch auto:0, manual:1 uint8_t yaw_manual; ///< yaw auto:0, manual:1 @@ -23,11 +23,11 @@ typedef struct __mavlink_attitude_control_t #define MAVLINK_MESSAGE_INFO_ATTITUDE_CONTROL { \ "ATTITUDE_CONTROL", \ 9, \ - { { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_attitude_control_t, target) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 1, offsetof(mavlink_attitude_control_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 5, offsetof(mavlink_attitude_control_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_attitude_control_t, yaw) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 13, offsetof(mavlink_attitude_control_t, thrust) }, \ + { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_attitude_control_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_control_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_control_t, yaw) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_control_t, thrust) }, \ + { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_attitude_control_t, target) }, \ { "roll_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_attitude_control_t, roll_manual) }, \ { "pitch_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_attitude_control_t, pitch_manual) }, \ { "yaw_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_attitude_control_t, yaw_manual) }, \ @@ -58,34 +58,34 @@ static inline uint16_t mavlink_msg_attitude_control_pack(uint8_t system_id, uint { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[21]; - _mav_put_uint8_t(buf, 0, target); - _mav_put_float(buf, 1, roll); - _mav_put_float(buf, 5, pitch); - _mav_put_float(buf, 9, yaw); - _mav_put_float(buf, 13, thrust); + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target); _mav_put_uint8_t(buf, 17, roll_manual); _mav_put_uint8_t(buf, 18, pitch_manual); _mav_put_uint8_t(buf, 19, yaw_manual); _mav_put_uint8_t(buf, 20, thrust_manual); - memcpy(_MAV_PAYLOAD(msg), buf, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21); #else mavlink_attitude_control_t packet; - packet.target = target; packet.roll = roll; packet.pitch = pitch; packet.yaw = yaw; packet.thrust = thrust; + packet.target = target; packet.roll_manual = roll_manual; packet.pitch_manual = pitch_manual; packet.yaw_manual = yaw_manual; packet.thrust_manual = thrust_manual; - memcpy(_MAV_PAYLOAD(msg), &packet, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21); #endif msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROL; - return mavlink_finalize_message(msg, system_id, component_id, 21); + return mavlink_finalize_message(msg, system_id, component_id, 21, 254); } /** @@ -111,34 +111,34 @@ static inline uint16_t mavlink_msg_attitude_control_pack_chan(uint8_t system_id, { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[21]; - _mav_put_uint8_t(buf, 0, target); - _mav_put_float(buf, 1, roll); - _mav_put_float(buf, 5, pitch); - _mav_put_float(buf, 9, yaw); - _mav_put_float(buf, 13, thrust); + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target); _mav_put_uint8_t(buf, 17, roll_manual); _mav_put_uint8_t(buf, 18, pitch_manual); _mav_put_uint8_t(buf, 19, yaw_manual); _mav_put_uint8_t(buf, 20, thrust_manual); - memcpy(_MAV_PAYLOAD(msg), buf, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21); #else mavlink_attitude_control_t packet; - packet.target = target; packet.roll = roll; packet.pitch = pitch; packet.yaw = yaw; packet.thrust = thrust; + packet.target = target; packet.roll_manual = roll_manual; packet.pitch_manual = pitch_manual; packet.yaw_manual = yaw_manual; packet.thrust_manual = thrust_manual; - memcpy(_MAV_PAYLOAD(msg), &packet, 21); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21); #endif msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 21); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 21, 254); } /** @@ -174,30 +174,30 @@ static inline void mavlink_msg_attitude_control_send(mavlink_channel_t chan, uin { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[21]; - _mav_put_uint8_t(buf, 0, target); - _mav_put_float(buf, 1, roll); - _mav_put_float(buf, 5, pitch); - _mav_put_float(buf, 9, yaw); - _mav_put_float(buf, 13, thrust); + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target); _mav_put_uint8_t(buf, 17, roll_manual); _mav_put_uint8_t(buf, 18, pitch_manual); _mav_put_uint8_t(buf, 19, yaw_manual); _mav_put_uint8_t(buf, 20, thrust_manual); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, buf, 21); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, buf, 21, 254); #else mavlink_attitude_control_t packet; - packet.target = target; packet.roll = roll; packet.pitch = pitch; packet.yaw = yaw; packet.thrust = thrust; + packet.target = target; packet.roll_manual = roll_manual; packet.pitch_manual = pitch_manual; packet.yaw_manual = yaw_manual; packet.thrust_manual = thrust_manual; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, (const char *)&packet, 21); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, (const char *)&packet, 21, 254); #endif } @@ -213,7 +213,7 @@ static inline void mavlink_msg_attitude_control_send(mavlink_channel_t chan, uin */ static inline uint8_t mavlink_msg_attitude_control_get_target(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 0); + return _MAV_RETURN_uint8_t(msg, 16); } /** @@ -223,7 +223,7 @@ static inline uint8_t mavlink_msg_attitude_control_get_target(const mavlink_mess */ static inline float mavlink_msg_attitude_control_get_roll(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 1); + return _MAV_RETURN_float(msg, 0); } /** @@ -233,7 +233,7 @@ static inline float mavlink_msg_attitude_control_get_roll(const mavlink_message_ */ static inline float mavlink_msg_attitude_control_get_pitch(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 5); + return _MAV_RETURN_float(msg, 4); } /** @@ -243,7 +243,7 @@ static inline float mavlink_msg_attitude_control_get_pitch(const mavlink_message */ static inline float mavlink_msg_attitude_control_get_yaw(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 9); + return _MAV_RETURN_float(msg, 8); } /** @@ -253,7 +253,7 @@ static inline float mavlink_msg_attitude_control_get_yaw(const mavlink_message_t */ static inline float mavlink_msg_attitude_control_get_thrust(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 13); + return _MAV_RETURN_float(msg, 12); } /** @@ -305,11 +305,11 @@ static inline uint8_t mavlink_msg_attitude_control_get_thrust_manual(const mavli static inline void mavlink_msg_attitude_control_decode(const mavlink_message_t* msg, mavlink_attitude_control_t* attitude_control) { #if MAVLINK_NEED_BYTE_SWAP - attitude_control->target = mavlink_msg_attitude_control_get_target(msg); attitude_control->roll = mavlink_msg_attitude_control_get_roll(msg); attitude_control->pitch = mavlink_msg_attitude_control_get_pitch(msg); attitude_control->yaw = mavlink_msg_attitude_control_get_yaw(msg); attitude_control->thrust = mavlink_msg_attitude_control_get_thrust(msg); + attitude_control->target = mavlink_msg_attitude_control_get_target(msg); attitude_control->roll_manual = mavlink_msg_attitude_control_get_roll_manual(msg); attitude_control->pitch_manual = mavlink_msg_attitude_control_get_pitch_manual(msg); attitude_control->yaw_manual = mavlink_msg_attitude_control_get_yaw_manual(msg); diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_brief_feature.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h similarity index 85% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_brief_feature.h rename to mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h index 52b7fcfa7366b7541bc0fb18051406e1019dba61..cde782b484963c2d72cc59ca49e5d45d3778a24f 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_brief_feature.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h @@ -7,11 +7,11 @@ typedef struct __mavlink_brief_feature_t float x; ///< x position in m float y; ///< y position in m float z; ///< z position in m - uint8_t orientation_assignment; ///< Orientation assignment 0: false, 1:true + float response; ///< Harris operator response at this location uint16_t size; ///< Size in pixels uint16_t orientation; ///< Orientation + uint8_t orientation_assignment; ///< Orientation assignment 0: false, 1:true uint8_t descriptor[32]; ///< Descriptor - float response; ///< Harris operator response at this location } mavlink_brief_feature_t; #define MAVLINK_MSG_ID_BRIEF_FEATURE_LEN 53 @@ -25,11 +25,11 @@ typedef struct __mavlink_brief_feature_t { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_brief_feature_t, x) }, \ { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_brief_feature_t, y) }, \ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_brief_feature_t, z) }, \ - { "orientation_assignment", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_brief_feature_t, orientation_assignment) }, \ - { "size", NULL, MAVLINK_TYPE_UINT16_T, 0, 13, offsetof(mavlink_brief_feature_t, size) }, \ - { "orientation", NULL, MAVLINK_TYPE_UINT16_T, 0, 15, offsetof(mavlink_brief_feature_t, orientation) }, \ - { "descriptor", NULL, MAVLINK_TYPE_UINT8_T, 32, 17, offsetof(mavlink_brief_feature_t, descriptor) }, \ - { "response", NULL, MAVLINK_TYPE_FLOAT, 0, 49, offsetof(mavlink_brief_feature_t, response) }, \ + { "response", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_brief_feature_t, response) }, \ + { "size", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_brief_feature_t, size) }, \ + { "orientation", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_brief_feature_t, orientation) }, \ + { "orientation_assignment", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_brief_feature_t, orientation_assignment) }, \ + { "descriptor", NULL, MAVLINK_TYPE_UINT8_T, 32, 21, offsetof(mavlink_brief_feature_t, descriptor) }, \ } \ } @@ -58,27 +58,27 @@ static inline uint16_t mavlink_msg_brief_feature_pack(uint8_t system_id, uint8_t _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); - _mav_put_uint8_t(buf, 12, orientation_assignment); - _mav_put_uint16_t(buf, 13, size); - _mav_put_uint16_t(buf, 15, orientation); - _mav_put_float(buf, 49, response); - _mav_put_uint8_t_array(buf, 17, descriptor, 32); - memcpy(_MAV_PAYLOAD(msg), buf, 53); + _mav_put_float(buf, 12, response); + _mav_put_uint16_t(buf, 16, size); + _mav_put_uint16_t(buf, 18, orientation); + _mav_put_uint8_t(buf, 20, orientation_assignment); + _mav_put_uint8_t_array(buf, 21, descriptor, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 53); #else mavlink_brief_feature_t packet; packet.x = x; packet.y = y; packet.z = z; - packet.orientation_assignment = orientation_assignment; + packet.response = response; packet.size = size; packet.orientation = orientation; - packet.response = response; + packet.orientation_assignment = orientation_assignment; mav_array_memcpy(packet.descriptor, descriptor, sizeof(uint8_t)*32); - memcpy(_MAV_PAYLOAD(msg), &packet, 53); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 53); #endif msg->msgid = MAVLINK_MSG_ID_BRIEF_FEATURE; - return mavlink_finalize_message(msg, system_id, component_id, 53); + return mavlink_finalize_message(msg, system_id, component_id, 53, 88); } /** @@ -106,27 +106,27 @@ static inline uint16_t mavlink_msg_brief_feature_pack_chan(uint8_t system_id, ui _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); - _mav_put_uint8_t(buf, 12, orientation_assignment); - _mav_put_uint16_t(buf, 13, size); - _mav_put_uint16_t(buf, 15, orientation); - _mav_put_float(buf, 49, response); - _mav_put_uint8_t_array(buf, 17, descriptor, 32); - memcpy(_MAV_PAYLOAD(msg), buf, 53); + _mav_put_float(buf, 12, response); + _mav_put_uint16_t(buf, 16, size); + _mav_put_uint16_t(buf, 18, orientation); + _mav_put_uint8_t(buf, 20, orientation_assignment); + _mav_put_uint8_t_array(buf, 21, descriptor, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 53); #else mavlink_brief_feature_t packet; packet.x = x; packet.y = y; packet.z = z; - packet.orientation_assignment = orientation_assignment; + packet.response = response; packet.size = size; packet.orientation = orientation; - packet.response = response; + packet.orientation_assignment = orientation_assignment; mav_array_memcpy(packet.descriptor, descriptor, sizeof(uint8_t)*32); - memcpy(_MAV_PAYLOAD(msg), &packet, 53); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 53); #endif msg->msgid = MAVLINK_MSG_ID_BRIEF_FEATURE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 53); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 53, 88); } /** @@ -164,23 +164,23 @@ static inline void mavlink_msg_brief_feature_send(mavlink_channel_t chan, float _mav_put_float(buf, 0, x); _mav_put_float(buf, 4, y); _mav_put_float(buf, 8, z); - _mav_put_uint8_t(buf, 12, orientation_assignment); - _mav_put_uint16_t(buf, 13, size); - _mav_put_uint16_t(buf, 15, orientation); - _mav_put_float(buf, 49, response); - _mav_put_uint8_t_array(buf, 17, descriptor, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, buf, 53); + _mav_put_float(buf, 12, response); + _mav_put_uint16_t(buf, 16, size); + _mav_put_uint16_t(buf, 18, orientation); + _mav_put_uint8_t(buf, 20, orientation_assignment); + _mav_put_uint8_t_array(buf, 21, descriptor, 32); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, buf, 53, 88); #else mavlink_brief_feature_t packet; packet.x = x; packet.y = y; packet.z = z; - packet.orientation_assignment = orientation_assignment; + packet.response = response; packet.size = size; packet.orientation = orientation; - packet.response = response; + packet.orientation_assignment = orientation_assignment; mav_array_memcpy(packet.descriptor, descriptor, sizeof(uint8_t)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, (const char *)&packet, 53); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, (const char *)&packet, 53, 88); #endif } @@ -226,7 +226,7 @@ static inline float mavlink_msg_brief_feature_get_z(const mavlink_message_t* msg */ static inline uint8_t mavlink_msg_brief_feature_get_orientation_assignment(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 12); + return _MAV_RETURN_uint8_t(msg, 20); } /** @@ -236,7 +236,7 @@ static inline uint8_t mavlink_msg_brief_feature_get_orientation_assignment(const */ static inline uint16_t mavlink_msg_brief_feature_get_size(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 13); + return _MAV_RETURN_uint16_t(msg, 16); } /** @@ -246,7 +246,7 @@ static inline uint16_t mavlink_msg_brief_feature_get_size(const mavlink_message_ */ static inline uint16_t mavlink_msg_brief_feature_get_orientation(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 15); + return _MAV_RETURN_uint16_t(msg, 18); } /** @@ -256,7 +256,7 @@ static inline uint16_t mavlink_msg_brief_feature_get_orientation(const mavlink_m */ static inline uint16_t mavlink_msg_brief_feature_get_descriptor(const mavlink_message_t* msg, uint8_t *descriptor) { - return _MAV_RETURN_uint8_t_array(msg, descriptor, 32, 17); + return _MAV_RETURN_uint8_t_array(msg, descriptor, 32, 21); } /** @@ -266,7 +266,7 @@ static inline uint16_t mavlink_msg_brief_feature_get_descriptor(const mavlink_me */ static inline float mavlink_msg_brief_feature_get_response(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 49); + return _MAV_RETURN_float(msg, 12); } /** @@ -281,11 +281,11 @@ static inline void mavlink_msg_brief_feature_decode(const mavlink_message_t* msg brief_feature->x = mavlink_msg_brief_feature_get_x(msg); brief_feature->y = mavlink_msg_brief_feature_get_y(msg); brief_feature->z = mavlink_msg_brief_feature_get_z(msg); - brief_feature->orientation_assignment = mavlink_msg_brief_feature_get_orientation_assignment(msg); + brief_feature->response = mavlink_msg_brief_feature_get_response(msg); brief_feature->size = mavlink_msg_brief_feature_get_size(msg); brief_feature->orientation = mavlink_msg_brief_feature_get_orientation(msg); + brief_feature->orientation_assignment = mavlink_msg_brief_feature_get_orientation_assignment(msg); mavlink_msg_brief_feature_get_descriptor(msg, brief_feature->descriptor); - brief_feature->response = mavlink_msg_brief_feature_get_response(msg); #else memcpy(brief_feature, _MAV_PAYLOAD(msg), 53); #endif diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_data_transmission_handshake.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_data_transmission_handshake.h similarity index 63% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_data_transmission_handshake.h rename to mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_data_transmission_handshake.h index 1026439ccf468651dede26ade8a3fd6b14d5f146..d3ca73f12d59afeb97f3e9371d58931eaf213ab4 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_data_transmission_handshake.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_data_transmission_handshake.h @@ -4,26 +4,30 @@ typedef struct __mavlink_data_transmission_handshake_t { - uint8_t type; ///< type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) uint32_t size; ///< total data size in bytes (set on ACK only) + uint16_t width; ///< Width of a matrix or image + uint16_t height; ///< Height of a matrix or image + uint8_t type; ///< type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) uint8_t packets; ///< number of packets beeing sent (set on ACK only) uint8_t payload; ///< payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) uint8_t jpg_quality; ///< JPEG quality out of [1,100] } mavlink_data_transmission_handshake_t; -#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 8 -#define MAVLINK_MSG_ID_193_LEN 8 +#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 12 +#define MAVLINK_MSG_ID_193_LEN 12 #define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE { \ "DATA_TRANSMISSION_HANDSHAKE", \ - 5, \ - { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, type) }, \ - { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 1, offsetof(mavlink_data_transmission_handshake_t, size) }, \ - { "packets", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_data_transmission_handshake_t, packets) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, payload) }, \ - { "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \ + 7, \ + { { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \ + { "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, width) }, \ + { "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, height) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, type) }, \ + { "packets", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_data_transmission_handshake_t, packets) }, \ + { "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, payload) }, \ + { "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \ } \ } @@ -36,36 +40,42 @@ typedef struct __mavlink_data_transmission_handshake_t * * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) * @param size total data size in bytes (set on ACK only) + * @param width Width of a matrix or image + * @param height Height of a matrix or image * @param packets number of packets beeing sent (set on ACK only) * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) * @param jpg_quality JPEG quality out of [1,100] * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t type, uint32_t size, uint8_t packets, uint8_t payload, uint8_t jpg_quality) + uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint8_t packets, uint8_t payload, uint8_t jpg_quality) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[8]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint32_t(buf, 1, size); - _mav_put_uint8_t(buf, 5, packets); - _mav_put_uint8_t(buf, 6, payload); - _mav_put_uint8_t(buf, 7, jpg_quality); - - memcpy(_MAV_PAYLOAD(msg), buf, 8); + char buf[12]; + _mav_put_uint32_t(buf, 0, size); + _mav_put_uint16_t(buf, 4, width); + _mav_put_uint16_t(buf, 6, height); + _mav_put_uint8_t(buf, 8, type); + _mav_put_uint8_t(buf, 9, packets); + _mav_put_uint8_t(buf, 10, payload); + _mav_put_uint8_t(buf, 11, jpg_quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); #else mavlink_data_transmission_handshake_t packet; - packet.type = type; packet.size = size; + packet.width = width; + packet.height = height; + packet.type = type; packet.packets = packets; packet.payload = payload; packet.jpg_quality = jpg_quality; - memcpy(_MAV_PAYLOAD(msg), &packet, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); #endif msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE; - return mavlink_finalize_message(msg, system_id, component_id, 8); + return mavlink_finalize_message(msg, system_id, component_id, 12, 23); } /** @@ -76,6 +86,8 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t syst * @param msg The MAVLink message to compress the data into * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) * @param size total data size in bytes (set on ACK only) + * @param width Width of a matrix or image + * @param height Height of a matrix or image * @param packets number of packets beeing sent (set on ACK only) * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) * @param jpg_quality JPEG quality out of [1,100] @@ -83,30 +95,34 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t syst */ static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, - uint8_t type,uint32_t size,uint8_t packets,uint8_t payload,uint8_t jpg_quality) + uint8_t type,uint32_t size,uint16_t width,uint16_t height,uint8_t packets,uint8_t payload,uint8_t jpg_quality) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[8]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint32_t(buf, 1, size); - _mav_put_uint8_t(buf, 5, packets); - _mav_put_uint8_t(buf, 6, payload); - _mav_put_uint8_t(buf, 7, jpg_quality); - - memcpy(_MAV_PAYLOAD(msg), buf, 8); + char buf[12]; + _mav_put_uint32_t(buf, 0, size); + _mav_put_uint16_t(buf, 4, width); + _mav_put_uint16_t(buf, 6, height); + _mav_put_uint8_t(buf, 8, type); + _mav_put_uint8_t(buf, 9, packets); + _mav_put_uint8_t(buf, 10, payload); + _mav_put_uint8_t(buf, 11, jpg_quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); #else mavlink_data_transmission_handshake_t packet; - packet.type = type; packet.size = size; + packet.width = width; + packet.height = height; + packet.type = type; packet.packets = packets; packet.payload = payload; packet.jpg_quality = jpg_quality; - memcpy(_MAV_PAYLOAD(msg), &packet, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); #endif msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 23); } /** @@ -119,7 +135,7 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t */ static inline uint16_t mavlink_msg_data_transmission_handshake_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake) { - return mavlink_msg_data_transmission_handshake_pack(system_id, component_id, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); + return mavlink_msg_data_transmission_handshake_pack(system_id, component_id, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); } /** @@ -128,32 +144,38 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_encode(uint8_t sy * * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) * @param size total data size in bytes (set on ACK only) + * @param width Width of a matrix or image + * @param height Height of a matrix or image * @param packets number of packets beeing sent (set on ACK only) * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) * @param jpg_quality JPEG quality out of [1,100] */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_t chan, uint8_t type, uint32_t size, uint8_t packets, uint8_t payload, uint8_t jpg_quality) +static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_t chan, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint8_t packets, uint8_t payload, uint8_t jpg_quality) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[8]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint32_t(buf, 1, size); - _mav_put_uint8_t(buf, 5, packets); - _mav_put_uint8_t(buf, 6, payload); - _mav_put_uint8_t(buf, 7, jpg_quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, 8); + char buf[12]; + _mav_put_uint32_t(buf, 0, size); + _mav_put_uint16_t(buf, 4, width); + _mav_put_uint16_t(buf, 6, height); + _mav_put_uint8_t(buf, 8, type); + _mav_put_uint8_t(buf, 9, packets); + _mav_put_uint8_t(buf, 10, payload); + _mav_put_uint8_t(buf, 11, jpg_quality); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, 12, 23); #else mavlink_data_transmission_handshake_t packet; - packet.type = type; packet.size = size; + packet.width = width; + packet.height = height; + packet.type = type; packet.packets = packets; packet.payload = payload; packet.jpg_quality = jpg_quality; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, 8); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, 12, 23); #endif } @@ -169,7 +191,7 @@ static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_ */ static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 0); + return _MAV_RETURN_uint8_t(msg, 8); } /** @@ -179,7 +201,27 @@ static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mav */ static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const mavlink_message_t* msg) { - return _MAV_RETURN_uint32_t(msg, 1); + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field width from data_transmission_handshake message + * + * @return Width of a matrix or image + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_get_width(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field height from data_transmission_handshake message + * + * @return Height of a matrix or image + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_get_height(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); } /** @@ -189,7 +231,7 @@ static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const ma */ static inline uint8_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 5); + return _MAV_RETURN_uint8_t(msg, 9); } /** @@ -199,7 +241,7 @@ static inline uint8_t mavlink_msg_data_transmission_handshake_get_packets(const */ static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 6); + return _MAV_RETURN_uint8_t(msg, 10); } /** @@ -209,7 +251,7 @@ static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const */ static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 7); + return _MAV_RETURN_uint8_t(msg, 11); } /** @@ -221,12 +263,14 @@ static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(co static inline void mavlink_msg_data_transmission_handshake_decode(const mavlink_message_t* msg, mavlink_data_transmission_handshake_t* data_transmission_handshake) { #if MAVLINK_NEED_BYTE_SWAP - data_transmission_handshake->type = mavlink_msg_data_transmission_handshake_get_type(msg); data_transmission_handshake->size = mavlink_msg_data_transmission_handshake_get_size(msg); + data_transmission_handshake->width = mavlink_msg_data_transmission_handshake_get_width(msg); + data_transmission_handshake->height = mavlink_msg_data_transmission_handshake_get_height(msg); + data_transmission_handshake->type = mavlink_msg_data_transmission_handshake_get_type(msg); data_transmission_handshake->packets = mavlink_msg_data_transmission_handshake_get_packets(msg); data_transmission_handshake->payload = mavlink_msg_data_transmission_handshake_get_payload(msg); data_transmission_handshake->jpg_quality = mavlink_msg_data_transmission_handshake_get_jpg_quality(msg); #else - memcpy(data_transmission_handshake, _MAV_PAYLOAD(msg), 8); + memcpy(data_transmission_handshake, _MAV_PAYLOAD(msg), 12); #endif } diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_encapsulated_data.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_encapsulated_data.h similarity index 94% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_encapsulated_data.h rename to mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_encapsulated_data.h index d730d547fd3139299277379cd9efda59bde2ad99..e07be29528e02260d2a212b6c7f193fe5f337d2c 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_encapsulated_data.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_encapsulated_data.h @@ -39,16 +39,16 @@ static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uin char buf[255]; _mav_put_uint16_t(buf, 0, seqnr); _mav_put_uint8_t_array(buf, 2, data, 253); - memcpy(_MAV_PAYLOAD(msg), buf, 255); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 255); #else mavlink_encapsulated_data_t packet; packet.seqnr = seqnr; mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253); - memcpy(_MAV_PAYLOAD(msg), &packet, 255); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 255); #endif msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA; - return mavlink_finalize_message(msg, system_id, component_id, 255); + return mavlink_finalize_message(msg, system_id, component_id, 255, 223); } /** @@ -69,16 +69,16 @@ static inline uint16_t mavlink_msg_encapsulated_data_pack_chan(uint8_t system_id char buf[255]; _mav_put_uint16_t(buf, 0, seqnr); _mav_put_uint8_t_array(buf, 2, data, 253); - memcpy(_MAV_PAYLOAD(msg), buf, 255); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 255); #else mavlink_encapsulated_data_t packet; packet.seqnr = seqnr; mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253); - memcpy(_MAV_PAYLOAD(msg), &packet, 255); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 255); #endif msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 255); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 255, 223); } /** @@ -109,12 +109,12 @@ static inline void mavlink_msg_encapsulated_data_send(mavlink_channel_t chan, ui char buf[255]; _mav_put_uint16_t(buf, 0, seqnr); _mav_put_uint8_t_array(buf, 2, data, 253); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, 255); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, 255, 223); #else mavlink_encapsulated_data_t packet; packet.seqnr = seqnr; mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)&packet, 255); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)&packet, 255, 223); #endif } diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_image_available.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h similarity index 79% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_image_available.h rename to mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h index 37cc547edd5f2da7b2a8b7cd0b3ef964f0855bea..913fcd94c15636c5d0a2c3b436fb2fd51350875a 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_image_available.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h @@ -5,15 +5,10 @@ typedef struct __mavlink_image_available_t { uint64_t cam_id; ///< Camera id - uint8_t cam_no; ///< Camera # (starts with 0) uint64_t timestamp; ///< Timestamp uint64_t valid_until; ///< Until which timestamp this buffer will stay valid uint32_t img_seq; ///< The image sequence number uint32_t img_buf_index; ///< Position of the image in the buffer, starts with 0 - uint16_t width; ///< Image width - uint16_t height; ///< Image height - uint16_t depth; ///< Image depth - uint8_t channels; ///< Image channels uint32_t key; ///< Shared memory area key uint32_t exposure; ///< Exposure time, in microseconds float gain; ///< Camera gain @@ -27,6 +22,11 @@ typedef struct __mavlink_image_available_t float ground_x; ///< Ground truth X float ground_y; ///< Ground truth Y float ground_z; ///< Ground truth Z + uint16_t width; ///< Image width + uint16_t height; ///< Image height + uint16_t depth; ///< Image depth + uint8_t cam_no; ///< Camera # (starts with 0) + uint8_t channels; ///< Image channels } mavlink_image_available_t; #define MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN 92 @@ -38,28 +38,28 @@ typedef struct __mavlink_image_available_t "IMAGE_AVAILABLE", \ 23, \ { { "cam_id", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_image_available_t, cam_id) }, \ - { "cam_no", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_image_available_t, cam_no) }, \ - { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 9, offsetof(mavlink_image_available_t, timestamp) }, \ - { "valid_until", NULL, MAVLINK_TYPE_UINT64_T, 0, 17, offsetof(mavlink_image_available_t, valid_until) }, \ - { "img_seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 25, offsetof(mavlink_image_available_t, img_seq) }, \ - { "img_buf_index", NULL, MAVLINK_TYPE_UINT32_T, 0, 29, offsetof(mavlink_image_available_t, img_buf_index) }, \ - { "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 33, offsetof(mavlink_image_available_t, width) }, \ - { "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 35, offsetof(mavlink_image_available_t, height) }, \ - { "depth", NULL, MAVLINK_TYPE_UINT16_T, 0, 37, offsetof(mavlink_image_available_t, depth) }, \ - { "channels", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_image_available_t, channels) }, \ - { "key", NULL, MAVLINK_TYPE_UINT32_T, 0, 40, offsetof(mavlink_image_available_t, key) }, \ - { "exposure", NULL, MAVLINK_TYPE_UINT32_T, 0, 44, offsetof(mavlink_image_available_t, exposure) }, \ - { "gain", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_image_available_t, gain) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_image_available_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_image_available_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_image_available_t, yaw) }, \ - { "local_z", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_image_available_t, local_z) }, \ - { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_image_available_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_image_available_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_image_available_t, alt) }, \ - { "ground_x", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_image_available_t, ground_x) }, \ - { "ground_y", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_image_available_t, ground_y) }, \ - { "ground_z", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_image_available_t, ground_z) }, \ + { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_image_available_t, timestamp) }, \ + { "valid_until", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_image_available_t, valid_until) }, \ + { "img_seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_image_available_t, img_seq) }, \ + { "img_buf_index", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_image_available_t, img_buf_index) }, \ + { "key", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_image_available_t, key) }, \ + { "exposure", NULL, MAVLINK_TYPE_UINT32_T, 0, 36, offsetof(mavlink_image_available_t, exposure) }, \ + { "gain", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_image_available_t, gain) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_image_available_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_image_available_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_image_available_t, yaw) }, \ + { "local_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_image_available_t, local_z) }, \ + { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_image_available_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_image_available_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_image_available_t, alt) }, \ + { "ground_x", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_image_available_t, ground_x) }, \ + { "ground_y", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_image_available_t, ground_y) }, \ + { "ground_z", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_image_available_t, ground_z) }, \ + { "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 84, offsetof(mavlink_image_available_t, width) }, \ + { "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 86, offsetof(mavlink_image_available_t, height) }, \ + { "depth", NULL, MAVLINK_TYPE_UINT16_T, 0, 88, offsetof(mavlink_image_available_t, depth) }, \ + { "cam_no", NULL, MAVLINK_TYPE_UINT8_T, 0, 90, offsetof(mavlink_image_available_t, cam_no) }, \ + { "channels", NULL, MAVLINK_TYPE_UINT8_T, 0, 91, offsetof(mavlink_image_available_t, channels) }, \ } \ } @@ -101,42 +101,37 @@ static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[92]; _mav_put_uint64_t(buf, 0, cam_id); - _mav_put_uint8_t(buf, 8, cam_no); - _mav_put_uint64_t(buf, 9, timestamp); - _mav_put_uint64_t(buf, 17, valid_until); - _mav_put_uint32_t(buf, 25, img_seq); - _mav_put_uint32_t(buf, 29, img_buf_index); - _mav_put_uint16_t(buf, 33, width); - _mav_put_uint16_t(buf, 35, height); - _mav_put_uint16_t(buf, 37, depth); - _mav_put_uint8_t(buf, 39, channels); - _mav_put_uint32_t(buf, 40, key); - _mav_put_uint32_t(buf, 44, exposure); - _mav_put_float(buf, 48, gain); - _mav_put_float(buf, 52, roll); - _mav_put_float(buf, 56, pitch); - _mav_put_float(buf, 60, yaw); - _mav_put_float(buf, 64, local_z); - _mav_put_float(buf, 68, lat); - _mav_put_float(buf, 72, lon); - _mav_put_float(buf, 76, alt); - _mav_put_float(buf, 80, ground_x); - _mav_put_float(buf, 84, ground_y); - _mav_put_float(buf, 88, ground_z); - - memcpy(_MAV_PAYLOAD(msg), buf, 92); + _mav_put_uint64_t(buf, 8, timestamp); + _mav_put_uint64_t(buf, 16, valid_until); + _mav_put_uint32_t(buf, 24, img_seq); + _mav_put_uint32_t(buf, 28, img_buf_index); + _mav_put_uint32_t(buf, 32, key); + _mav_put_uint32_t(buf, 36, exposure); + _mav_put_float(buf, 40, gain); + _mav_put_float(buf, 44, roll); + _mav_put_float(buf, 48, pitch); + _mav_put_float(buf, 52, yaw); + _mav_put_float(buf, 56, local_z); + _mav_put_float(buf, 60, lat); + _mav_put_float(buf, 64, lon); + _mav_put_float(buf, 68, alt); + _mav_put_float(buf, 72, ground_x); + _mav_put_float(buf, 76, ground_y); + _mav_put_float(buf, 80, ground_z); + _mav_put_uint16_t(buf, 84, width); + _mav_put_uint16_t(buf, 86, height); + _mav_put_uint16_t(buf, 88, depth); + _mav_put_uint8_t(buf, 90, cam_no); + _mav_put_uint8_t(buf, 91, channels); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 92); #else mavlink_image_available_t packet; packet.cam_id = cam_id; - packet.cam_no = cam_no; packet.timestamp = timestamp; packet.valid_until = valid_until; packet.img_seq = img_seq; packet.img_buf_index = img_buf_index; - packet.width = width; - packet.height = height; - packet.depth = depth; - packet.channels = channels; packet.key = key; packet.exposure = exposure; packet.gain = gain; @@ -150,12 +145,17 @@ static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8 packet.ground_x = ground_x; packet.ground_y = ground_y; packet.ground_z = ground_z; + packet.width = width; + packet.height = height; + packet.depth = depth; + packet.cam_no = cam_no; + packet.channels = channels; - memcpy(_MAV_PAYLOAD(msg), &packet, 92); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 92); #endif msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE; - return mavlink_finalize_message(msg, system_id, component_id, 92); + return mavlink_finalize_message(msg, system_id, component_id, 92, 224); } /** @@ -196,42 +196,37 @@ static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id, #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[92]; _mav_put_uint64_t(buf, 0, cam_id); - _mav_put_uint8_t(buf, 8, cam_no); - _mav_put_uint64_t(buf, 9, timestamp); - _mav_put_uint64_t(buf, 17, valid_until); - _mav_put_uint32_t(buf, 25, img_seq); - _mav_put_uint32_t(buf, 29, img_buf_index); - _mav_put_uint16_t(buf, 33, width); - _mav_put_uint16_t(buf, 35, height); - _mav_put_uint16_t(buf, 37, depth); - _mav_put_uint8_t(buf, 39, channels); - _mav_put_uint32_t(buf, 40, key); - _mav_put_uint32_t(buf, 44, exposure); - _mav_put_float(buf, 48, gain); - _mav_put_float(buf, 52, roll); - _mav_put_float(buf, 56, pitch); - _mav_put_float(buf, 60, yaw); - _mav_put_float(buf, 64, local_z); - _mav_put_float(buf, 68, lat); - _mav_put_float(buf, 72, lon); - _mav_put_float(buf, 76, alt); - _mav_put_float(buf, 80, ground_x); - _mav_put_float(buf, 84, ground_y); - _mav_put_float(buf, 88, ground_z); - - memcpy(_MAV_PAYLOAD(msg), buf, 92); + _mav_put_uint64_t(buf, 8, timestamp); + _mav_put_uint64_t(buf, 16, valid_until); + _mav_put_uint32_t(buf, 24, img_seq); + _mav_put_uint32_t(buf, 28, img_buf_index); + _mav_put_uint32_t(buf, 32, key); + _mav_put_uint32_t(buf, 36, exposure); + _mav_put_float(buf, 40, gain); + _mav_put_float(buf, 44, roll); + _mav_put_float(buf, 48, pitch); + _mav_put_float(buf, 52, yaw); + _mav_put_float(buf, 56, local_z); + _mav_put_float(buf, 60, lat); + _mav_put_float(buf, 64, lon); + _mav_put_float(buf, 68, alt); + _mav_put_float(buf, 72, ground_x); + _mav_put_float(buf, 76, ground_y); + _mav_put_float(buf, 80, ground_z); + _mav_put_uint16_t(buf, 84, width); + _mav_put_uint16_t(buf, 86, height); + _mav_put_uint16_t(buf, 88, depth); + _mav_put_uint8_t(buf, 90, cam_no); + _mav_put_uint8_t(buf, 91, channels); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 92); #else mavlink_image_available_t packet; packet.cam_id = cam_id; - packet.cam_no = cam_no; packet.timestamp = timestamp; packet.valid_until = valid_until; packet.img_seq = img_seq; packet.img_buf_index = img_buf_index; - packet.width = width; - packet.height = height; - packet.depth = depth; - packet.channels = channels; packet.key = key; packet.exposure = exposure; packet.gain = gain; @@ -245,12 +240,17 @@ static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id, packet.ground_x = ground_x; packet.ground_y = ground_y; packet.ground_z = ground_z; + packet.width = width; + packet.height = height; + packet.depth = depth; + packet.cam_no = cam_no; + packet.channels = channels; - memcpy(_MAV_PAYLOAD(msg), &packet, 92); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 92); #endif msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 92); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 92, 224); } /** @@ -301,42 +301,37 @@ static inline void mavlink_msg_image_available_send(mavlink_channel_t chan, uint #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[92]; _mav_put_uint64_t(buf, 0, cam_id); - _mav_put_uint8_t(buf, 8, cam_no); - _mav_put_uint64_t(buf, 9, timestamp); - _mav_put_uint64_t(buf, 17, valid_until); - _mav_put_uint32_t(buf, 25, img_seq); - _mav_put_uint32_t(buf, 29, img_buf_index); - _mav_put_uint16_t(buf, 33, width); - _mav_put_uint16_t(buf, 35, height); - _mav_put_uint16_t(buf, 37, depth); - _mav_put_uint8_t(buf, 39, channels); - _mav_put_uint32_t(buf, 40, key); - _mav_put_uint32_t(buf, 44, exposure); - _mav_put_float(buf, 48, gain); - _mav_put_float(buf, 52, roll); - _mav_put_float(buf, 56, pitch); - _mav_put_float(buf, 60, yaw); - _mav_put_float(buf, 64, local_z); - _mav_put_float(buf, 68, lat); - _mav_put_float(buf, 72, lon); - _mav_put_float(buf, 76, alt); - _mav_put_float(buf, 80, ground_x); - _mav_put_float(buf, 84, ground_y); - _mav_put_float(buf, 88, ground_z); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, buf, 92); + _mav_put_uint64_t(buf, 8, timestamp); + _mav_put_uint64_t(buf, 16, valid_until); + _mav_put_uint32_t(buf, 24, img_seq); + _mav_put_uint32_t(buf, 28, img_buf_index); + _mav_put_uint32_t(buf, 32, key); + _mav_put_uint32_t(buf, 36, exposure); + _mav_put_float(buf, 40, gain); + _mav_put_float(buf, 44, roll); + _mav_put_float(buf, 48, pitch); + _mav_put_float(buf, 52, yaw); + _mav_put_float(buf, 56, local_z); + _mav_put_float(buf, 60, lat); + _mav_put_float(buf, 64, lon); + _mav_put_float(buf, 68, alt); + _mav_put_float(buf, 72, ground_x); + _mav_put_float(buf, 76, ground_y); + _mav_put_float(buf, 80, ground_z); + _mav_put_uint16_t(buf, 84, width); + _mav_put_uint16_t(buf, 86, height); + _mav_put_uint16_t(buf, 88, depth); + _mav_put_uint8_t(buf, 90, cam_no); + _mav_put_uint8_t(buf, 91, channels); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, buf, 92, 224); #else mavlink_image_available_t packet; packet.cam_id = cam_id; - packet.cam_no = cam_no; packet.timestamp = timestamp; packet.valid_until = valid_until; packet.img_seq = img_seq; packet.img_buf_index = img_buf_index; - packet.width = width; - packet.height = height; - packet.depth = depth; - packet.channels = channels; packet.key = key; packet.exposure = exposure; packet.gain = gain; @@ -350,8 +345,13 @@ static inline void mavlink_msg_image_available_send(mavlink_channel_t chan, uint packet.ground_x = ground_x; packet.ground_y = ground_y; packet.ground_z = ground_z; + packet.width = width; + packet.height = height; + packet.depth = depth; + packet.cam_no = cam_no; + packet.channels = channels; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, (const char *)&packet, 92); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, (const char *)&packet, 92, 224); #endif } @@ -377,7 +377,7 @@ static inline uint64_t mavlink_msg_image_available_get_cam_id(const mavlink_mess */ static inline uint8_t mavlink_msg_image_available_get_cam_no(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 8); + return _MAV_RETURN_uint8_t(msg, 90); } /** @@ -387,7 +387,7 @@ static inline uint8_t mavlink_msg_image_available_get_cam_no(const mavlink_messa */ static inline uint64_t mavlink_msg_image_available_get_timestamp(const mavlink_message_t* msg) { - return _MAV_RETURN_uint64_t(msg, 9); + return _MAV_RETURN_uint64_t(msg, 8); } /** @@ -397,7 +397,7 @@ static inline uint64_t mavlink_msg_image_available_get_timestamp(const mavlink_m */ static inline uint64_t mavlink_msg_image_available_get_valid_until(const mavlink_message_t* msg) { - return _MAV_RETURN_uint64_t(msg, 17); + return _MAV_RETURN_uint64_t(msg, 16); } /** @@ -407,7 +407,7 @@ static inline uint64_t mavlink_msg_image_available_get_valid_until(const mavlink */ static inline uint32_t mavlink_msg_image_available_get_img_seq(const mavlink_message_t* msg) { - return _MAV_RETURN_uint32_t(msg, 25); + return _MAV_RETURN_uint32_t(msg, 24); } /** @@ -417,7 +417,7 @@ static inline uint32_t mavlink_msg_image_available_get_img_seq(const mavlink_mes */ static inline uint32_t mavlink_msg_image_available_get_img_buf_index(const mavlink_message_t* msg) { - return _MAV_RETURN_uint32_t(msg, 29); + return _MAV_RETURN_uint32_t(msg, 28); } /** @@ -427,7 +427,7 @@ static inline uint32_t mavlink_msg_image_available_get_img_buf_index(const mavli */ static inline uint16_t mavlink_msg_image_available_get_width(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 33); + return _MAV_RETURN_uint16_t(msg, 84); } /** @@ -437,7 +437,7 @@ static inline uint16_t mavlink_msg_image_available_get_width(const mavlink_messa */ static inline uint16_t mavlink_msg_image_available_get_height(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 35); + return _MAV_RETURN_uint16_t(msg, 86); } /** @@ -447,7 +447,7 @@ static inline uint16_t mavlink_msg_image_available_get_height(const mavlink_mess */ static inline uint16_t mavlink_msg_image_available_get_depth(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 37); + return _MAV_RETURN_uint16_t(msg, 88); } /** @@ -457,7 +457,7 @@ static inline uint16_t mavlink_msg_image_available_get_depth(const mavlink_messa */ static inline uint8_t mavlink_msg_image_available_get_channels(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 39); + return _MAV_RETURN_uint8_t(msg, 91); } /** @@ -467,7 +467,7 @@ static inline uint8_t mavlink_msg_image_available_get_channels(const mavlink_mes */ static inline uint32_t mavlink_msg_image_available_get_key(const mavlink_message_t* msg) { - return _MAV_RETURN_uint32_t(msg, 40); + return _MAV_RETURN_uint32_t(msg, 32); } /** @@ -477,7 +477,7 @@ static inline uint32_t mavlink_msg_image_available_get_key(const mavlink_message */ static inline uint32_t mavlink_msg_image_available_get_exposure(const mavlink_message_t* msg) { - return _MAV_RETURN_uint32_t(msg, 44); + return _MAV_RETURN_uint32_t(msg, 36); } /** @@ -487,7 +487,7 @@ static inline uint32_t mavlink_msg_image_available_get_exposure(const mavlink_me */ static inline float mavlink_msg_image_available_get_gain(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 48); + return _MAV_RETURN_float(msg, 40); } /** @@ -497,7 +497,7 @@ static inline float mavlink_msg_image_available_get_gain(const mavlink_message_t */ static inline float mavlink_msg_image_available_get_roll(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 52); + return _MAV_RETURN_float(msg, 44); } /** @@ -507,7 +507,7 @@ static inline float mavlink_msg_image_available_get_roll(const mavlink_message_t */ static inline float mavlink_msg_image_available_get_pitch(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 56); + return _MAV_RETURN_float(msg, 48); } /** @@ -517,7 +517,7 @@ static inline float mavlink_msg_image_available_get_pitch(const mavlink_message_ */ static inline float mavlink_msg_image_available_get_yaw(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 60); + return _MAV_RETURN_float(msg, 52); } /** @@ -527,7 +527,7 @@ static inline float mavlink_msg_image_available_get_yaw(const mavlink_message_t* */ static inline float mavlink_msg_image_available_get_local_z(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 64); + return _MAV_RETURN_float(msg, 56); } /** @@ -537,7 +537,7 @@ static inline float mavlink_msg_image_available_get_local_z(const mavlink_messag */ static inline float mavlink_msg_image_available_get_lat(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 68); + return _MAV_RETURN_float(msg, 60); } /** @@ -547,7 +547,7 @@ static inline float mavlink_msg_image_available_get_lat(const mavlink_message_t* */ static inline float mavlink_msg_image_available_get_lon(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 72); + return _MAV_RETURN_float(msg, 64); } /** @@ -557,7 +557,7 @@ static inline float mavlink_msg_image_available_get_lon(const mavlink_message_t* */ static inline float mavlink_msg_image_available_get_alt(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 76); + return _MAV_RETURN_float(msg, 68); } /** @@ -567,7 +567,7 @@ static inline float mavlink_msg_image_available_get_alt(const mavlink_message_t* */ static inline float mavlink_msg_image_available_get_ground_x(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 80); + return _MAV_RETURN_float(msg, 72); } /** @@ -577,7 +577,7 @@ static inline float mavlink_msg_image_available_get_ground_x(const mavlink_messa */ static inline float mavlink_msg_image_available_get_ground_y(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 84); + return _MAV_RETURN_float(msg, 76); } /** @@ -587,7 +587,7 @@ static inline float mavlink_msg_image_available_get_ground_y(const mavlink_messa */ static inline float mavlink_msg_image_available_get_ground_z(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 88); + return _MAV_RETURN_float(msg, 80); } /** @@ -600,15 +600,10 @@ static inline void mavlink_msg_image_available_decode(const mavlink_message_t* m { #if MAVLINK_NEED_BYTE_SWAP image_available->cam_id = mavlink_msg_image_available_get_cam_id(msg); - image_available->cam_no = mavlink_msg_image_available_get_cam_no(msg); image_available->timestamp = mavlink_msg_image_available_get_timestamp(msg); image_available->valid_until = mavlink_msg_image_available_get_valid_until(msg); image_available->img_seq = mavlink_msg_image_available_get_img_seq(msg); image_available->img_buf_index = mavlink_msg_image_available_get_img_buf_index(msg); - image_available->width = mavlink_msg_image_available_get_width(msg); - image_available->height = mavlink_msg_image_available_get_height(msg); - image_available->depth = mavlink_msg_image_available_get_depth(msg); - image_available->channels = mavlink_msg_image_available_get_channels(msg); image_available->key = mavlink_msg_image_available_get_key(msg); image_available->exposure = mavlink_msg_image_available_get_exposure(msg); image_available->gain = mavlink_msg_image_available_get_gain(msg); @@ -622,6 +617,11 @@ static inline void mavlink_msg_image_available_decode(const mavlink_message_t* m image_available->ground_x = mavlink_msg_image_available_get_ground_x(msg); image_available->ground_y = mavlink_msg_image_available_get_ground_y(msg); image_available->ground_z = mavlink_msg_image_available_get_ground_z(msg); + image_available->width = mavlink_msg_image_available_get_width(msg); + image_available->height = mavlink_msg_image_available_get_height(msg); + image_available->depth = mavlink_msg_image_available_get_depth(msg); + image_available->cam_no = mavlink_msg_image_available_get_cam_no(msg); + image_available->channels = mavlink_msg_image_available_get_channels(msg); #else memcpy(image_available, _MAV_PAYLOAD(msg), 92); #endif diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_image_trigger_control.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h similarity index 93% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_image_trigger_control.h rename to mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h index b381adac26c5ffa0bc433126b843148d444af600..deb05769a1e36ece25625a7a7b6876a8c332a865 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_image_trigger_control.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h @@ -36,16 +36,16 @@ static inline uint16_t mavlink_msg_image_trigger_control_pack(uint8_t system_id, char buf[1]; _mav_put_uint8_t(buf, 0, enable); - memcpy(_MAV_PAYLOAD(msg), buf, 1); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 1); #else mavlink_image_trigger_control_t packet; packet.enable = enable; - memcpy(_MAV_PAYLOAD(msg), &packet, 1); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 1); #endif msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL; - return mavlink_finalize_message(msg, system_id, component_id, 1); + return mavlink_finalize_message(msg, system_id, component_id, 1, 95); } /** @@ -65,16 +65,16 @@ static inline uint16_t mavlink_msg_image_trigger_control_pack_chan(uint8_t syste char buf[1]; _mav_put_uint8_t(buf, 0, enable); - memcpy(_MAV_PAYLOAD(msg), buf, 1); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 1); #else mavlink_image_trigger_control_t packet; packet.enable = enable; - memcpy(_MAV_PAYLOAD(msg), &packet, 1); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 1); #endif msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 1); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 1, 95); } /** @@ -104,12 +104,12 @@ static inline void mavlink_msg_image_trigger_control_send(mavlink_channel_t chan char buf[1]; _mav_put_uint8_t(buf, 0, enable); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, buf, 1); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, buf, 1, 95); #else mavlink_image_trigger_control_t packet; packet.enable = enable; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, (const char *)&packet, 1); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, (const char *)&packet, 1, 95); #endif } diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_image_triggered.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h similarity index 97% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_image_triggered.h rename to mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h index 485721fd707d57a838432e0f1157547ba17f3930..557d748e125500bde810e82dfa7f5dbfbb9e5b20 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_image_triggered.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h @@ -80,7 +80,7 @@ static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8 _mav_put_float(buf, 44, ground_y); _mav_put_float(buf, 48, ground_z); - memcpy(_MAV_PAYLOAD(msg), buf, 52); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 52); #else mavlink_image_triggered_t packet; packet.timestamp = timestamp; @@ -96,11 +96,11 @@ static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8 packet.ground_y = ground_y; packet.ground_z = ground_z; - memcpy(_MAV_PAYLOAD(msg), &packet, 52); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 52); #endif msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED; - return mavlink_finalize_message(msg, system_id, component_id, 52); + return mavlink_finalize_message(msg, system_id, component_id, 52, 86); } /** @@ -142,7 +142,7 @@ static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, _mav_put_float(buf, 44, ground_y); _mav_put_float(buf, 48, ground_z); - memcpy(_MAV_PAYLOAD(msg), buf, 52); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 52); #else mavlink_image_triggered_t packet; packet.timestamp = timestamp; @@ -158,11 +158,11 @@ static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, packet.ground_y = ground_y; packet.ground_z = ground_z; - memcpy(_MAV_PAYLOAD(msg), &packet, 52); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 52); #endif msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 52); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 52, 86); } /** @@ -214,7 +214,7 @@ static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint _mav_put_float(buf, 44, ground_y); _mav_put_float(buf, 48, ground_z); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, buf, 52); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, buf, 52, 86); #else mavlink_image_triggered_t packet; packet.timestamp = timestamp; @@ -230,7 +230,7 @@ static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint packet.ground_y = ground_y; packet.ground_z = ground_z; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, (const char *)&packet, 52); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, (const char *)&packet, 52, 86); #endif } diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_marker.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h similarity index 77% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_marker.h rename to mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h index 4ce4cba5be776c993d8ef868935edd62e3650da5..0c8cc6f18991c0c39cb3268a69642ca388b5d68a 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_marker.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h @@ -4,13 +4,13 @@ typedef struct __mavlink_marker_t { - uint16_t id; ///< ID float x; ///< x position float y; ///< y position float z; ///< z position float roll; ///< roll orientation float pitch; ///< pitch orientation float yaw; ///< yaw orientation + uint16_t id; ///< ID } mavlink_marker_t; #define MAVLINK_MSG_ID_MARKER_LEN 26 @@ -21,13 +21,13 @@ typedef struct __mavlink_marker_t #define MAVLINK_MESSAGE_INFO_MARKER { \ "MARKER", \ 7, \ - { { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_marker_t, id) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 2, offsetof(mavlink_marker_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_marker_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_marker_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_marker_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 18, offsetof(mavlink_marker_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 22, offsetof(mavlink_marker_t, yaw) }, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_marker_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_marker_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_marker_t, z) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_marker_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_marker_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_marker_t, yaw) }, \ + { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_marker_t, id) }, \ } \ } @@ -52,30 +52,30 @@ static inline uint16_t mavlink_msg_marker_pack(uint8_t system_id, uint8_t compon { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[26]; - _mav_put_uint16_t(buf, 0, id); - _mav_put_float(buf, 2, x); - _mav_put_float(buf, 6, y); - _mav_put_float(buf, 10, z); - _mav_put_float(buf, 14, roll); - _mav_put_float(buf, 18, pitch); - _mav_put_float(buf, 22, yaw); + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, roll); + _mav_put_float(buf, 16, pitch); + _mav_put_float(buf, 20, yaw); + _mav_put_uint16_t(buf, 24, id); - memcpy(_MAV_PAYLOAD(msg), buf, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); #else mavlink_marker_t packet; - packet.id = id; packet.x = x; packet.y = y; packet.z = z; packet.roll = roll; packet.pitch = pitch; packet.yaw = yaw; + packet.id = id; - memcpy(_MAV_PAYLOAD(msg), &packet, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); #endif msg->msgid = MAVLINK_MSG_ID_MARKER; - return mavlink_finalize_message(msg, system_id, component_id, 26); + return mavlink_finalize_message(msg, system_id, component_id, 26, 249); } /** @@ -99,30 +99,30 @@ static inline uint16_t mavlink_msg_marker_pack_chan(uint8_t system_id, uint8_t c { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[26]; - _mav_put_uint16_t(buf, 0, id); - _mav_put_float(buf, 2, x); - _mav_put_float(buf, 6, y); - _mav_put_float(buf, 10, z); - _mav_put_float(buf, 14, roll); - _mav_put_float(buf, 18, pitch); - _mav_put_float(buf, 22, yaw); + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, roll); + _mav_put_float(buf, 16, pitch); + _mav_put_float(buf, 20, yaw); + _mav_put_uint16_t(buf, 24, id); - memcpy(_MAV_PAYLOAD(msg), buf, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); #else mavlink_marker_t packet; - packet.id = id; packet.x = x; packet.y = y; packet.z = z; packet.roll = roll; packet.pitch = pitch; packet.yaw = yaw; + packet.id = id; - memcpy(_MAV_PAYLOAD(msg), &packet, 26); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); #endif msg->msgid = MAVLINK_MSG_ID_MARKER; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26, 249); } /** @@ -156,26 +156,26 @@ static inline void mavlink_msg_marker_send(mavlink_channel_t chan, uint16_t id, { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[26]; - _mav_put_uint16_t(buf, 0, id); - _mav_put_float(buf, 2, x); - _mav_put_float(buf, 6, y); - _mav_put_float(buf, 10, z); - _mav_put_float(buf, 14, roll); - _mav_put_float(buf, 18, pitch); - _mav_put_float(buf, 22, yaw); + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, roll); + _mav_put_float(buf, 16, pitch); + _mav_put_float(buf, 20, yaw); + _mav_put_uint16_t(buf, 24, id); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, buf, 26); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, buf, 26, 249); #else mavlink_marker_t packet; - packet.id = id; packet.x = x; packet.y = y; packet.z = z; packet.roll = roll; packet.pitch = pitch; packet.yaw = yaw; + packet.id = id; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, (const char *)&packet, 26); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, (const char *)&packet, 26, 249); #endif } @@ -191,7 +191,7 @@ static inline void mavlink_msg_marker_send(mavlink_channel_t chan, uint16_t id, */ static inline uint16_t mavlink_msg_marker_get_id(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 0); + return _MAV_RETURN_uint16_t(msg, 24); } /** @@ -201,7 +201,7 @@ static inline uint16_t mavlink_msg_marker_get_id(const mavlink_message_t* msg) */ static inline float mavlink_msg_marker_get_x(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 2); + return _MAV_RETURN_float(msg, 0); } /** @@ -211,7 +211,7 @@ static inline float mavlink_msg_marker_get_x(const mavlink_message_t* msg) */ static inline float mavlink_msg_marker_get_y(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 6); + return _MAV_RETURN_float(msg, 4); } /** @@ -221,7 +221,7 @@ static inline float mavlink_msg_marker_get_y(const mavlink_message_t* msg) */ static inline float mavlink_msg_marker_get_z(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 10); + return _MAV_RETURN_float(msg, 8); } /** @@ -231,7 +231,7 @@ static inline float mavlink_msg_marker_get_z(const mavlink_message_t* msg) */ static inline float mavlink_msg_marker_get_roll(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 14); + return _MAV_RETURN_float(msg, 12); } /** @@ -241,7 +241,7 @@ static inline float mavlink_msg_marker_get_roll(const mavlink_message_t* msg) */ static inline float mavlink_msg_marker_get_pitch(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 18); + return _MAV_RETURN_float(msg, 16); } /** @@ -251,7 +251,7 @@ static inline float mavlink_msg_marker_get_pitch(const mavlink_message_t* msg) */ static inline float mavlink_msg_marker_get_yaw(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 22); + return _MAV_RETURN_float(msg, 20); } /** @@ -263,13 +263,13 @@ static inline float mavlink_msg_marker_get_yaw(const mavlink_message_t* msg) static inline void mavlink_msg_marker_decode(const mavlink_message_t* msg, mavlink_marker_t* marker) { #if MAVLINK_NEED_BYTE_SWAP - marker->id = mavlink_msg_marker_get_id(msg); marker->x = mavlink_msg_marker_get_x(msg); marker->y = mavlink_msg_marker_get_y(msg); marker->z = mavlink_msg_marker_get_z(msg); marker->roll = mavlink_msg_marker_get_roll(msg); marker->pitch = mavlink_msg_marker_get_pitch(msg); marker->yaw = mavlink_msg_marker_get_yaw(msg); + marker->id = mavlink_msg_marker_get_id(msg); #else memcpy(marker, _MAV_PAYLOAD(msg), 26); #endif diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_pattern_detected.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h similarity index 88% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_pattern_detected.h rename to mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h index ec9c098fd6a3c3d8e8426c0473d86eb501bb8bf3..907246b207478ed5a8843aebb0b4de904b8152f9 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_pattern_detected.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h @@ -4,8 +4,8 @@ typedef struct __mavlink_pattern_detected_t { - uint8_t type; ///< 0: Pattern, 1: Letter float confidence; ///< Confidence of detection + uint8_t type; ///< 0: Pattern, 1: Letter char file[100]; ///< Pattern file name uint8_t detected; ///< Accepted as true detection, 0 no, 1 yes } mavlink_pattern_detected_t; @@ -18,8 +18,8 @@ typedef struct __mavlink_pattern_detected_t #define MAVLINK_MESSAGE_INFO_PATTERN_DETECTED { \ "PATTERN_DETECTED", \ 4, \ - { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_pattern_detected_t, type) }, \ - { "confidence", NULL, MAVLINK_TYPE_FLOAT, 0, 1, offsetof(mavlink_pattern_detected_t, confidence) }, \ + { { "confidence", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_pattern_detected_t, confidence) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_pattern_detected_t, type) }, \ { "file", NULL, MAVLINK_TYPE_CHAR, 100, 5, offsetof(mavlink_pattern_detected_t, file) }, \ { "detected", NULL, MAVLINK_TYPE_UINT8_T, 0, 105, offsetof(mavlink_pattern_detected_t, detected) }, \ } \ @@ -43,22 +43,22 @@ static inline uint16_t mavlink_msg_pattern_detected_pack(uint8_t system_id, uint { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[106]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_float(buf, 1, confidence); + _mav_put_float(buf, 0, confidence); + _mav_put_uint8_t(buf, 4, type); _mav_put_uint8_t(buf, 105, detected); _mav_put_char_array(buf, 5, file, 100); - memcpy(_MAV_PAYLOAD(msg), buf, 106); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 106); #else mavlink_pattern_detected_t packet; - packet.type = type; packet.confidence = confidence; + packet.type = type; packet.detected = detected; mav_array_memcpy(packet.file, file, sizeof(char)*100); - memcpy(_MAV_PAYLOAD(msg), &packet, 106); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 106); #endif msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED; - return mavlink_finalize_message(msg, system_id, component_id, 106); + return mavlink_finalize_message(msg, system_id, component_id, 106, 90); } /** @@ -79,22 +79,22 @@ static inline uint16_t mavlink_msg_pattern_detected_pack_chan(uint8_t system_id, { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[106]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_float(buf, 1, confidence); + _mav_put_float(buf, 0, confidence); + _mav_put_uint8_t(buf, 4, type); _mav_put_uint8_t(buf, 105, detected); _mav_put_char_array(buf, 5, file, 100); - memcpy(_MAV_PAYLOAD(msg), buf, 106); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 106); #else mavlink_pattern_detected_t packet; - packet.type = type; packet.confidence = confidence; + packet.type = type; packet.detected = detected; mav_array_memcpy(packet.file, file, sizeof(char)*100); - memcpy(_MAV_PAYLOAD(msg), &packet, 106); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 106); #endif msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 106); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 106, 90); } /** @@ -125,18 +125,18 @@ static inline void mavlink_msg_pattern_detected_send(mavlink_channel_t chan, uin { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[106]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_float(buf, 1, confidence); + _mav_put_float(buf, 0, confidence); + _mav_put_uint8_t(buf, 4, type); _mav_put_uint8_t(buf, 105, detected); _mav_put_char_array(buf, 5, file, 100); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, buf, 106); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, buf, 106, 90); #else mavlink_pattern_detected_t packet; - packet.type = type; packet.confidence = confidence; + packet.type = type; packet.detected = detected; mav_array_memcpy(packet.file, file, sizeof(char)*100); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, (const char *)&packet, 106); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, (const char *)&packet, 106, 90); #endif } @@ -152,7 +152,7 @@ static inline void mavlink_msg_pattern_detected_send(mavlink_channel_t chan, uin */ static inline uint8_t mavlink_msg_pattern_detected_get_type(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 0); + return _MAV_RETURN_uint8_t(msg, 4); } /** @@ -162,7 +162,7 @@ static inline uint8_t mavlink_msg_pattern_detected_get_type(const mavlink_messag */ static inline float mavlink_msg_pattern_detected_get_confidence(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 1); + return _MAV_RETURN_float(msg, 0); } /** @@ -194,8 +194,8 @@ static inline uint8_t mavlink_msg_pattern_detected_get_detected(const mavlink_me static inline void mavlink_msg_pattern_detected_decode(const mavlink_message_t* msg, mavlink_pattern_detected_t* pattern_detected) { #if MAVLINK_NEED_BYTE_SWAP - pattern_detected->type = mavlink_msg_pattern_detected_get_type(msg); pattern_detected->confidence = mavlink_msg_pattern_detected_get_confidence(msg); + pattern_detected->type = mavlink_msg_pattern_detected_get_type(msg); mavlink_msg_pattern_detected_get_file(msg, pattern_detected->file); pattern_detected->detected = mavlink_msg_pattern_detected_get_detected(msg); #else diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_point_of_interest.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h similarity index 81% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_point_of_interest.h rename to mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h index 543f93d109c02a9721bd5ddddce20bb89146ec6c..eec8d40691ca9d90915a6e3e972dd0ccf5ac429d 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_point_of_interest.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h @@ -4,13 +4,13 @@ typedef struct __mavlink_point_of_interest_t { - uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug - uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta - uint8_t coordinate_system; ///< 0: global, 1:local - uint16_t timeout; ///< 0: no timeout, >1: timeout in seconds float x; ///< X Position float y; ///< Y Position float z; ///< Z Position + uint16_t timeout; ///< 0: no timeout, >1: timeout in seconds + uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + uint8_t coordinate_system; ///< 0: global, 1:local char name[26]; ///< POI name } mavlink_point_of_interest_t; @@ -22,13 +22,13 @@ typedef struct __mavlink_point_of_interest_t #define MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST { \ "POINT_OF_INTEREST", \ 8, \ - { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_point_of_interest_t, type) }, \ - { "color", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_point_of_interest_t, color) }, \ - { "coordinate_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_point_of_interest_t, coordinate_system) }, \ - { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 3, offsetof(mavlink_point_of_interest_t, timeout) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 5, offsetof(mavlink_point_of_interest_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_point_of_interest_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 13, offsetof(mavlink_point_of_interest_t, z) }, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_point_of_interest_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_point_of_interest_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_point_of_interest_t, z) }, \ + { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_point_of_interest_t, timeout) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_point_of_interest_t, type) }, \ + { "color", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_point_of_interest_t, color) }, \ + { "coordinate_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_point_of_interest_t, coordinate_system) }, \ { "name", NULL, MAVLINK_TYPE_CHAR, 26, 17, offsetof(mavlink_point_of_interest_t, name) }, \ } \ } @@ -55,30 +55,30 @@ static inline uint16_t mavlink_msg_point_of_interest_pack(uint8_t system_id, uin { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[43]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, color); - _mav_put_uint8_t(buf, 2, coordinate_system); - _mav_put_uint16_t(buf, 3, timeout); - _mav_put_float(buf, 5, x); - _mav_put_float(buf, 9, y); - _mav_put_float(buf, 13, z); + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_uint16_t(buf, 12, timeout); + _mav_put_uint8_t(buf, 14, type); + _mav_put_uint8_t(buf, 15, color); + _mav_put_uint8_t(buf, 16, coordinate_system); _mav_put_char_array(buf, 17, name, 26); - memcpy(_MAV_PAYLOAD(msg), buf, 43); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 43); #else mavlink_point_of_interest_t packet; - packet.type = type; - packet.color = color; - packet.coordinate_system = coordinate_system; - packet.timeout = timeout; packet.x = x; packet.y = y; packet.z = z; + packet.timeout = timeout; + packet.type = type; + packet.color = color; + packet.coordinate_system = coordinate_system; mav_array_memcpy(packet.name, name, sizeof(char)*26); - memcpy(_MAV_PAYLOAD(msg), &packet, 43); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 43); #endif msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST; - return mavlink_finalize_message(msg, system_id, component_id, 43); + return mavlink_finalize_message(msg, system_id, component_id, 43, 95); } /** @@ -103,30 +103,30 @@ static inline uint16_t mavlink_msg_point_of_interest_pack_chan(uint8_t system_id { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[43]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, color); - _mav_put_uint8_t(buf, 2, coordinate_system); - _mav_put_uint16_t(buf, 3, timeout); - _mav_put_float(buf, 5, x); - _mav_put_float(buf, 9, y); - _mav_put_float(buf, 13, z); + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_uint16_t(buf, 12, timeout); + _mav_put_uint8_t(buf, 14, type); + _mav_put_uint8_t(buf, 15, color); + _mav_put_uint8_t(buf, 16, coordinate_system); _mav_put_char_array(buf, 17, name, 26); - memcpy(_MAV_PAYLOAD(msg), buf, 43); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 43); #else mavlink_point_of_interest_t packet; - packet.type = type; - packet.color = color; - packet.coordinate_system = coordinate_system; - packet.timeout = timeout; packet.x = x; packet.y = y; packet.z = z; + packet.timeout = timeout; + packet.type = type; + packet.color = color; + packet.coordinate_system = coordinate_system; mav_array_memcpy(packet.name, name, sizeof(char)*26); - memcpy(_MAV_PAYLOAD(msg), &packet, 43); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 43); #endif msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 43); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 43, 95); } /** @@ -161,26 +161,26 @@ static inline void mavlink_msg_point_of_interest_send(mavlink_channel_t chan, ui { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[43]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, color); - _mav_put_uint8_t(buf, 2, coordinate_system); - _mav_put_uint16_t(buf, 3, timeout); - _mav_put_float(buf, 5, x); - _mav_put_float(buf, 9, y); - _mav_put_float(buf, 13, z); + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_uint16_t(buf, 12, timeout); + _mav_put_uint8_t(buf, 14, type); + _mav_put_uint8_t(buf, 15, color); + _mav_put_uint8_t(buf, 16, coordinate_system); _mav_put_char_array(buf, 17, name, 26); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, buf, 43); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, buf, 43, 95); #else mavlink_point_of_interest_t packet; - packet.type = type; - packet.color = color; - packet.coordinate_system = coordinate_system; - packet.timeout = timeout; packet.x = x; packet.y = y; packet.z = z; + packet.timeout = timeout; + packet.type = type; + packet.color = color; + packet.coordinate_system = coordinate_system; mav_array_memcpy(packet.name, name, sizeof(char)*26); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, (const char *)&packet, 43); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, (const char *)&packet, 43, 95); #endif } @@ -196,7 +196,7 @@ static inline void mavlink_msg_point_of_interest_send(mavlink_channel_t chan, ui */ static inline uint8_t mavlink_msg_point_of_interest_get_type(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 0); + return _MAV_RETURN_uint8_t(msg, 14); } /** @@ -206,7 +206,7 @@ static inline uint8_t mavlink_msg_point_of_interest_get_type(const mavlink_messa */ static inline uint8_t mavlink_msg_point_of_interest_get_color(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 1); + return _MAV_RETURN_uint8_t(msg, 15); } /** @@ -216,7 +216,7 @@ static inline uint8_t mavlink_msg_point_of_interest_get_color(const mavlink_mess */ static inline uint8_t mavlink_msg_point_of_interest_get_coordinate_system(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 2); + return _MAV_RETURN_uint8_t(msg, 16); } /** @@ -226,7 +226,7 @@ static inline uint8_t mavlink_msg_point_of_interest_get_coordinate_system(const */ static inline uint16_t mavlink_msg_point_of_interest_get_timeout(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 3); + return _MAV_RETURN_uint16_t(msg, 12); } /** @@ -236,7 +236,7 @@ static inline uint16_t mavlink_msg_point_of_interest_get_timeout(const mavlink_m */ static inline float mavlink_msg_point_of_interest_get_x(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 5); + return _MAV_RETURN_float(msg, 0); } /** @@ -246,7 +246,7 @@ static inline float mavlink_msg_point_of_interest_get_x(const mavlink_message_t* */ static inline float mavlink_msg_point_of_interest_get_y(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 9); + return _MAV_RETURN_float(msg, 4); } /** @@ -256,7 +256,7 @@ static inline float mavlink_msg_point_of_interest_get_y(const mavlink_message_t* */ static inline float mavlink_msg_point_of_interest_get_z(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 13); + return _MAV_RETURN_float(msg, 8); } /** @@ -278,13 +278,13 @@ static inline uint16_t mavlink_msg_point_of_interest_get_name(const mavlink_mess static inline void mavlink_msg_point_of_interest_decode(const mavlink_message_t* msg, mavlink_point_of_interest_t* point_of_interest) { #if MAVLINK_NEED_BYTE_SWAP - point_of_interest->type = mavlink_msg_point_of_interest_get_type(msg); - point_of_interest->color = mavlink_msg_point_of_interest_get_color(msg); - point_of_interest->coordinate_system = mavlink_msg_point_of_interest_get_coordinate_system(msg); - point_of_interest->timeout = mavlink_msg_point_of_interest_get_timeout(msg); point_of_interest->x = mavlink_msg_point_of_interest_get_x(msg); point_of_interest->y = mavlink_msg_point_of_interest_get_y(msg); point_of_interest->z = mavlink_msg_point_of_interest_get_z(msg); + point_of_interest->timeout = mavlink_msg_point_of_interest_get_timeout(msg); + point_of_interest->type = mavlink_msg_point_of_interest_get_type(msg); + point_of_interest->color = mavlink_msg_point_of_interest_get_color(msg); + point_of_interest->coordinate_system = mavlink_msg_point_of_interest_get_coordinate_system(msg); mavlink_msg_point_of_interest_get_name(msg, point_of_interest->name); #else memcpy(point_of_interest, _MAV_PAYLOAD(msg), 43); diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_point_of_interest_connection.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h similarity index 81% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_point_of_interest_connection.h rename to mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h index d9c70a138c11b8a36f2dcba31945f6eb71581653..f83630093ea1f6616addc000235c30146d738df7 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_point_of_interest_connection.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h @@ -4,16 +4,16 @@ typedef struct __mavlink_point_of_interest_connection_t { - uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug - uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta - uint8_t coordinate_system; ///< 0: global, 1:local - uint16_t timeout; ///< 0: no timeout, >1: timeout in seconds float xp1; ///< X1 Position float yp1; ///< Y1 Position float zp1; ///< Z1 Position float xp2; ///< X2 Position float yp2; ///< Y2 Position float zp2; ///< Z2 Position + uint16_t timeout; ///< 0: no timeout, >1: timeout in seconds + uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + uint8_t coordinate_system; ///< 0: global, 1:local char name[26]; ///< POI connection name } mavlink_point_of_interest_connection_t; @@ -25,16 +25,16 @@ typedef struct __mavlink_point_of_interest_connection_t #define MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST_CONNECTION { \ "POINT_OF_INTEREST_CONNECTION", \ 11, \ - { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_point_of_interest_connection_t, type) }, \ - { "color", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_point_of_interest_connection_t, color) }, \ - { "coordinate_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_point_of_interest_connection_t, coordinate_system) }, \ - { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 3, offsetof(mavlink_point_of_interest_connection_t, timeout) }, \ - { "xp1", NULL, MAVLINK_TYPE_FLOAT, 0, 5, offsetof(mavlink_point_of_interest_connection_t, xp1) }, \ - { "yp1", NULL, MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_point_of_interest_connection_t, yp1) }, \ - { "zp1", NULL, MAVLINK_TYPE_FLOAT, 0, 13, offsetof(mavlink_point_of_interest_connection_t, zp1) }, \ - { "xp2", NULL, MAVLINK_TYPE_FLOAT, 0, 17, offsetof(mavlink_point_of_interest_connection_t, xp2) }, \ - { "yp2", NULL, MAVLINK_TYPE_FLOAT, 0, 21, offsetof(mavlink_point_of_interest_connection_t, yp2) }, \ - { "zp2", NULL, MAVLINK_TYPE_FLOAT, 0, 25, offsetof(mavlink_point_of_interest_connection_t, zp2) }, \ + { { "xp1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_point_of_interest_connection_t, xp1) }, \ + { "yp1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_point_of_interest_connection_t, yp1) }, \ + { "zp1", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_point_of_interest_connection_t, zp1) }, \ + { "xp2", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_point_of_interest_connection_t, xp2) }, \ + { "yp2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_point_of_interest_connection_t, yp2) }, \ + { "zp2", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_point_of_interest_connection_t, zp2) }, \ + { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_point_of_interest_connection_t, timeout) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_point_of_interest_connection_t, type) }, \ + { "color", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_point_of_interest_connection_t, color) }, \ + { "coordinate_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_point_of_interest_connection_t, coordinate_system) }, \ { "name", NULL, MAVLINK_TYPE_CHAR, 26, 29, offsetof(mavlink_point_of_interest_connection_t, name) }, \ } \ } @@ -64,36 +64,36 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_pack(uint8_t sys { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[55]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, color); - _mav_put_uint8_t(buf, 2, coordinate_system); - _mav_put_uint16_t(buf, 3, timeout); - _mav_put_float(buf, 5, xp1); - _mav_put_float(buf, 9, yp1); - _mav_put_float(buf, 13, zp1); - _mav_put_float(buf, 17, xp2); - _mav_put_float(buf, 21, yp2); - _mav_put_float(buf, 25, zp2); + _mav_put_float(buf, 0, xp1); + _mav_put_float(buf, 4, yp1); + _mav_put_float(buf, 8, zp1); + _mav_put_float(buf, 12, xp2); + _mav_put_float(buf, 16, yp2); + _mav_put_float(buf, 20, zp2); + _mav_put_uint16_t(buf, 24, timeout); + _mav_put_uint8_t(buf, 26, type); + _mav_put_uint8_t(buf, 27, color); + _mav_put_uint8_t(buf, 28, coordinate_system); _mav_put_char_array(buf, 29, name, 26); - memcpy(_MAV_PAYLOAD(msg), buf, 55); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 55); #else mavlink_point_of_interest_connection_t packet; - packet.type = type; - packet.color = color; - packet.coordinate_system = coordinate_system; - packet.timeout = timeout; packet.xp1 = xp1; packet.yp1 = yp1; packet.zp1 = zp1; packet.xp2 = xp2; packet.yp2 = yp2; packet.zp2 = zp2; + packet.timeout = timeout; + packet.type = type; + packet.color = color; + packet.coordinate_system = coordinate_system; mav_array_memcpy(packet.name, name, sizeof(char)*26); - memcpy(_MAV_PAYLOAD(msg), &packet, 55); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 55); #endif msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION; - return mavlink_finalize_message(msg, system_id, component_id, 55); + return mavlink_finalize_message(msg, system_id, component_id, 55, 36); } /** @@ -121,36 +121,36 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_pack_chan(uint8_ { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[55]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, color); - _mav_put_uint8_t(buf, 2, coordinate_system); - _mav_put_uint16_t(buf, 3, timeout); - _mav_put_float(buf, 5, xp1); - _mav_put_float(buf, 9, yp1); - _mav_put_float(buf, 13, zp1); - _mav_put_float(buf, 17, xp2); - _mav_put_float(buf, 21, yp2); - _mav_put_float(buf, 25, zp2); + _mav_put_float(buf, 0, xp1); + _mav_put_float(buf, 4, yp1); + _mav_put_float(buf, 8, zp1); + _mav_put_float(buf, 12, xp2); + _mav_put_float(buf, 16, yp2); + _mav_put_float(buf, 20, zp2); + _mav_put_uint16_t(buf, 24, timeout); + _mav_put_uint8_t(buf, 26, type); + _mav_put_uint8_t(buf, 27, color); + _mav_put_uint8_t(buf, 28, coordinate_system); _mav_put_char_array(buf, 29, name, 26); - memcpy(_MAV_PAYLOAD(msg), buf, 55); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 55); #else mavlink_point_of_interest_connection_t packet; - packet.type = type; - packet.color = color; - packet.coordinate_system = coordinate_system; - packet.timeout = timeout; packet.xp1 = xp1; packet.yp1 = yp1; packet.zp1 = zp1; packet.xp2 = xp2; packet.yp2 = yp2; packet.zp2 = zp2; + packet.timeout = timeout; + packet.type = type; + packet.color = color; + packet.coordinate_system = coordinate_system; mav_array_memcpy(packet.name, name, sizeof(char)*26); - memcpy(_MAV_PAYLOAD(msg), &packet, 55); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 55); #endif msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 55); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 55, 36); } /** @@ -188,32 +188,32 @@ static inline void mavlink_msg_point_of_interest_connection_send(mavlink_channel { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[55]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, color); - _mav_put_uint8_t(buf, 2, coordinate_system); - _mav_put_uint16_t(buf, 3, timeout); - _mav_put_float(buf, 5, xp1); - _mav_put_float(buf, 9, yp1); - _mav_put_float(buf, 13, zp1); - _mav_put_float(buf, 17, xp2); - _mav_put_float(buf, 21, yp2); - _mav_put_float(buf, 25, zp2); + _mav_put_float(buf, 0, xp1); + _mav_put_float(buf, 4, yp1); + _mav_put_float(buf, 8, zp1); + _mav_put_float(buf, 12, xp2); + _mav_put_float(buf, 16, yp2); + _mav_put_float(buf, 20, zp2); + _mav_put_uint16_t(buf, 24, timeout); + _mav_put_uint8_t(buf, 26, type); + _mav_put_uint8_t(buf, 27, color); + _mav_put_uint8_t(buf, 28, coordinate_system); _mav_put_char_array(buf, 29, name, 26); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, buf, 55); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, buf, 55, 36); #else mavlink_point_of_interest_connection_t packet; - packet.type = type; - packet.color = color; - packet.coordinate_system = coordinate_system; - packet.timeout = timeout; packet.xp1 = xp1; packet.yp1 = yp1; packet.zp1 = zp1; packet.xp2 = xp2; packet.yp2 = yp2; packet.zp2 = zp2; + packet.timeout = timeout; + packet.type = type; + packet.color = color; + packet.coordinate_system = coordinate_system; mav_array_memcpy(packet.name, name, sizeof(char)*26); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, (const char *)&packet, 55); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, (const char *)&packet, 55, 36); #endif } @@ -229,7 +229,7 @@ static inline void mavlink_msg_point_of_interest_connection_send(mavlink_channel */ static inline uint8_t mavlink_msg_point_of_interest_connection_get_type(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 0); + return _MAV_RETURN_uint8_t(msg, 26); } /** @@ -239,7 +239,7 @@ static inline uint8_t mavlink_msg_point_of_interest_connection_get_type(const ma */ static inline uint8_t mavlink_msg_point_of_interest_connection_get_color(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 1); + return _MAV_RETURN_uint8_t(msg, 27); } /** @@ -249,7 +249,7 @@ static inline uint8_t mavlink_msg_point_of_interest_connection_get_color(const m */ static inline uint8_t mavlink_msg_point_of_interest_connection_get_coordinate_system(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 2); + return _MAV_RETURN_uint8_t(msg, 28); } /** @@ -259,7 +259,7 @@ static inline uint8_t mavlink_msg_point_of_interest_connection_get_coordinate_sy */ static inline uint16_t mavlink_msg_point_of_interest_connection_get_timeout(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 3); + return _MAV_RETURN_uint16_t(msg, 24); } /** @@ -269,7 +269,7 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_get_timeout(cons */ static inline float mavlink_msg_point_of_interest_connection_get_xp1(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 5); + return _MAV_RETURN_float(msg, 0); } /** @@ -279,7 +279,7 @@ static inline float mavlink_msg_point_of_interest_connection_get_xp1(const mavli */ static inline float mavlink_msg_point_of_interest_connection_get_yp1(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 9); + return _MAV_RETURN_float(msg, 4); } /** @@ -289,7 +289,7 @@ static inline float mavlink_msg_point_of_interest_connection_get_yp1(const mavli */ static inline float mavlink_msg_point_of_interest_connection_get_zp1(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 13); + return _MAV_RETURN_float(msg, 8); } /** @@ -299,7 +299,7 @@ static inline float mavlink_msg_point_of_interest_connection_get_zp1(const mavli */ static inline float mavlink_msg_point_of_interest_connection_get_xp2(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 17); + return _MAV_RETURN_float(msg, 12); } /** @@ -309,7 +309,7 @@ static inline float mavlink_msg_point_of_interest_connection_get_xp2(const mavli */ static inline float mavlink_msg_point_of_interest_connection_get_yp2(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 21); + return _MAV_RETURN_float(msg, 16); } /** @@ -319,7 +319,7 @@ static inline float mavlink_msg_point_of_interest_connection_get_yp2(const mavli */ static inline float mavlink_msg_point_of_interest_connection_get_zp2(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 25); + return _MAV_RETURN_float(msg, 20); } /** @@ -341,16 +341,16 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_get_name(const m static inline void mavlink_msg_point_of_interest_connection_decode(const mavlink_message_t* msg, mavlink_point_of_interest_connection_t* point_of_interest_connection) { #if MAVLINK_NEED_BYTE_SWAP - point_of_interest_connection->type = mavlink_msg_point_of_interest_connection_get_type(msg); - point_of_interest_connection->color = mavlink_msg_point_of_interest_connection_get_color(msg); - point_of_interest_connection->coordinate_system = mavlink_msg_point_of_interest_connection_get_coordinate_system(msg); - point_of_interest_connection->timeout = mavlink_msg_point_of_interest_connection_get_timeout(msg); point_of_interest_connection->xp1 = mavlink_msg_point_of_interest_connection_get_xp1(msg); point_of_interest_connection->yp1 = mavlink_msg_point_of_interest_connection_get_yp1(msg); point_of_interest_connection->zp1 = mavlink_msg_point_of_interest_connection_get_zp1(msg); point_of_interest_connection->xp2 = mavlink_msg_point_of_interest_connection_get_xp2(msg); point_of_interest_connection->yp2 = mavlink_msg_point_of_interest_connection_get_yp2(msg); point_of_interest_connection->zp2 = mavlink_msg_point_of_interest_connection_get_zp2(msg); + point_of_interest_connection->timeout = mavlink_msg_point_of_interest_connection_get_timeout(msg); + point_of_interest_connection->type = mavlink_msg_point_of_interest_connection_get_type(msg); + point_of_interest_connection->color = mavlink_msg_point_of_interest_connection_get_color(msg); + point_of_interest_connection->coordinate_system = mavlink_msg_point_of_interest_connection_get_coordinate_system(msg); mavlink_msg_point_of_interest_connection_get_name(msg, point_of_interest_connection->name); #else memcpy(point_of_interest_connection, _MAV_PAYLOAD(msg), 55); diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_position_control_setpoint.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h similarity index 81% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_position_control_setpoint.h rename to mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h index 154805205829aac34b33cff5558c410f64312e78..495fb884cf1346995e17455155d6b5e13961f768 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_position_control_setpoint.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h @@ -4,11 +4,11 @@ typedef struct __mavlink_position_control_setpoint_t { - uint16_t id; ///< ID of waypoint, 0 for plain position float x; ///< x position float y; ///< y position float z; ///< z position float yaw; ///< yaw orientation in radians, 0 = NORTH + uint16_t id; ///< ID of waypoint, 0 for plain position } mavlink_position_control_setpoint_t; #define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN 18 @@ -19,11 +19,11 @@ typedef struct __mavlink_position_control_setpoint_t #define MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT { \ "POSITION_CONTROL_SETPOINT", \ 5, \ - { { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_position_control_setpoint_t, id) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 2, offsetof(mavlink_position_control_setpoint_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_position_control_setpoint_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_position_control_setpoint_t, z) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_position_control_setpoint_t, yaw) }, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_position_control_setpoint_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_control_setpoint_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_control_setpoint_t, z) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_control_setpoint_t, yaw) }, \ + { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_position_control_setpoint_t, id) }, \ } \ } @@ -46,26 +46,26 @@ static inline uint16_t mavlink_msg_position_control_setpoint_pack(uint8_t system { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[18]; - _mav_put_uint16_t(buf, 0, id); - _mav_put_float(buf, 2, x); - _mav_put_float(buf, 6, y); - _mav_put_float(buf, 10, z); - _mav_put_float(buf, 14, yaw); + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint16_t(buf, 16, id); - memcpy(_MAV_PAYLOAD(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); #else mavlink_position_control_setpoint_t packet; - packet.id = id; packet.x = x; packet.y = y; packet.z = z; packet.yaw = yaw; + packet.id = id; - memcpy(_MAV_PAYLOAD(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); #endif msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT; - return mavlink_finalize_message(msg, system_id, component_id, 18); + return mavlink_finalize_message(msg, system_id, component_id, 18, 28); } /** @@ -87,26 +87,26 @@ static inline uint16_t mavlink_msg_position_control_setpoint_pack_chan(uint8_t s { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[18]; - _mav_put_uint16_t(buf, 0, id); - _mav_put_float(buf, 2, x); - _mav_put_float(buf, 6, y); - _mav_put_float(buf, 10, z); - _mav_put_float(buf, 14, yaw); + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint16_t(buf, 16, id); - memcpy(_MAV_PAYLOAD(msg), buf, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); #else mavlink_position_control_setpoint_t packet; - packet.id = id; packet.x = x; packet.y = y; packet.z = z; packet.yaw = yaw; + packet.id = id; - memcpy(_MAV_PAYLOAD(msg), &packet, 18); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); #endif msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 28); } /** @@ -138,22 +138,22 @@ static inline void mavlink_msg_position_control_setpoint_send(mavlink_channel_t { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[18]; - _mav_put_uint16_t(buf, 0, id); - _mav_put_float(buf, 2, x); - _mav_put_float(buf, 6, y); - _mav_put_float(buf, 10, z); - _mav_put_float(buf, 14, yaw); + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint16_t(buf, 16, id); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, buf, 18); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, buf, 18, 28); #else mavlink_position_control_setpoint_t packet; - packet.id = id; packet.x = x; packet.y = y; packet.z = z; packet.yaw = yaw; + packet.id = id; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, (const char *)&packet, 18); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, (const char *)&packet, 18, 28); #endif } @@ -169,7 +169,7 @@ static inline void mavlink_msg_position_control_setpoint_send(mavlink_channel_t */ static inline uint16_t mavlink_msg_position_control_setpoint_get_id(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 0); + return _MAV_RETURN_uint16_t(msg, 16); } /** @@ -179,7 +179,7 @@ static inline uint16_t mavlink_msg_position_control_setpoint_get_id(const mavlin */ static inline float mavlink_msg_position_control_setpoint_get_x(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 2); + return _MAV_RETURN_float(msg, 0); } /** @@ -189,7 +189,7 @@ static inline float mavlink_msg_position_control_setpoint_get_x(const mavlink_me */ static inline float mavlink_msg_position_control_setpoint_get_y(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 6); + return _MAV_RETURN_float(msg, 4); } /** @@ -199,7 +199,7 @@ static inline float mavlink_msg_position_control_setpoint_get_y(const mavlink_me */ static inline float mavlink_msg_position_control_setpoint_get_z(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 10); + return _MAV_RETURN_float(msg, 8); } /** @@ -209,7 +209,7 @@ static inline float mavlink_msg_position_control_setpoint_get_z(const mavlink_me */ static inline float mavlink_msg_position_control_setpoint_get_yaw(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 14); + return _MAV_RETURN_float(msg, 12); } /** @@ -221,11 +221,11 @@ static inline float mavlink_msg_position_control_setpoint_get_yaw(const mavlink_ static inline void mavlink_msg_position_control_setpoint_decode(const mavlink_message_t* msg, mavlink_position_control_setpoint_t* position_control_setpoint) { #if MAVLINK_NEED_BYTE_SWAP - position_control_setpoint->id = mavlink_msg_position_control_setpoint_get_id(msg); position_control_setpoint->x = mavlink_msg_position_control_setpoint_get_x(msg); position_control_setpoint->y = mavlink_msg_position_control_setpoint_get_y(msg); position_control_setpoint->z = mavlink_msg_position_control_setpoint_get_z(msg); position_control_setpoint->yaw = mavlink_msg_position_control_setpoint_get_yaw(msg); + position_control_setpoint->id = mavlink_msg_position_control_setpoint_get_id(msg); #else memcpy(position_control_setpoint, _MAV_PAYLOAD(msg), 18); #endif diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_raw_aux.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h similarity index 80% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_raw_aux.h rename to mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h index dad8126b67c8691ec26f5afb826f4667fa98a340..507e0f2f9bb49659758be951f8ba066b4c9c6826 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_raw_aux.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h @@ -4,13 +4,13 @@ typedef struct __mavlink_raw_aux_t { + int32_t baro; ///< Barometric pressure (hecto Pascal) uint16_t adc1; ///< ADC1 (J405 ADC3, LPC2148 AD0.6) uint16_t adc2; ///< ADC2 (J405 ADC5, LPC2148 AD0.2) uint16_t adc3; ///< ADC3 (J405 ADC6, LPC2148 AD0.1) uint16_t adc4; ///< ADC4 (J405 ADC7, LPC2148 AD1.3) uint16_t vbat; ///< Battery voltage int16_t temp; ///< Temperature (degrees celcius) - int32_t baro; ///< Barometric pressure (hecto Pascal) } mavlink_raw_aux_t; #define MAVLINK_MSG_ID_RAW_AUX_LEN 16 @@ -21,13 +21,13 @@ typedef struct __mavlink_raw_aux_t #define MAVLINK_MESSAGE_INFO_RAW_AUX { \ "RAW_AUX", \ 7, \ - { { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_raw_aux_t, adc1) }, \ - { "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_raw_aux_t, adc2) }, \ - { "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_raw_aux_t, adc3) }, \ - { "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_raw_aux_t, adc4) }, \ - { "vbat", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_raw_aux_t, vbat) }, \ - { "temp", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_aux_t, temp) }, \ - { "baro", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_raw_aux_t, baro) }, \ + { { "baro", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_raw_aux_t, baro) }, \ + { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_raw_aux_t, adc1) }, \ + { "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_raw_aux_t, adc2) }, \ + { "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_raw_aux_t, adc3) }, \ + { "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_raw_aux_t, adc4) }, \ + { "vbat", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_raw_aux_t, vbat) }, \ + { "temp", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_aux_t, temp) }, \ } \ } @@ -52,30 +52,30 @@ static inline uint16_t mavlink_msg_raw_aux_pack(uint8_t system_id, uint8_t compo { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[16]; - _mav_put_uint16_t(buf, 0, adc1); - _mav_put_uint16_t(buf, 2, adc2); - _mav_put_uint16_t(buf, 4, adc3); - _mav_put_uint16_t(buf, 6, adc4); - _mav_put_uint16_t(buf, 8, vbat); - _mav_put_int16_t(buf, 10, temp); - _mav_put_int32_t(buf, 12, baro); + _mav_put_int32_t(buf, 0, baro); + _mav_put_uint16_t(buf, 4, adc1); + _mav_put_uint16_t(buf, 6, adc2); + _mav_put_uint16_t(buf, 8, adc3); + _mav_put_uint16_t(buf, 10, adc4); + _mav_put_uint16_t(buf, 12, vbat); + _mav_put_int16_t(buf, 14, temp); - memcpy(_MAV_PAYLOAD(msg), buf, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); #else mavlink_raw_aux_t packet; + packet.baro = baro; packet.adc1 = adc1; packet.adc2 = adc2; packet.adc3 = adc3; packet.adc4 = adc4; packet.vbat = vbat; packet.temp = temp; - packet.baro = baro; - memcpy(_MAV_PAYLOAD(msg), &packet, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); #endif msg->msgid = MAVLINK_MSG_ID_RAW_AUX; - return mavlink_finalize_message(msg, system_id, component_id, 16); + return mavlink_finalize_message(msg, system_id, component_id, 16, 182); } /** @@ -99,30 +99,30 @@ static inline uint16_t mavlink_msg_raw_aux_pack_chan(uint8_t system_id, uint8_t { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[16]; - _mav_put_uint16_t(buf, 0, adc1); - _mav_put_uint16_t(buf, 2, adc2); - _mav_put_uint16_t(buf, 4, adc3); - _mav_put_uint16_t(buf, 6, adc4); - _mav_put_uint16_t(buf, 8, vbat); - _mav_put_int16_t(buf, 10, temp); - _mav_put_int32_t(buf, 12, baro); + _mav_put_int32_t(buf, 0, baro); + _mav_put_uint16_t(buf, 4, adc1); + _mav_put_uint16_t(buf, 6, adc2); + _mav_put_uint16_t(buf, 8, adc3); + _mav_put_uint16_t(buf, 10, adc4); + _mav_put_uint16_t(buf, 12, vbat); + _mav_put_int16_t(buf, 14, temp); - memcpy(_MAV_PAYLOAD(msg), buf, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); #else mavlink_raw_aux_t packet; + packet.baro = baro; packet.adc1 = adc1; packet.adc2 = adc2; packet.adc3 = adc3; packet.adc4 = adc4; packet.vbat = vbat; packet.temp = temp; - packet.baro = baro; - memcpy(_MAV_PAYLOAD(msg), &packet, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); #endif msg->msgid = MAVLINK_MSG_ID_RAW_AUX; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16, 182); } /** @@ -156,26 +156,26 @@ static inline void mavlink_msg_raw_aux_send(mavlink_channel_t chan, uint16_t adc { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[16]; - _mav_put_uint16_t(buf, 0, adc1); - _mav_put_uint16_t(buf, 2, adc2); - _mav_put_uint16_t(buf, 4, adc3); - _mav_put_uint16_t(buf, 6, adc4); - _mav_put_uint16_t(buf, 8, vbat); - _mav_put_int16_t(buf, 10, temp); - _mav_put_int32_t(buf, 12, baro); + _mav_put_int32_t(buf, 0, baro); + _mav_put_uint16_t(buf, 4, adc1); + _mav_put_uint16_t(buf, 6, adc2); + _mav_put_uint16_t(buf, 8, adc3); + _mav_put_uint16_t(buf, 10, adc4); + _mav_put_uint16_t(buf, 12, vbat); + _mav_put_int16_t(buf, 14, temp); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, buf, 16); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, buf, 16, 182); #else mavlink_raw_aux_t packet; + packet.baro = baro; packet.adc1 = adc1; packet.adc2 = adc2; packet.adc3 = adc3; packet.adc4 = adc4; packet.vbat = vbat; packet.temp = temp; - packet.baro = baro; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, (const char *)&packet, 16); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, (const char *)&packet, 16, 182); #endif } @@ -191,7 +191,7 @@ static inline void mavlink_msg_raw_aux_send(mavlink_channel_t chan, uint16_t adc */ static inline uint16_t mavlink_msg_raw_aux_get_adc1(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 0); + return _MAV_RETURN_uint16_t(msg, 4); } /** @@ -201,7 +201,7 @@ static inline uint16_t mavlink_msg_raw_aux_get_adc1(const mavlink_message_t* msg */ static inline uint16_t mavlink_msg_raw_aux_get_adc2(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 2); + return _MAV_RETURN_uint16_t(msg, 6); } /** @@ -211,7 +211,7 @@ static inline uint16_t mavlink_msg_raw_aux_get_adc2(const mavlink_message_t* msg */ static inline uint16_t mavlink_msg_raw_aux_get_adc3(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 4); + return _MAV_RETURN_uint16_t(msg, 8); } /** @@ -221,7 +221,7 @@ static inline uint16_t mavlink_msg_raw_aux_get_adc3(const mavlink_message_t* msg */ static inline uint16_t mavlink_msg_raw_aux_get_adc4(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 6); + return _MAV_RETURN_uint16_t(msg, 10); } /** @@ -231,7 +231,7 @@ static inline uint16_t mavlink_msg_raw_aux_get_adc4(const mavlink_message_t* msg */ static inline uint16_t mavlink_msg_raw_aux_get_vbat(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 8); + return _MAV_RETURN_uint16_t(msg, 12); } /** @@ -241,7 +241,7 @@ static inline uint16_t mavlink_msg_raw_aux_get_vbat(const mavlink_message_t* msg */ static inline int16_t mavlink_msg_raw_aux_get_temp(const mavlink_message_t* msg) { - return _MAV_RETURN_int16_t(msg, 10); + return _MAV_RETURN_int16_t(msg, 14); } /** @@ -251,7 +251,7 @@ static inline int16_t mavlink_msg_raw_aux_get_temp(const mavlink_message_t* msg) */ static inline int32_t mavlink_msg_raw_aux_get_baro(const mavlink_message_t* msg) { - return _MAV_RETURN_int32_t(msg, 12); + return _MAV_RETURN_int32_t(msg, 0); } /** @@ -263,13 +263,13 @@ static inline int32_t mavlink_msg_raw_aux_get_baro(const mavlink_message_t* msg) static inline void mavlink_msg_raw_aux_decode(const mavlink_message_t* msg, mavlink_raw_aux_t* raw_aux) { #if MAVLINK_NEED_BYTE_SWAP + raw_aux->baro = mavlink_msg_raw_aux_get_baro(msg); raw_aux->adc1 = mavlink_msg_raw_aux_get_adc1(msg); raw_aux->adc2 = mavlink_msg_raw_aux_get_adc2(msg); raw_aux->adc3 = mavlink_msg_raw_aux_get_adc3(msg); raw_aux->adc4 = mavlink_msg_raw_aux_get_adc4(msg); raw_aux->vbat = mavlink_msg_raw_aux_get_vbat(msg); raw_aux->temp = mavlink_msg_raw_aux_get_temp(msg); - raw_aux->baro = mavlink_msg_raw_aux_get_baro(msg); #else memcpy(raw_aux, _MAV_PAYLOAD(msg), 16); #endif diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_set_cam_shutter.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h similarity index 80% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_set_cam_shutter.h rename to mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h index feb13cd734a7c40072168e9b9d36e1a01c50e120..698625b7e1f0fd5cda21ec7c40112143ae5da27e 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_set_cam_shutter.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h @@ -4,12 +4,12 @@ typedef struct __mavlink_set_cam_shutter_t { + float gain; ///< Camera gain + uint16_t interval; ///< Shutter interval, in microseconds + uint16_t exposure; ///< Exposure time, in microseconds uint8_t cam_no; ///< Camera id uint8_t cam_mode; ///< Camera mode: 0 = auto, 1 = manual uint8_t trigger_pin; ///< Trigger pin, 0-3 for PtGrey FireFly - uint16_t interval; ///< Shutter interval, in microseconds - uint16_t exposure; ///< Exposure time, in microseconds - float gain; ///< Camera gain } mavlink_set_cam_shutter_t; #define MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN 11 @@ -20,12 +20,12 @@ typedef struct __mavlink_set_cam_shutter_t #define MAVLINK_MESSAGE_INFO_SET_CAM_SHUTTER { \ "SET_CAM_SHUTTER", \ 6, \ - { { "cam_no", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_cam_shutter_t, cam_no) }, \ - { "cam_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_cam_shutter_t, cam_mode) }, \ - { "trigger_pin", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_set_cam_shutter_t, trigger_pin) }, \ - { "interval", NULL, MAVLINK_TYPE_UINT16_T, 0, 3, offsetof(mavlink_set_cam_shutter_t, interval) }, \ - { "exposure", NULL, MAVLINK_TYPE_UINT16_T, 0, 5, offsetof(mavlink_set_cam_shutter_t, exposure) }, \ - { "gain", NULL, MAVLINK_TYPE_FLOAT, 0, 7, offsetof(mavlink_set_cam_shutter_t, gain) }, \ + { { "gain", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_cam_shutter_t, gain) }, \ + { "interval", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_set_cam_shutter_t, interval) }, \ + { "exposure", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_set_cam_shutter_t, exposure) }, \ + { "cam_no", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_set_cam_shutter_t, cam_no) }, \ + { "cam_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_set_cam_shutter_t, cam_mode) }, \ + { "trigger_pin", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_set_cam_shutter_t, trigger_pin) }, \ } \ } @@ -49,28 +49,28 @@ static inline uint16_t mavlink_msg_set_cam_shutter_pack(uint8_t system_id, uint8 { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[11]; - _mav_put_uint8_t(buf, 0, cam_no); - _mav_put_uint8_t(buf, 1, cam_mode); - _mav_put_uint8_t(buf, 2, trigger_pin); - _mav_put_uint16_t(buf, 3, interval); - _mav_put_uint16_t(buf, 5, exposure); - _mav_put_float(buf, 7, gain); - - memcpy(_MAV_PAYLOAD(msg), buf, 11); + _mav_put_float(buf, 0, gain); + _mav_put_uint16_t(buf, 4, interval); + _mav_put_uint16_t(buf, 6, exposure); + _mav_put_uint8_t(buf, 8, cam_no); + _mav_put_uint8_t(buf, 9, cam_mode); + _mav_put_uint8_t(buf, 10, trigger_pin); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 11); #else mavlink_set_cam_shutter_t packet; + packet.gain = gain; + packet.interval = interval; + packet.exposure = exposure; packet.cam_no = cam_no; packet.cam_mode = cam_mode; packet.trigger_pin = trigger_pin; - packet.interval = interval; - packet.exposure = exposure; - packet.gain = gain; - memcpy(_MAV_PAYLOAD(msg), &packet, 11); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 11); #endif msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER; - return mavlink_finalize_message(msg, system_id, component_id, 11); + return mavlink_finalize_message(msg, system_id, component_id, 11, 108); } /** @@ -93,28 +93,28 @@ static inline uint16_t mavlink_msg_set_cam_shutter_pack_chan(uint8_t system_id, { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[11]; - _mav_put_uint8_t(buf, 0, cam_no); - _mav_put_uint8_t(buf, 1, cam_mode); - _mav_put_uint8_t(buf, 2, trigger_pin); - _mav_put_uint16_t(buf, 3, interval); - _mav_put_uint16_t(buf, 5, exposure); - _mav_put_float(buf, 7, gain); - - memcpy(_MAV_PAYLOAD(msg), buf, 11); + _mav_put_float(buf, 0, gain); + _mav_put_uint16_t(buf, 4, interval); + _mav_put_uint16_t(buf, 6, exposure); + _mav_put_uint8_t(buf, 8, cam_no); + _mav_put_uint8_t(buf, 9, cam_mode); + _mav_put_uint8_t(buf, 10, trigger_pin); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 11); #else mavlink_set_cam_shutter_t packet; + packet.gain = gain; + packet.interval = interval; + packet.exposure = exposure; packet.cam_no = cam_no; packet.cam_mode = cam_mode; packet.trigger_pin = trigger_pin; - packet.interval = interval; - packet.exposure = exposure; - packet.gain = gain; - memcpy(_MAV_PAYLOAD(msg), &packet, 11); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 11); #endif msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 11); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 11, 108); } /** @@ -147,24 +147,24 @@ static inline void mavlink_msg_set_cam_shutter_send(mavlink_channel_t chan, uint { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[11]; - _mav_put_uint8_t(buf, 0, cam_no); - _mav_put_uint8_t(buf, 1, cam_mode); - _mav_put_uint8_t(buf, 2, trigger_pin); - _mav_put_uint16_t(buf, 3, interval); - _mav_put_uint16_t(buf, 5, exposure); - _mav_put_float(buf, 7, gain); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, buf, 11); + _mav_put_float(buf, 0, gain); + _mav_put_uint16_t(buf, 4, interval); + _mav_put_uint16_t(buf, 6, exposure); + _mav_put_uint8_t(buf, 8, cam_no); + _mav_put_uint8_t(buf, 9, cam_mode); + _mav_put_uint8_t(buf, 10, trigger_pin); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, buf, 11, 108); #else mavlink_set_cam_shutter_t packet; + packet.gain = gain; + packet.interval = interval; + packet.exposure = exposure; packet.cam_no = cam_no; packet.cam_mode = cam_mode; packet.trigger_pin = trigger_pin; - packet.interval = interval; - packet.exposure = exposure; - packet.gain = gain; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, (const char *)&packet, 11); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, (const char *)&packet, 11, 108); #endif } @@ -180,7 +180,7 @@ static inline void mavlink_msg_set_cam_shutter_send(mavlink_channel_t chan, uint */ static inline uint8_t mavlink_msg_set_cam_shutter_get_cam_no(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 0); + return _MAV_RETURN_uint8_t(msg, 8); } /** @@ -190,7 +190,7 @@ static inline uint8_t mavlink_msg_set_cam_shutter_get_cam_no(const mavlink_messa */ static inline uint8_t mavlink_msg_set_cam_shutter_get_cam_mode(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 1); + return _MAV_RETURN_uint8_t(msg, 9); } /** @@ -200,7 +200,7 @@ static inline uint8_t mavlink_msg_set_cam_shutter_get_cam_mode(const mavlink_mes */ static inline uint8_t mavlink_msg_set_cam_shutter_get_trigger_pin(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 2); + return _MAV_RETURN_uint8_t(msg, 10); } /** @@ -210,7 +210,7 @@ static inline uint8_t mavlink_msg_set_cam_shutter_get_trigger_pin(const mavlink_ */ static inline uint16_t mavlink_msg_set_cam_shutter_get_interval(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 3); + return _MAV_RETURN_uint16_t(msg, 4); } /** @@ -220,7 +220,7 @@ static inline uint16_t mavlink_msg_set_cam_shutter_get_interval(const mavlink_me */ static inline uint16_t mavlink_msg_set_cam_shutter_get_exposure(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 5); + return _MAV_RETURN_uint16_t(msg, 6); } /** @@ -230,7 +230,7 @@ static inline uint16_t mavlink_msg_set_cam_shutter_get_exposure(const mavlink_me */ static inline float mavlink_msg_set_cam_shutter_get_gain(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 7); + return _MAV_RETURN_float(msg, 0); } /** @@ -242,12 +242,12 @@ static inline float mavlink_msg_set_cam_shutter_get_gain(const mavlink_message_t static inline void mavlink_msg_set_cam_shutter_decode(const mavlink_message_t* msg, mavlink_set_cam_shutter_t* set_cam_shutter) { #if MAVLINK_NEED_BYTE_SWAP + set_cam_shutter->gain = mavlink_msg_set_cam_shutter_get_gain(msg); + set_cam_shutter->interval = mavlink_msg_set_cam_shutter_get_interval(msg); + set_cam_shutter->exposure = mavlink_msg_set_cam_shutter_get_exposure(msg); set_cam_shutter->cam_no = mavlink_msg_set_cam_shutter_get_cam_no(msg); set_cam_shutter->cam_mode = mavlink_msg_set_cam_shutter_get_cam_mode(msg); set_cam_shutter->trigger_pin = mavlink_msg_set_cam_shutter_get_trigger_pin(msg); - set_cam_shutter->interval = mavlink_msg_set_cam_shutter_get_interval(msg); - set_cam_shutter->exposure = mavlink_msg_set_cam_shutter_get_exposure(msg); - set_cam_shutter->gain = mavlink_msg_set_cam_shutter_get_gain(msg); #else memcpy(set_cam_shutter, _MAV_PAYLOAD(msg), 11); #endif diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h new file mode 100644 index 0000000000000000000000000000000000000000..27c08b7c9ce289430bcef88367a8ddbcf47d55b4 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h @@ -0,0 +1,254 @@ +// MESSAGE SET_POSITION_CONTROL_OFFSET PACKING + +#define MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET 160 + +typedef struct __mavlink_set_position_control_offset_t +{ + float x; ///< x position offset + float y; ///< y position offset + float z; ///< z position offset + float yaw; ///< yaw orientation offset in radians, 0 = NORTH + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_set_position_control_offset_t; + +#define MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN 18 +#define MAVLINK_MSG_ID_160_LEN 18 + + + +#define MAVLINK_MESSAGE_INFO_SET_POSITION_CONTROL_OFFSET { \ + "SET_POSITION_CONTROL_OFFSET", \ + 6, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_position_control_offset_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_position_control_offset_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_position_control_offset_t, z) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_control_offset_t, yaw) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_set_position_control_offset_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_set_position_control_offset_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a set_position_control_offset 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 target_system System ID + * @param target_component Component ID + * @param x x position offset + * @param y y position offset + * @param z z position offset + * @param yaw yaw orientation offset in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_position_control_offset_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); +#else + mavlink_set_position_control_offset_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET; + return mavlink_finalize_message(msg, system_id, component_id, 18, 22); +} + +/** + * @brief Pack a set_position_control_offset 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 target_system System ID + * @param target_component Component ID + * @param x x position offset + * @param y y position offset + * @param z z position offset + * @param yaw yaw orientation offset in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_position_control_offset_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,float x,float y,float z,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18); +#else + mavlink_set_position_control_offset_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 22); +} + +/** + * @brief Encode a set_position_control_offset 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 set_position_control_offset C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_position_control_offset_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_control_offset_t* set_position_control_offset) +{ + return mavlink_msg_set_position_control_offset_pack(system_id, component_id, msg, set_position_control_offset->target_system, set_position_control_offset->target_component, set_position_control_offset->x, set_position_control_offset->y, set_position_control_offset->z, set_position_control_offset->yaw); +} + +/** + * @brief Send a set_position_control_offset message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param x x position offset + * @param y y position offset + * @param z z position offset + * @param yaw yaw orientation offset in radians, 0 = NORTH + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_position_control_offset_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, buf, 18, 22); +#else + mavlink_set_position_control_offset_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, (const char *)&packet, 18, 22); +#endif +} + +#endif + +// MESSAGE SET_POSITION_CONTROL_OFFSET UNPACKING + + +/** + * @brief Get field target_system from set_position_control_offset message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_position_control_offset_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field target_component from set_position_control_offset message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_position_control_offset_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field x from set_position_control_offset message + * + * @return x position offset + */ +static inline float mavlink_msg_set_position_control_offset_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field y from set_position_control_offset message + * + * @return y position offset + */ +static inline float mavlink_msg_set_position_control_offset_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field z from set_position_control_offset message + * + * @return z position offset + */ +static inline float mavlink_msg_set_position_control_offset_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw from set_position_control_offset message + * + * @return yaw orientation offset in radians, 0 = NORTH + */ +static inline float mavlink_msg_set_position_control_offset_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a set_position_control_offset message into a struct + * + * @param msg The message to decode + * @param set_position_control_offset C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_position_control_offset_decode(const mavlink_message_t* msg, mavlink_set_position_control_offset_t* set_position_control_offset) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_position_control_offset->x = mavlink_msg_set_position_control_offset_get_x(msg); + set_position_control_offset->y = mavlink_msg_set_position_control_offset_get_y(msg); + set_position_control_offset->z = mavlink_msg_set_position_control_offset_get_z(msg); + set_position_control_offset->yaw = mavlink_msg_set_position_control_offset_get_yaw(msg); + set_position_control_offset->target_system = mavlink_msg_set_position_control_offset_get_target_system(msg); + set_position_control_offset->target_component = mavlink_msg_set_position_control_offset_get_target_component(msg); +#else + memcpy(set_position_control_offset, _MAV_PAYLOAD(msg), 18); +#endif +} diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_watchdog_command.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h similarity index 84% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_watchdog_command.h rename to mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h index 8d87b2d78917f1e7622e3eef03477658ff56f4cf..240f69e727680904c9d78035d7e43b8a460e016f 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_watchdog_command.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h @@ -4,9 +4,9 @@ typedef struct __mavlink_watchdog_command_t { - uint8_t target_system_id; ///< Target system ID uint16_t watchdog_id; ///< Watchdog ID uint16_t process_id; ///< Process ID + uint8_t target_system_id; ///< Target system ID uint8_t command_id; ///< Command ID } mavlink_watchdog_command_t; @@ -18,9 +18,9 @@ typedef struct __mavlink_watchdog_command_t #define MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND { \ "WATCHDOG_COMMAND", \ 4, \ - { { "target_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_watchdog_command_t, target_system_id) }, \ - { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 1, offsetof(mavlink_watchdog_command_t, watchdog_id) }, \ - { "process_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 3, offsetof(mavlink_watchdog_command_t, process_id) }, \ + { { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_watchdog_command_t, watchdog_id) }, \ + { "process_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_watchdog_command_t, process_id) }, \ + { "target_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_watchdog_command_t, target_system_id) }, \ { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_watchdog_command_t, command_id) }, \ } \ } @@ -43,24 +43,24 @@ static inline uint16_t mavlink_msg_watchdog_command_pack(uint8_t system_id, uint { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[6]; - _mav_put_uint8_t(buf, 0, target_system_id); - _mav_put_uint16_t(buf, 1, watchdog_id); - _mav_put_uint16_t(buf, 3, process_id); + _mav_put_uint16_t(buf, 0, watchdog_id); + _mav_put_uint16_t(buf, 2, process_id); + _mav_put_uint8_t(buf, 4, target_system_id); _mav_put_uint8_t(buf, 5, command_id); - memcpy(_MAV_PAYLOAD(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); #else mavlink_watchdog_command_t packet; - packet.target_system_id = target_system_id; packet.watchdog_id = watchdog_id; packet.process_id = process_id; + packet.target_system_id = target_system_id; packet.command_id = command_id; - memcpy(_MAV_PAYLOAD(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); #endif msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND; - return mavlink_finalize_message(msg, system_id, component_id, 6); + return mavlink_finalize_message(msg, system_id, component_id, 6, 162); } /** @@ -81,24 +81,24 @@ static inline uint16_t mavlink_msg_watchdog_command_pack_chan(uint8_t system_id, { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[6]; - _mav_put_uint8_t(buf, 0, target_system_id); - _mav_put_uint16_t(buf, 1, watchdog_id); - _mav_put_uint16_t(buf, 3, process_id); + _mav_put_uint16_t(buf, 0, watchdog_id); + _mav_put_uint16_t(buf, 2, process_id); + _mav_put_uint8_t(buf, 4, target_system_id); _mav_put_uint8_t(buf, 5, command_id); - memcpy(_MAV_PAYLOAD(msg), buf, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6); #else mavlink_watchdog_command_t packet; - packet.target_system_id = target_system_id; packet.watchdog_id = watchdog_id; packet.process_id = process_id; + packet.target_system_id = target_system_id; packet.command_id = command_id; - memcpy(_MAV_PAYLOAD(msg), &packet, 6); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6); #endif msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 162); } /** @@ -129,20 +129,20 @@ static inline void mavlink_msg_watchdog_command_send(mavlink_channel_t chan, uin { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[6]; - _mav_put_uint8_t(buf, 0, target_system_id); - _mav_put_uint16_t(buf, 1, watchdog_id); - _mav_put_uint16_t(buf, 3, process_id); + _mav_put_uint16_t(buf, 0, watchdog_id); + _mav_put_uint16_t(buf, 2, process_id); + _mav_put_uint8_t(buf, 4, target_system_id); _mav_put_uint8_t(buf, 5, command_id); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, buf, 6); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, buf, 6, 162); #else mavlink_watchdog_command_t packet; - packet.target_system_id = target_system_id; packet.watchdog_id = watchdog_id; packet.process_id = process_id; + packet.target_system_id = target_system_id; packet.command_id = command_id; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, (const char *)&packet, 6); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, (const char *)&packet, 6, 162); #endif } @@ -158,7 +158,7 @@ static inline void mavlink_msg_watchdog_command_send(mavlink_channel_t chan, uin */ static inline uint8_t mavlink_msg_watchdog_command_get_target_system_id(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 0); + return _MAV_RETURN_uint8_t(msg, 4); } /** @@ -168,7 +168,7 @@ static inline uint8_t mavlink_msg_watchdog_command_get_target_system_id(const ma */ static inline uint16_t mavlink_msg_watchdog_command_get_watchdog_id(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 1); + return _MAV_RETURN_uint16_t(msg, 0); } /** @@ -178,7 +178,7 @@ static inline uint16_t mavlink_msg_watchdog_command_get_watchdog_id(const mavlin */ static inline uint16_t mavlink_msg_watchdog_command_get_process_id(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 3); + return _MAV_RETURN_uint16_t(msg, 2); } /** @@ -200,9 +200,9 @@ static inline uint8_t mavlink_msg_watchdog_command_get_command_id(const mavlink_ static inline void mavlink_msg_watchdog_command_decode(const mavlink_message_t* msg, mavlink_watchdog_command_t* watchdog_command) { #if MAVLINK_NEED_BYTE_SWAP - watchdog_command->target_system_id = mavlink_msg_watchdog_command_get_target_system_id(msg); watchdog_command->watchdog_id = mavlink_msg_watchdog_command_get_watchdog_id(msg); watchdog_command->process_id = mavlink_msg_watchdog_command_get_process_id(msg); + watchdog_command->target_system_id = mavlink_msg_watchdog_command_get_target_system_id(msg); watchdog_command->command_id = mavlink_msg_watchdog_command_get_command_id(msg); #else memcpy(watchdog_command, _MAV_PAYLOAD(msg), 6); diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_watchdog_heartbeat.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h similarity index 94% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_watchdog_heartbeat.h rename to mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h index 0232e01c3fe8049a47127da039786578525b9736..f1fe5eb86a0649fdd7a6635ca7b86be64b551d32 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_watchdog_heartbeat.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h @@ -40,17 +40,17 @@ static inline uint16_t mavlink_msg_watchdog_heartbeat_pack(uint8_t system_id, ui _mav_put_uint16_t(buf, 0, watchdog_id); _mav_put_uint16_t(buf, 2, process_count); - memcpy(_MAV_PAYLOAD(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); #else mavlink_watchdog_heartbeat_t packet; packet.watchdog_id = watchdog_id; packet.process_count = process_count; - memcpy(_MAV_PAYLOAD(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); #endif msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT; - return mavlink_finalize_message(msg, system_id, component_id, 4); + return mavlink_finalize_message(msg, system_id, component_id, 4, 153); } /** @@ -72,17 +72,17 @@ static inline uint16_t mavlink_msg_watchdog_heartbeat_pack_chan(uint8_t system_i _mav_put_uint16_t(buf, 0, watchdog_id); _mav_put_uint16_t(buf, 2, process_count); - memcpy(_MAV_PAYLOAD(msg), buf, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); #else mavlink_watchdog_heartbeat_t packet; packet.watchdog_id = watchdog_id; packet.process_count = process_count; - memcpy(_MAV_PAYLOAD(msg), &packet, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); #endif msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 153); } /** @@ -114,13 +114,13 @@ static inline void mavlink_msg_watchdog_heartbeat_send(mavlink_channel_t chan, u _mav_put_uint16_t(buf, 0, watchdog_id); _mav_put_uint16_t(buf, 2, process_count); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, buf, 4); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, buf, 4, 153); #else mavlink_watchdog_heartbeat_t packet; packet.watchdog_id = watchdog_id; packet.process_count = process_count; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, (const char *)&packet, 4); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, (const char *)&packet, 4, 153); #endif } diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_watchdog_process_info.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h similarity index 81% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_watchdog_process_info.h rename to mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h index 5b3ced0d40f8b836f2f9eb7a0c6eec64bc25e336..7ba3ddf0378a4fa907f7affe28f3b9796f012cfa 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_watchdog_process_info.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h @@ -4,11 +4,11 @@ typedef struct __mavlink_watchdog_process_info_t { + int32_t timeout; ///< Timeout (seconds) uint16_t watchdog_id; ///< Watchdog ID uint16_t process_id; ///< Process ID char name[100]; ///< Process name char arguments[147]; ///< Process arguments - int32_t timeout; ///< Timeout (seconds) } mavlink_watchdog_process_info_t; #define MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN 255 @@ -20,11 +20,11 @@ typedef struct __mavlink_watchdog_process_info_t #define MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_INFO { \ "WATCHDOG_PROCESS_INFO", \ 5, \ - { { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_watchdog_process_info_t, watchdog_id) }, \ - { "process_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_watchdog_process_info_t, process_id) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 100, 4, offsetof(mavlink_watchdog_process_info_t, name) }, \ - { "arguments", NULL, MAVLINK_TYPE_CHAR, 147, 104, offsetof(mavlink_watchdog_process_info_t, arguments) }, \ - { "timeout", NULL, MAVLINK_TYPE_INT32_T, 0, 251, offsetof(mavlink_watchdog_process_info_t, timeout) }, \ + { { "timeout", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_watchdog_process_info_t, timeout) }, \ + { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_watchdog_process_info_t, watchdog_id) }, \ + { "process_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_watchdog_process_info_t, process_id) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 100, 8, offsetof(mavlink_watchdog_process_info_t, name) }, \ + { "arguments", NULL, MAVLINK_TYPE_CHAR, 147, 108, offsetof(mavlink_watchdog_process_info_t, arguments) }, \ } \ } @@ -47,24 +47,24 @@ static inline uint16_t mavlink_msg_watchdog_process_info_pack(uint8_t system_id, { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[255]; - _mav_put_uint16_t(buf, 0, watchdog_id); - _mav_put_uint16_t(buf, 2, process_id); - _mav_put_int32_t(buf, 251, timeout); - _mav_put_char_array(buf, 4, name, 100); - _mav_put_char_array(buf, 104, arguments, 147); - memcpy(_MAV_PAYLOAD(msg), buf, 255); + _mav_put_int32_t(buf, 0, timeout); + _mav_put_uint16_t(buf, 4, watchdog_id); + _mav_put_uint16_t(buf, 6, process_id); + _mav_put_char_array(buf, 8, name, 100); + _mav_put_char_array(buf, 108, arguments, 147); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 255); #else mavlink_watchdog_process_info_t packet; + packet.timeout = timeout; packet.watchdog_id = watchdog_id; packet.process_id = process_id; - packet.timeout = timeout; mav_array_memcpy(packet.name, name, sizeof(char)*100); mav_array_memcpy(packet.arguments, arguments, sizeof(char)*147); - memcpy(_MAV_PAYLOAD(msg), &packet, 255); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 255); #endif msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO; - return mavlink_finalize_message(msg, system_id, component_id, 255); + return mavlink_finalize_message(msg, system_id, component_id, 255, 16); } /** @@ -86,24 +86,24 @@ static inline uint16_t mavlink_msg_watchdog_process_info_pack_chan(uint8_t syste { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[255]; - _mav_put_uint16_t(buf, 0, watchdog_id); - _mav_put_uint16_t(buf, 2, process_id); - _mav_put_int32_t(buf, 251, timeout); - _mav_put_char_array(buf, 4, name, 100); - _mav_put_char_array(buf, 104, arguments, 147); - memcpy(_MAV_PAYLOAD(msg), buf, 255); + _mav_put_int32_t(buf, 0, timeout); + _mav_put_uint16_t(buf, 4, watchdog_id); + _mav_put_uint16_t(buf, 6, process_id); + _mav_put_char_array(buf, 8, name, 100); + _mav_put_char_array(buf, 108, arguments, 147); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 255); #else mavlink_watchdog_process_info_t packet; + packet.timeout = timeout; packet.watchdog_id = watchdog_id; packet.process_id = process_id; - packet.timeout = timeout; mav_array_memcpy(packet.name, name, sizeof(char)*100); mav_array_memcpy(packet.arguments, arguments, sizeof(char)*147); - memcpy(_MAV_PAYLOAD(msg), &packet, 255); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 255); #endif msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 255); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 255, 16); } /** @@ -135,20 +135,20 @@ static inline void mavlink_msg_watchdog_process_info_send(mavlink_channel_t chan { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[255]; - _mav_put_uint16_t(buf, 0, watchdog_id); - _mav_put_uint16_t(buf, 2, process_id); - _mav_put_int32_t(buf, 251, timeout); - _mav_put_char_array(buf, 4, name, 100); - _mav_put_char_array(buf, 104, arguments, 147); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, buf, 255); + _mav_put_int32_t(buf, 0, timeout); + _mav_put_uint16_t(buf, 4, watchdog_id); + _mav_put_uint16_t(buf, 6, process_id); + _mav_put_char_array(buf, 8, name, 100); + _mav_put_char_array(buf, 108, arguments, 147); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, buf, 255, 16); #else mavlink_watchdog_process_info_t packet; + packet.timeout = timeout; packet.watchdog_id = watchdog_id; packet.process_id = process_id; - packet.timeout = timeout; mav_array_memcpy(packet.name, name, sizeof(char)*100); mav_array_memcpy(packet.arguments, arguments, sizeof(char)*147); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, (const char *)&packet, 255); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, (const char *)&packet, 255, 16); #endif } @@ -164,7 +164,7 @@ static inline void mavlink_msg_watchdog_process_info_send(mavlink_channel_t chan */ static inline uint16_t mavlink_msg_watchdog_process_info_get_watchdog_id(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 0); + return _MAV_RETURN_uint16_t(msg, 4); } /** @@ -174,7 +174,7 @@ static inline uint16_t mavlink_msg_watchdog_process_info_get_watchdog_id(const m */ static inline uint16_t mavlink_msg_watchdog_process_info_get_process_id(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 2); + return _MAV_RETURN_uint16_t(msg, 6); } /** @@ -184,7 +184,7 @@ static inline uint16_t mavlink_msg_watchdog_process_info_get_process_id(const ma */ static inline uint16_t mavlink_msg_watchdog_process_info_get_name(const mavlink_message_t* msg, char *name) { - return _MAV_RETURN_char_array(msg, name, 100, 4); + return _MAV_RETURN_char_array(msg, name, 100, 8); } /** @@ -194,7 +194,7 @@ static inline uint16_t mavlink_msg_watchdog_process_info_get_name(const mavlink_ */ static inline uint16_t mavlink_msg_watchdog_process_info_get_arguments(const mavlink_message_t* msg, char *arguments) { - return _MAV_RETURN_char_array(msg, arguments, 147, 104); + return _MAV_RETURN_char_array(msg, arguments, 147, 108); } /** @@ -204,7 +204,7 @@ static inline uint16_t mavlink_msg_watchdog_process_info_get_arguments(const mav */ static inline int32_t mavlink_msg_watchdog_process_info_get_timeout(const mavlink_message_t* msg) { - return _MAV_RETURN_int32_t(msg, 251); + return _MAV_RETURN_int32_t(msg, 0); } /** @@ -216,11 +216,11 @@ static inline int32_t mavlink_msg_watchdog_process_info_get_timeout(const mavlin static inline void mavlink_msg_watchdog_process_info_decode(const mavlink_message_t* msg, mavlink_watchdog_process_info_t* watchdog_process_info) { #if MAVLINK_NEED_BYTE_SWAP + watchdog_process_info->timeout = mavlink_msg_watchdog_process_info_get_timeout(msg); watchdog_process_info->watchdog_id = mavlink_msg_watchdog_process_info_get_watchdog_id(msg); watchdog_process_info->process_id = mavlink_msg_watchdog_process_info_get_process_id(msg); mavlink_msg_watchdog_process_info_get_name(msg, watchdog_process_info->name); mavlink_msg_watchdog_process_info_get_arguments(msg, watchdog_process_info->arguments); - watchdog_process_info->timeout = mavlink_msg_watchdog_process_info_get_timeout(msg); #else memcpy(watchdog_process_info, _MAV_PAYLOAD(msg), 255); #endif diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_watchdog_process_status.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h similarity index 79% rename from mavlink/include/v0.9/pixhawk/mavlink_msg_watchdog_process_status.h rename to mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h index 0796f0bfead5d7fc0d8fbc3e1858e3baf5f5160c..5795c63283e94129b9d85ce983b89eb6d801b88e 100644 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_watchdog_process_status.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h @@ -4,12 +4,12 @@ typedef struct __mavlink_watchdog_process_status_t { + int32_t pid; ///< PID uint16_t watchdog_id; ///< Watchdog ID uint16_t process_id; ///< Process ID + uint16_t crashes; ///< Number of crashes uint8_t state; ///< Is running / finished / suspended / crashed uint8_t muted; ///< Is muted - int32_t pid; ///< PID - uint16_t crashes; ///< Number of crashes } mavlink_watchdog_process_status_t; #define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN 12 @@ -20,12 +20,12 @@ typedef struct __mavlink_watchdog_process_status_t #define MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS { \ "WATCHDOG_PROCESS_STATUS", \ 6, \ - { { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_watchdog_process_status_t, watchdog_id) }, \ - { "process_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_watchdog_process_status_t, process_id) }, \ - { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_watchdog_process_status_t, state) }, \ - { "muted", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_watchdog_process_status_t, muted) }, \ - { "pid", NULL, MAVLINK_TYPE_INT32_T, 0, 6, offsetof(mavlink_watchdog_process_status_t, pid) }, \ - { "crashes", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_watchdog_process_status_t, crashes) }, \ + { { "pid", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_watchdog_process_status_t, pid) }, \ + { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_watchdog_process_status_t, watchdog_id) }, \ + { "process_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_watchdog_process_status_t, process_id) }, \ + { "crashes", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_watchdog_process_status_t, crashes) }, \ + { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_watchdog_process_status_t, state) }, \ + { "muted", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_watchdog_process_status_t, muted) }, \ } \ } @@ -49,28 +49,28 @@ static inline uint16_t mavlink_msg_watchdog_process_status_pack(uint8_t system_i { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[12]; - _mav_put_uint16_t(buf, 0, watchdog_id); - _mav_put_uint16_t(buf, 2, process_id); - _mav_put_uint8_t(buf, 4, state); - _mav_put_uint8_t(buf, 5, muted); - _mav_put_int32_t(buf, 6, pid); - _mav_put_uint16_t(buf, 10, crashes); - - memcpy(_MAV_PAYLOAD(msg), buf, 12); + _mav_put_int32_t(buf, 0, pid); + _mav_put_uint16_t(buf, 4, watchdog_id); + _mav_put_uint16_t(buf, 6, process_id); + _mav_put_uint16_t(buf, 8, crashes); + _mav_put_uint8_t(buf, 10, state); + _mav_put_uint8_t(buf, 11, muted); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); #else mavlink_watchdog_process_status_t packet; + packet.pid = pid; packet.watchdog_id = watchdog_id; packet.process_id = process_id; + packet.crashes = crashes; packet.state = state; packet.muted = muted; - packet.pid = pid; - packet.crashes = crashes; - memcpy(_MAV_PAYLOAD(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); #endif msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, 12); + return mavlink_finalize_message(msg, system_id, component_id, 12, 29); } /** @@ -93,28 +93,28 @@ static inline uint16_t mavlink_msg_watchdog_process_status_pack_chan(uint8_t sys { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[12]; - _mav_put_uint16_t(buf, 0, watchdog_id); - _mav_put_uint16_t(buf, 2, process_id); - _mav_put_uint8_t(buf, 4, state); - _mav_put_uint8_t(buf, 5, muted); - _mav_put_int32_t(buf, 6, pid); - _mav_put_uint16_t(buf, 10, crashes); - - memcpy(_MAV_PAYLOAD(msg), buf, 12); + _mav_put_int32_t(buf, 0, pid); + _mav_put_uint16_t(buf, 4, watchdog_id); + _mav_put_uint16_t(buf, 6, process_id); + _mav_put_uint16_t(buf, 8, crashes); + _mav_put_uint8_t(buf, 10, state); + _mav_put_uint8_t(buf, 11, muted); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); #else mavlink_watchdog_process_status_t packet; + packet.pid = pid; packet.watchdog_id = watchdog_id; packet.process_id = process_id; + packet.crashes = crashes; packet.state = state; packet.muted = muted; - packet.pid = pid; - packet.crashes = crashes; - memcpy(_MAV_PAYLOAD(msg), &packet, 12); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); #endif msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 29); } /** @@ -147,24 +147,24 @@ static inline void mavlink_msg_watchdog_process_status_send(mavlink_channel_t ch { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[12]; - _mav_put_uint16_t(buf, 0, watchdog_id); - _mav_put_uint16_t(buf, 2, process_id); - _mav_put_uint8_t(buf, 4, state); - _mav_put_uint8_t(buf, 5, muted); - _mav_put_int32_t(buf, 6, pid); - _mav_put_uint16_t(buf, 10, crashes); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, buf, 12); + _mav_put_int32_t(buf, 0, pid); + _mav_put_uint16_t(buf, 4, watchdog_id); + _mav_put_uint16_t(buf, 6, process_id); + _mav_put_uint16_t(buf, 8, crashes); + _mav_put_uint8_t(buf, 10, state); + _mav_put_uint8_t(buf, 11, muted); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, buf, 12, 29); #else mavlink_watchdog_process_status_t packet; + packet.pid = pid; packet.watchdog_id = watchdog_id; packet.process_id = process_id; + packet.crashes = crashes; packet.state = state; packet.muted = muted; - packet.pid = pid; - packet.crashes = crashes; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, (const char *)&packet, 12); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, (const char *)&packet, 12, 29); #endif } @@ -180,7 +180,7 @@ static inline void mavlink_msg_watchdog_process_status_send(mavlink_channel_t ch */ static inline uint16_t mavlink_msg_watchdog_process_status_get_watchdog_id(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 0); + return _MAV_RETURN_uint16_t(msg, 4); } /** @@ -190,7 +190,7 @@ static inline uint16_t mavlink_msg_watchdog_process_status_get_watchdog_id(const */ static inline uint16_t mavlink_msg_watchdog_process_status_get_process_id(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 2); + return _MAV_RETURN_uint16_t(msg, 6); } /** @@ -200,7 +200,7 @@ static inline uint16_t mavlink_msg_watchdog_process_status_get_process_id(const */ static inline uint8_t mavlink_msg_watchdog_process_status_get_state(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 4); + return _MAV_RETURN_uint8_t(msg, 10); } /** @@ -210,7 +210,7 @@ static inline uint8_t mavlink_msg_watchdog_process_status_get_state(const mavlin */ static inline uint8_t mavlink_msg_watchdog_process_status_get_muted(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 5); + return _MAV_RETURN_uint8_t(msg, 11); } /** @@ -220,7 +220,7 @@ static inline uint8_t mavlink_msg_watchdog_process_status_get_muted(const mavlin */ static inline int32_t mavlink_msg_watchdog_process_status_get_pid(const mavlink_message_t* msg) { - return _MAV_RETURN_int32_t(msg, 6); + return _MAV_RETURN_int32_t(msg, 0); } /** @@ -230,7 +230,7 @@ static inline int32_t mavlink_msg_watchdog_process_status_get_pid(const mavlink_ */ static inline uint16_t mavlink_msg_watchdog_process_status_get_crashes(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 10); + return _MAV_RETURN_uint16_t(msg, 8); } /** @@ -242,12 +242,12 @@ static inline uint16_t mavlink_msg_watchdog_process_status_get_crashes(const mav static inline void mavlink_msg_watchdog_process_status_decode(const mavlink_message_t* msg, mavlink_watchdog_process_status_t* watchdog_process_status) { #if MAVLINK_NEED_BYTE_SWAP + watchdog_process_status->pid = mavlink_msg_watchdog_process_status_get_pid(msg); watchdog_process_status->watchdog_id = mavlink_msg_watchdog_process_status_get_watchdog_id(msg); watchdog_process_status->process_id = mavlink_msg_watchdog_process_status_get_process_id(msg); + watchdog_process_status->crashes = mavlink_msg_watchdog_process_status_get_crashes(msg); watchdog_process_status->state = mavlink_msg_watchdog_process_status_get_state(msg); watchdog_process_status->muted = mavlink_msg_watchdog_process_status_get_muted(msg); - watchdog_process_status->pid = mavlink_msg_watchdog_process_status_get_pid(msg); - watchdog_process_status->crashes = mavlink_msg_watchdog_process_status_get_crashes(msg); #else memcpy(watchdog_process_status, _MAV_PAYLOAD(msg), 12); #endif diff --git a/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h b/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h new file mode 100644 index 0000000000000000000000000000000000000000..aa96e0bd7ac0b1c135055706e00d4a24ed3c23a6 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h @@ -0,0 +1,82 @@ +/** @file + * @brief MAVLink comm protocol generated from pixhawk.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef PIXHAWK_H +#define PIXHAWK_H + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 54, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 11, 52, 1, 92, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 26, 16, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 0, 0, 0, 0, 0, 0, 106, 43, 55, 12, 255, 53, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 200, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 108, 86, 95, 224, 0, 0, 0, 0, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 249, 182, 0, 0, 0, 0, 0, 0, 0, 153, 16, 29, 162, 0, 0, 0, 0, 0, 0, 90, 95, 36, 23, 223, 88, 0, 0, 0, 0, 254, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_CAM_SHUTTER, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGERED, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGER_CONTROL, MAVLINK_MESSAGE_INFO_IMAGE_AVAILABLE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_POSITION_CONTROL_OFFSET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT, MAVLINK_MESSAGE_INFO_MARKER, MAVLINK_MESSAGE_INFO_RAW_AUX, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_WATCHDOG_HEARTBEAT, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_INFO, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS, MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PATTERN_DETECTED, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST_CONNECTION, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_BRIEF_FEATURE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ATTITUDE_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_PIXHAWK + +#include "../common/common.h" + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +// ENUM DEFINITIONS + + +/** @brief Content Types for data transmission handshake */ +#ifndef HAVE_ENUM_DATA_TYPES +#define HAVE_ENUM_DATA_TYPES +enum DATA_TYPES +{ + DATA_TYPE_JPEG_IMAGE=1, /* | */ + DATA_TYPE_RAW_IMAGE=2, /* | */ + DATA_TYPE_KINECT=3, /* | */ + DATA_TYPES_ENUM_END=4, /* | */ +}; +#endif + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_set_cam_shutter.h" +#include "./mavlink_msg_image_triggered.h" +#include "./mavlink_msg_image_trigger_control.h" +#include "./mavlink_msg_image_available.h" +#include "./mavlink_msg_set_position_control_offset.h" +#include "./mavlink_msg_position_control_setpoint.h" +#include "./mavlink_msg_marker.h" +#include "./mavlink_msg_raw_aux.h" +#include "./mavlink_msg_watchdog_heartbeat.h" +#include "./mavlink_msg_watchdog_process_info.h" +#include "./mavlink_msg_watchdog_process_status.h" +#include "./mavlink_msg_watchdog_command.h" +#include "./mavlink_msg_pattern_detected.h" +#include "./mavlink_msg_point_of_interest.h" +#include "./mavlink_msg_point_of_interest_connection.h" +#include "./mavlink_msg_data_transmission_handshake.h" +#include "./mavlink_msg_encapsulated_data.h" +#include "./mavlink_msg_brief_feature.h" +#include "./mavlink_msg_attitude_control.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // PIXHAWK_H diff --git a/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.pb.h b/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.pb.h new file mode 100644 index 0000000000000000000000000000000000000000..7556606e98e26066d539950e6a43037145937770 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.pb.h @@ -0,0 +1,3663 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: pixhawk.proto + +#ifndef PROTOBUF_pixhawk_2eproto__INCLUDED +#define PROTOBUF_pixhawk_2eproto__INCLUDED + +#include + +#include + +#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 +#include +#include +#include +// @@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_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_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_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(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(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(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(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(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/include/v0.9/pixhawk/testsuite.h b/mavlink/include/mavlink/v1.0/pixhawk/testsuite.h similarity index 80% rename from mavlink/include/v0.9/pixhawk/testsuite.h rename to mavlink/include/mavlink/v1.0/pixhawk/testsuite.h index 3e18abc82780d9efb6e420972c380cbb453926ad..54a7ae5ba6e028a18982b3c5ee149e661fe9745b 100644 --- a/mavlink/include/v0.9/pixhawk/testsuite.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/testsuite.h @@ -30,21 +30,21 @@ static void mavlink_test_set_cam_shutter(uint8_t system_id, uint8_t component_id uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint16_t i; mavlink_set_cam_shutter_t packet_in = { - 5, - 72, - 139, - 17391, - 17495, - 66.0, + 17.0, + 17443, + 17547, + 29, + 96, + 163, }; mavlink_set_cam_shutter_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); + packet1.gain = packet_in.gain; + packet1.interval = packet_in.interval; + packet1.exposure = packet_in.exposure; packet1.cam_no = packet_in.cam_no; packet1.cam_mode = packet_in.cam_mode; packet1.trigger_pin = packet_in.trigger_pin; - packet1.interval = packet_in.interval; - packet1.exposure = packet_in.exposure; - packet1.gain = packet_in.gain; @@ -192,17 +192,14 @@ static void mavlink_test_image_available(uint8_t system_id, uint8_t component_id uint16_t i; mavlink_image_available_t packet_in = { 93372036854775807ULL, - 29, - 93372036854776374ULL, - 93372036854776878ULL, - 963498764, - 963498972, - 18951, - 19055, - 19159, - 58, - 963499544, - 963499752, + 93372036854776311ULL, + 93372036854776815ULL, + 963498712, + 963498920, + 963499128, + 963499336, + 297.0, + 325.0, 353.0, 381.0, 409.0, @@ -212,21 +209,19 @@ static void mavlink_test_image_available(uint8_t system_id, uint8_t component_id 521.0, 549.0, 577.0, - 605.0, - 633.0, + 21603, + 21707, + 21811, + 147, + 214, }; mavlink_image_available_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); packet1.cam_id = packet_in.cam_id; - packet1.cam_no = packet_in.cam_no; packet1.timestamp = packet_in.timestamp; packet1.valid_until = packet_in.valid_until; packet1.img_seq = packet_in.img_seq; packet1.img_buf_index = packet_in.img_buf_index; - packet1.width = packet_in.width; - packet1.height = packet_in.height; - packet1.depth = packet_in.depth; - packet1.channels = packet_in.channels; packet1.key = packet_in.key; packet1.exposure = packet_in.exposure; packet1.gain = packet_in.gain; @@ -240,6 +235,11 @@ static void mavlink_test_image_available(uint8_t system_id, uint8_t component_id packet1.ground_x = packet_in.ground_x; packet1.ground_y = packet_in.ground_y; packet1.ground_z = packet_in.ground_z; + packet1.width = packet_in.width; + packet1.height = packet_in.height; + packet1.depth = packet_in.depth; + packet1.cam_no = packet_in.cam_no; + packet1.channels = packet_in.channels; @@ -272,257 +272,43 @@ static void mavlink_test_image_available(uint8_t system_id, uint8_t component_id MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } -static void mavlink_test_vision_position_estimate(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_vision_position_estimate_t packet_in = { - 93372036854775807ULL, - 73.0, - 101.0, - 129.0, - 157.0, - 185.0, - 213.0, - }; - mavlink_vision_position_estimate_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.usec = packet_in.usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - - - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_position_estimate_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_position_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_position_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_vision_position_estimate_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>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); -} - -/** - * @brief Initiliaze the buffer for the X.25 CRC - * - * @param crcAccum the 16 bit X.25 CRC - */ -static inline void crc_init(uint16_t* crcAccum) -{ - *crcAccum = X25_INIT_CRC; -} - - -/** - * @brief Calculates the X.25 checksum on a byte buffer - * - * @param pBuffer buffer containing the byte array to hash - * @param length length of the byte array - * @return the checksum over the buffer bytes - **/ -static inline uint16_t crc_calculate(uint8_t* pBuffer, uint16_t length) -{ - uint16_t crcTmp; - crc_init(&crcTmp); - while (length--) { - crc_accumulate(*pBuffer++, &crcTmp); - } - return crcTmp; -} - -/** - * @brief Accumulate the X.25 CRC by adding an array of bytes - * - * The checksum function adds the hash of one char at a time to the - * 16 bit checksum (uint16_t). - * - * @param data new bytes to hash - * @param crcAccum the already accumulated checksum - **/ -static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_t length) -{ - const uint8_t *p = (const uint8_t *)pBuffer; - while (length--) { - crc_accumulate(*p++, crcAccum); - } -} - - - - -#endif /* _CHECKSUM_H_ */ - -#ifdef __cplusplus -} -#endif diff --git a/mavlink/include/v0.9/common/common.h b/mavlink/include/v0.9/common/common.h deleted file mode 100644 index 30490e82c61793c05c00f6ec79b806d4ba38c5b7..0000000000000000000000000000000000000000 --- a/mavlink/include/v0.9/common/common.h +++ /dev/null @@ -1,208 +0,0 @@ -/** @file - * @brief MAVLink comm protocol generated from common.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef COMMON_H -#define COMMON_H - -#ifdef __cplusplus -extern "C" { -#endif - -// MESSAGE LENGTHS AND CRCS - -#ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5} -#endif - -#ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7} -#endif - -#ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_BOOT, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, MAVLINK_MESSAGE_INFO_ACTION_ACK, MAVLINK_MESSAGE_INFO_ACTION, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_SET_NAV_MODE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, {NULL}, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_LOCAL_POSITION, MAVLINK_MESSAGE_INFO_GPS_RAW, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_WAYPOINT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST, MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT, MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL, MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED, MAVLINK_MESSAGE_INFO_WAYPOINT_ACK, MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_CONTROL_STATUS, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_POSITION_TARGET, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_SET_ALTITUDE, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG} -#endif - -#include "../protocol.h" - -#define MAVLINK_ENABLED_COMMON - - - -// MAVLINK VERSION - -#ifndef MAVLINK_VERSION -#define MAVLINK_VERSION 2 -#endif - -#if (MAVLINK_VERSION == 0) -#undef MAVLINK_VERSION -#define MAVLINK_VERSION 2 -#endif - -// ENUM DEFINITIONS - - -/** @brief Commands to be executed by the MAV. They can be executed on user request, - or as part of a mission script. If the action is used in a mission, the parameter mapping - to the waypoint/mission message is as follows: - Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what - ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. */ -#ifndef HAVE_ENUM_MAV_CMD -#define HAVE_ENUM_MAV_CMD -enum MAV_CMD -{ - MAV_CMD_NAV_WAYPOINT=16, /* Navigate to waypoint. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the waypoint counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at waypoint (rotary wing)| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this waypoint an unlimited amount of time |Empty| Empty| Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this waypoint for X turns |Turns| Empty| Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this waypoint for X seconds |Seconds (decimal)| Empty| Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the - vehicle itself. This can then be used by the vehicles control - system to control the vehicle attitude and the attitude of various - sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ - MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ - MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */ - MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera capturing. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the - vehicle itself. This can then be used by the vehicles control - system to control the vehicle attitude and the attitude of various - devices such as cameras. - |Region of interest mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple cameras etc.)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_ENUM_END=246, /* | */ -}; -#endif - -/** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a - recommendation to the autopilot software. Individual autopilots may or may not obey - the recommended messages. - */ -#ifndef HAVE_ENUM_MAV_DATA_STREAM -#define HAVE_ENUM_MAV_DATA_STREAM -enum MAV_DATA_STREAM -{ - MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */ - MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */ - MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */ - MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */ - MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */ - MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | */ - MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */ - MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */ - MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */ - MAV_DATA_STREAM_ENUM_END=13, /* | */ -}; -#endif - -/** @brief The ROI (region of interest) for the vehicle. This can be - be used by the vehicle for camera/vehicle attitude alignment (see - MAV_CMD_NAV_ROI). - */ -#ifndef HAVE_ENUM_MAV_ROI -#define HAVE_ENUM_MAV_ROI -enum MAV_ROI -{ - MAV_ROI_NONE=0, /* No region of interest. | */ - MAV_ROI_WPNEXT=1, /* Point toward next waypoint. | */ - MAV_ROI_WPINDEX=2, /* Point toward given waypoint. | */ - MAV_ROI_LOCATION=3, /* Point toward fixed location. | */ - MAV_ROI_TARGET=4, /* Point toward of given id. | */ - MAV_ROI_ENUM_END=5, /* | */ -}; -#endif - -// MESSAGE DEFINITIONS -#include "./mavlink_msg_heartbeat.h" -#include "./mavlink_msg_boot.h" -#include "./mavlink_msg_system_time.h" -#include "./mavlink_msg_ping.h" -#include "./mavlink_msg_system_time_utc.h" -#include "./mavlink_msg_change_operator_control.h" -#include "./mavlink_msg_change_operator_control_ack.h" -#include "./mavlink_msg_auth_key.h" -#include "./mavlink_msg_action_ack.h" -#include "./mavlink_msg_action.h" -#include "./mavlink_msg_set_mode.h" -#include "./mavlink_msg_set_nav_mode.h" -#include "./mavlink_msg_param_request_read.h" -#include "./mavlink_msg_param_request_list.h" -#include "./mavlink_msg_param_value.h" -#include "./mavlink_msg_param_set.h" -#include "./mavlink_msg_gps_raw_int.h" -#include "./mavlink_msg_scaled_imu.h" -#include "./mavlink_msg_gps_status.h" -#include "./mavlink_msg_raw_imu.h" -#include "./mavlink_msg_raw_pressure.h" -#include "./mavlink_msg_scaled_pressure.h" -#include "./mavlink_msg_attitude.h" -#include "./mavlink_msg_local_position.h" -#include "./mavlink_msg_global_position.h" -#include "./mavlink_msg_gps_raw.h" -#include "./mavlink_msg_sys_status.h" -#include "./mavlink_msg_rc_channels_raw.h" -#include "./mavlink_msg_rc_channels_scaled.h" -#include "./mavlink_msg_servo_output_raw.h" -#include "./mavlink_msg_waypoint.h" -#include "./mavlink_msg_waypoint_request.h" -#include "./mavlink_msg_waypoint_set_current.h" -#include "./mavlink_msg_waypoint_current.h" -#include "./mavlink_msg_waypoint_request_list.h" -#include "./mavlink_msg_waypoint_count.h" -#include "./mavlink_msg_waypoint_clear_all.h" -#include "./mavlink_msg_waypoint_reached.h" -#include "./mavlink_msg_waypoint_ack.h" -#include "./mavlink_msg_gps_set_global_origin.h" -#include "./mavlink_msg_gps_local_origin_set.h" -#include "./mavlink_msg_local_position_setpoint_set.h" -#include "./mavlink_msg_local_position_setpoint.h" -#include "./mavlink_msg_control_status.h" -#include "./mavlink_msg_safety_set_allowed_area.h" -#include "./mavlink_msg_safety_allowed_area.h" -#include "./mavlink_msg_set_roll_pitch_yaw_thrust.h" -#include "./mavlink_msg_set_roll_pitch_yaw_speed_thrust.h" -#include "./mavlink_msg_roll_pitch_yaw_thrust_setpoint.h" -#include "./mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h" -#include "./mavlink_msg_nav_controller_output.h" -#include "./mavlink_msg_position_target.h" -#include "./mavlink_msg_state_correction.h" -#include "./mavlink_msg_set_altitude.h" -#include "./mavlink_msg_request_data_stream.h" -#include "./mavlink_msg_hil_state.h" -#include "./mavlink_msg_hil_controls.h" -#include "./mavlink_msg_manual_control.h" -#include "./mavlink_msg_rc_channels_override.h" -#include "./mavlink_msg_global_position_int.h" -#include "./mavlink_msg_vfr_hud.h" -#include "./mavlink_msg_command.h" -#include "./mavlink_msg_command_ack.h" -#include "./mavlink_msg_optical_flow.h" -#include "./mavlink_msg_object_detection_event.h" -#include "./mavlink_msg_debug_vect.h" -#include "./mavlink_msg_named_value_float.h" -#include "./mavlink_msg_named_value_int.h" -#include "./mavlink_msg_statustext.h" -#include "./mavlink_msg_debug.h" - -#ifdef __cplusplus -} -#endif // __cplusplus -#endif // COMMON_H diff --git a/mavlink/include/v0.9/mavlink_helpers.h b/mavlink/include/v0.9/mavlink_helpers.h deleted file mode 100644 index 98250e1ac8377d4ffaf8966c9165a62fab64cf5f..0000000000000000000000000000000000000000 --- a/mavlink/include/v0.9/mavlink_helpers.h +++ /dev/null @@ -1,488 +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]; -} - -/** - * @brief Finalize a MAVLink message with channel assignment - * - * This function calculates the checksum and sets length and aircraft id correctly. - * It assumes that the message id and the payload are already correctly set. This function - * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack - * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead. - * - * @param msg Message to finalize - * @param system_id Id of the sending (this) system, 1-127 - * @param length Message length - */ -#if MAVLINK_CRC_EXTRA -MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t chan, uint8_t length, uint8_t crc_extra) -#else -MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t chan, uint8_t length) -#endif -{ - // This code part is the same for all messages; - uint16_t checksum; - msg->magic = MAVLINK_STX; - msg->len = length; - msg->sysid = system_id; - msg->compid = component_id; - // One sequence number per component - msg->seq = mavlink_get_channel_status(chan)->current_tx_seq; - mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1; - checksum = crc_calculate((uint8_t*)&msg->len, length + MAVLINK_CORE_HEADER_LEN); -#if MAVLINK_CRC_EXTRA - crc_accumulate(crc_extra, &checksum); -#endif - mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF); - mavlink_ck_b(msg) = (uint8_t)(checksum >> 8); - - return length + MAVLINK_NUM_NON_PAYLOAD_BYTES; -} - - -/** - * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel - */ -#if MAVLINK_CRC_EXTRA -MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t length, uint8_t crc_extra) -{ - return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length, crc_extra); -} -#else -MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t length) -{ - return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length); -} -#endif - -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); - -/** - * @brief Finalize a MAVLink message with channel assignment and send - */ -#if MAVLINK_CRC_EXTRA -MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, - uint8_t length, uint8_t crc_extra) -#else -MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length) -#endif -{ - uint16_t checksum; - uint8_t buf[MAVLINK_NUM_HEADER_BYTES]; - uint8_t ck[2]; - mavlink_status_t *status = mavlink_get_channel_status(chan); - buf[0] = MAVLINK_STX; - buf[1] = length; - buf[2] = status->current_tx_seq; - buf[3] = mavlink_system.sysid; - buf[4] = mavlink_system.compid; - buf[5] = msgid; - status->current_tx_seq++; - checksum = crc_calculate((uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN); - crc_accumulate_buffer(&checksum, packet, length); -#if MAVLINK_CRC_EXTRA - crc_accumulate(crc_extra, &checksum); -#endif - ck[0] = (uint8_t)(checksum & 0xFF); - ck[1] = (uint8_t)(checksum >> 8); - - MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); - _mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES); - _mavlink_send_uart(chan, packet, length); - _mavlink_send_uart(chan, (const char *)ck, 2); - MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); -} -#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS - -/** - * @brief Pack a message to send it over a serial byte stream - */ -MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg) -{ - memcpy(buffer, (uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len); - return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len; -} - -union __mavlink_bitfield { - uint8_t uint8; - int8_t int8; - uint16_t uint16; - int16_t int16; - uint32_t uint32; - int32_t int32; -}; - - -MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg) -{ - crc_init(&msg->checksum); -} - -MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) -{ - crc_accumulate(c, &msg->checksum); -} - -/** - * This is a convenience function which handles the complete MAVLink parsing. - * the function will parse one byte at a time and return the complete packet once - * it could be successfully decoded. Checksum and other failures will be silently - * ignored. - * - * @param chan ID of the current channel. This allows to parse different channels with this function. - * a channel is not a physical message channel like a serial port, but a logic partition of - * the communication streams in this case. COMM_NB is the limit for the number of channels - * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows - * @param c The char to barse - * - * @param returnMsg NULL if no message could be decoded, the message data else - * @return 0 if no message could be decoded, 1 else - * - * A typical use scenario of this function call is: - * - * @code - * #include // For fixed-width uint8_t type - * - * mavlink_message_t msg; - * int chan = 0; - * - * - * while(serial.bytesAvailable > 0) - * { - * uint8_t byte = serial.getNextByte(); - * if (mavlink_parse_char(chan, byte, &msg)) - * { - * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); - * } - * } - * - * - * @endcode - */ -MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) -{ - static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS]; - - /* - default message crc function. You can override this per-system to - put this data in a different memory segment - */ -#if MAVLINK_CRC_EXTRA -#ifndef MAVLINK_MESSAGE_CRC - static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS; -#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid] -#endif -#endif - - mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message - mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status - int bufferIndex = 0; - - status->msg_received = 0; - - switch (status->parse_state) - { - case MAVLINK_PARSE_STATE_UNINIT: - case MAVLINK_PARSE_STATE_IDLE: - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - mavlink_start_checksum(rxmsg); - } - break; - - case MAVLINK_PARSE_STATE_GOT_STX: - if (status->msg_received - /* Support shorter buffers than the - default maximum packet size */ -#if (MAVLINK_MAX_PAYLOAD_LEN < 255) - || c > MAVLINK_MAX_PAYLOAD_LEN -#endif - ) - { - status->buffer_overrun++; - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - } - else - { - // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2 - rxmsg->len = c; - status->packet_idx = 0; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH; - } - break; - - case MAVLINK_PARSE_STATE_GOT_LENGTH: - rxmsg->seq = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ; - break; - - case MAVLINK_PARSE_STATE_GOT_SEQ: - rxmsg->sysid = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID; - break; - - case MAVLINK_PARSE_STATE_GOT_SYSID: - rxmsg->compid = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID; - break; - - case MAVLINK_PARSE_STATE_GOT_COMPID: - rxmsg->msgid = c; - mavlink_update_checksum(rxmsg, c); - if (rxmsg->len == 0) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; - } - else - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID; - } - break; - - case MAVLINK_PARSE_STATE_GOT_MSGID: - _MAV_PAYLOAD(rxmsg)[status->packet_idx++] = (char)c; - mavlink_update_checksum(rxmsg, c); - if (status->packet_idx == rxmsg->len) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; - } - break; - - case MAVLINK_PARSE_STATE_GOT_PAYLOAD: -#if MAVLINK_CRC_EXTRA - mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid)); -#endif - if (c != (rxmsg->checksum & 0xFF)) { - // Check first checksum byte - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - mavlink_start_checksum(rxmsg); - } - } - else - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; - } - break; - - case MAVLINK_PARSE_STATE_GOT_CRC1: - if (c != (rxmsg->checksum >> 8)) { - // Check second checksum byte - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - mavlink_start_checksum(rxmsg); - } - } - else - { - // Successfully got message - status->msg_received = 1; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); - } - break; - } - - bufferIndex++; - // If a message has been sucessfully decoded, check index - if (status->msg_received == 1) - { - //while(status->current_seq != rxmsg->seq) - //{ - // status->packet_rx_drop_count++; - // status->current_seq++; - //} - status->current_rx_seq = rxmsg->seq; - // Initial condition: If no packet has been received so far, drop count is undefined - if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0; - // Count this packet as received - status->packet_rx_success_count++; - } - - r_mavlink_status->current_rx_seq = status->current_rx_seq+1; - r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; - r_mavlink_status->packet_rx_drop_count = status->parse_error; - status->parse_error = 0; - return status->msg_received; -} - -/** - * @brief Put a bitfield of length 1-32 bit into the buffer - * - * @param b the value to add, will be encoded in the bitfield - * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc. - * @param packet_index the position in the packet (the index of the first byte to use) - * @param bit_index the position in the byte (the index of the first bit to use) - * @param buffer packet buffer to write into - * @return new position of the last used byte in the buffer - */ -MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer) -{ - uint16_t bits_remain = bits; - // Transform number into network order - int32_t v; - uint8_t i_bit_index, i_byte_index, curr_bits_n; -#if MAVLINK_NEED_BYTE_SWAP - union { - int32_t i; - uint8_t b[4]; - } bin, bout; - bin.i = b; - bout.b[0] = bin.b[3]; - bout.b[1] = bin.b[2]; - bout.b[2] = bin.b[1]; - bout.b[3] = bin.b[0]; - v = bout.i; -#else - v = b; -#endif - - // buffer in - // 01100000 01000000 00000000 11110001 - // buffer out - // 11110001 00000000 01000000 01100000 - - // Existing partly filled byte (four free slots) - // 0111xxxx - - // Mask n free bits - // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1 - // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1 - - // Shift n bits into the right position - // out = in >> n; - - // Mask and shift bytes - i_bit_index = bit_index; - i_byte_index = packet_index; - if (bit_index > 0) - { - // If bits were available at start, they were available - // in the byte before the current index - i_byte_index--; - } - - // While bits have not been packed yet - while (bits_remain > 0) - { - // Bits still have to be packed - // there can be more than 8 bits, so - // we might have to pack them into more than one byte - - // First pack everything we can into the current 'open' byte - //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8 - //FIXME - if (bits_remain <= (uint8_t)(8 - i_bit_index)) - { - // Enough space - curr_bits_n = (uint8_t)bits_remain; - } - else - { - curr_bits_n = (8 - i_bit_index); - } - - // Pack these n bits into the current byte - // Mask out whatever was at that position with ones (xxx11111) - buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n)); - // Put content to this position, by masking out the non-used part - buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v); - - // Increment the bit index - i_bit_index += curr_bits_n; - - // Now proceed to the next byte, if necessary - bits_remain -= curr_bits_n; - if (bits_remain > 0) - { - // Offer another 8 bits / one byte - i_byte_index++; - i_bit_index = 0; - } - } - - *r_bit_index = i_bit_index; - // If a partly filled byte is present, mark this as consumed - if (i_bit_index != 7) i_byte_index++; - return i_byte_index - packet_index; -} - -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -// To make MAVLink work on your MCU, define comm_send_ch() if you wish -// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a -// whole packet at a time - -/* - -#include "mavlink_types.h" - -void comm_send_ch(mavlink_channel_t chan, uint8_t ch) -{ - if (chan == MAVLINK_COMM_0) - { - uart0_transmit(ch); - } - if (chan == MAVLINK_COMM_1) - { - uart1_transmit(ch); - } -} - */ - -MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len) -{ -#ifdef MAVLINK_SEND_UART_BYTES - /* this is the more efficient approach, if the platform - defines it */ - MAVLINK_SEND_UART_BYTES(chan, (uint8_t *)buf, len); -#else - /* fallback to one byte at a time */ - uint16_t i; - for (i = 0; i < len; i++) { - comm_send_ch(chan, (uint8_t)buf[i]); - } -#endif -} -#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS - -#endif /* _MAVLINK_HELPERS_H_ */ diff --git a/mavlink/include/v0.9/mavlink_types.h b/mavlink/include/v0.9/mavlink_types.h deleted file mode 100644 index 9daeffc63f7347027bffed188c00431744898174..0000000000000000000000000000000000000000 --- a/mavlink/include/v0.9/mavlink_types.h +++ /dev/null @@ -1,298 +0,0 @@ -#ifndef MAVLINK_TYPES_H_ -#define MAVLINK_TYPES_H_ - -#include "inttypes.h" - -enum MAV_CLASS -{ - MAV_CLASS_GENERIC = 0, ///< Generic autopilot, full support for everything - MAV_CLASS_PIXHAWK = 1, ///< PIXHAWK autopilot, http://pixhawk.ethz.ch - MAV_CLASS_SLUGS = 2, ///< SLUGS autopilot, http://slugsuav.soe.ucsc.edu - MAV_CLASS_ARDUPILOTMEGA = 3, ///< ArduPilotMega / ArduCopter, http://diydrones.com - MAV_CLASS_OPENPILOT = 4, ///< OpenPilot, http://openpilot.org - MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5, ///< Generic autopilot only supporting simple waypoints - MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, ///< Generic autopilot supporting waypoints and other simple navigation commands - MAV_CLASS_GENERIC_MISSION_FULL = 7, ///< Generic autopilot supporting the full mission command set - MAV_CLASS_NONE = 8, ///< No valid autopilot - MAV_CLASS_NB ///< Number of autopilot classes -}; - -enum MAV_ACTION -{ - MAV_ACTION_HOLD = 0, - MAV_ACTION_MOTORS_START = 1, - MAV_ACTION_LAUNCH = 2, - MAV_ACTION_RETURN = 3, - MAV_ACTION_EMCY_LAND = 4, - MAV_ACTION_EMCY_KILL = 5, - MAV_ACTION_CONFIRM_KILL = 6, - MAV_ACTION_CONTINUE = 7, - MAV_ACTION_MOTORS_STOP = 8, - MAV_ACTION_HALT = 9, - MAV_ACTION_SHUTDOWN = 10, - MAV_ACTION_REBOOT = 11, - MAV_ACTION_SET_MANUAL = 12, - MAV_ACTION_SET_AUTO = 13, - MAV_ACTION_STORAGE_READ = 14, - MAV_ACTION_STORAGE_WRITE = 15, - MAV_ACTION_CALIBRATE_RC = 16, - MAV_ACTION_CALIBRATE_GYRO = 17, - MAV_ACTION_CALIBRATE_MAG = 18, - MAV_ACTION_CALIBRATE_ACC = 19, - MAV_ACTION_CALIBRATE_PRESSURE = 20, - MAV_ACTION_REC_START = 21, - MAV_ACTION_REC_PAUSE = 22, - MAV_ACTION_REC_STOP = 23, - MAV_ACTION_TAKEOFF = 24, - MAV_ACTION_NAVIGATE = 25, - MAV_ACTION_LAND = 26, - MAV_ACTION_LOITER = 27, - MAV_ACTION_SET_ORIGIN = 28, - MAV_ACTION_RELAY_ON = 29, - MAV_ACTION_RELAY_OFF = 30, - MAV_ACTION_GET_IMAGE = 31, - MAV_ACTION_VIDEO_START = 32, - MAV_ACTION_VIDEO_STOP = 33, - MAV_ACTION_RESET_MAP = 34, - MAV_ACTION_RESET_PLAN = 35, - MAV_ACTION_DELAY_BEFORE_COMMAND = 36, - MAV_ACTION_ASCEND_AT_RATE = 37, - MAV_ACTION_CHANGE_MODE = 38, - MAV_ACTION_LOITER_MAX_TURNS = 39, - MAV_ACTION_LOITER_MAX_TIME = 40, - MAV_ACTION_START_HILSIM = 41, - MAV_ACTION_STOP_HILSIM = 42, - MAV_ACTION_NB ///< Number of MAV actions -}; - -enum MAV_MODE -{ - MAV_MODE_UNINIT = 0, ///< System is in undefined state - MAV_MODE_LOCKED = 1, ///< Motors are blocked, system is safe - MAV_MODE_MANUAL = 2, ///< System is allowed to be active, under manual (RC) control - MAV_MODE_GUIDED = 3, ///< System is allowed to be active, under autonomous control, manual setpoint - MAV_MODE_AUTO = 4, ///< System is allowed to be active, under autonomous control and navigation - MAV_MODE_TEST1 = 5, ///< Generic test mode, for custom use - MAV_MODE_TEST2 = 6, ///< Generic test mode, for custom use - MAV_MODE_TEST3 = 7, ///< Generic test mode, for custom use - MAV_MODE_READY = 8, ///< System is ready, motors are unblocked, but controllers are inactive - MAV_MODE_RC_TRAINING = 9 ///< System is blocked, only RC valued are read and reported back -}; - -enum MAV_STATE -{ - MAV_STATE_UNINIT = 0, - MAV_STATE_BOOT, - MAV_STATE_CALIBRATING, - MAV_STATE_STANDBY, - MAV_STATE_ACTIVE, - MAV_STATE_CRITICAL, - MAV_STATE_EMERGENCY, - MAV_STATE_HILSIM, - MAV_STATE_POWEROFF -}; - -enum MAV_NAV -{ - MAV_NAV_GROUNDED = 0, - MAV_NAV_LIFTOFF, - MAV_NAV_HOLD, - MAV_NAV_WAYPOINT, - MAV_NAV_VECTOR, - MAV_NAV_RETURNING, - MAV_NAV_LANDING, - MAV_NAV_LOST, - MAV_NAV_LOITER, - MAV_NAV_FREE_DRIFT -}; - -enum MAV_TYPE -{ - MAV_GENERIC = 0, - MAV_FIXED_WING = 1, - MAV_QUADROTOR = 2, - MAV_COAXIAL = 3, - MAV_HELICOPTER = 4, - MAV_GROUND = 5, - OCU = 6, - MAV_AIRSHIP = 7, - MAV_FREE_BALLOON = 8, - MAV_ROCKET = 9, - UGV_GROUND_ROVER = 10, - UGV_SURFACE_SHIP = 11 -}; - -enum MAV_AUTOPILOT_TYPE -{ - MAV_AUTOPILOT_GENERIC = 0, - MAV_AUTOPILOT_PIXHAWK = 1, - MAV_AUTOPILOT_SLUGS = 2, - MAV_AUTOPILOT_ARDUPILOTMEGA = 3, - MAV_AUTOPILOT_NONE = 4 -}; - -enum MAV_COMPONENT -{ - MAV_COMP_ID_GPS, - MAV_COMP_ID_WAYPOINTPLANNER, - MAV_COMP_ID_BLOBTRACKER, - MAV_COMP_ID_PATHPLANNER, - MAV_COMP_ID_AIRSLAM, - MAV_COMP_ID_MAPPER, - MAV_COMP_ID_CAMERA, - MAV_COMP_ID_IMU = 200, - MAV_COMP_ID_IMU_2 = 201, - MAV_COMP_ID_IMU_3 = 202, - MAV_COMP_ID_UDP_BRIDGE = 240, - MAV_COMP_ID_UART_BRIDGE = 241, - MAV_COMP_ID_SYSTEM_CONTROL = 250 -}; - -enum MAV_FRAME -{ - MAV_FRAME_GLOBAL = 0, - MAV_FRAME_LOCAL = 1, - MAV_FRAME_MISSION = 2, - MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, - MAV_FRAME_LOCAL_ENU = 4 -}; - -enum MAVLINK_DATA_STREAM_TYPE -{ - MAVLINK_DATA_STREAM_IMG_JPEG, - MAVLINK_DATA_STREAM_IMG_BMP, - MAVLINK_DATA_STREAM_IMG_RAW8U, - MAVLINK_DATA_STREAM_IMG_RAW32U, - MAVLINK_DATA_STREAM_IMG_PGM, - MAVLINK_DATA_STREAM_IMG_PNG -}; - -#ifndef MAVLINK_MAX_PAYLOAD_LEN -// it is possible to override this, but be careful! -#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length -#endif - -#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte) -#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum -#define MAVLINK_NUM_CHECKSUM_BYTES 2 -#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES) - -#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length - -typedef struct param_union { - union { - float param_float; - int32_t param_int32; - uint32_t param_uint32; - }; - uint8_t type; -} mavlink_param_union_t; - -typedef struct __mavlink_system { - uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function - uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function - uint8_t type; ///< Unused, can be used by user to store the system's type - uint8_t state; ///< Unused, can be used by user to store the system's state - uint8_t mode; ///< Unused, can be used by user to store the system's mode - uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode -} mavlink_system_t; - -typedef struct __mavlink_message { - uint16_t checksum; /// sent at end of packet - uint8_t magic; ///< protocol magic marker - uint8_t len; ///< Length of payload - uint8_t seq; ///< Sequence of packet - uint8_t sysid; ///< ID of message sender system/aircraft - uint8_t compid; ///< ID of the message sender component - uint8_t msgid; ///< ID of message in payload - uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; -} mavlink_message_t; - -typedef enum { - MAVLINK_TYPE_CHAR = 0, - MAVLINK_TYPE_UINT8_T = 1, - MAVLINK_TYPE_INT8_T = 2, - MAVLINK_TYPE_UINT16_T = 3, - MAVLINK_TYPE_INT16_T = 4, - MAVLINK_TYPE_UINT32_T = 5, - MAVLINK_TYPE_INT32_T = 6, - MAVLINK_TYPE_UINT64_T = 7, - MAVLINK_TYPE_INT64_T = 8, - MAVLINK_TYPE_FLOAT = 9, - MAVLINK_TYPE_DOUBLE = 10 -} mavlink_message_type_t; - -#define MAVLINK_MAX_FIELDS 64 - -typedef struct __mavlink_field_info { - const char *name; // name of this field - const char *print_format; // printing format hint, or NULL - mavlink_message_type_t type; // type of this field - unsigned array_length; // if non-zero, field is an array - unsigned wire_offset; // offset of each field in the payload - unsigned structure_offset; // offset in a C structure -} mavlink_field_info_t; - -// note that in this structure the order of fields is the order -// in the XML file, not necessary the wire order -typedef struct __mavlink_message_info { - const char *name; // name of the message - unsigned num_fields; // how many fields in this message - mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information -} mavlink_message_info_t; - -#define _MAV_PAYLOAD(msg) ((char *)(&(msg)->payload64[0])) - -// checksum is immediately after the payload bytes -#define mavlink_ck_a(msg) *(msg->len + (uint8_t *)_MAV_PAYLOAD(msg)) -#define mavlink_ck_b(msg) *((msg->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD(msg)) - -typedef enum { - MAVLINK_COMM_0, - MAVLINK_COMM_1, - MAVLINK_COMM_2, - MAVLINK_COMM_3 -} mavlink_channel_t; - -/* - * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number - * of buffers they will use. If more are used, then the result will be - * a stack overrun - */ -#ifndef MAVLINK_COMM_NUM_BUFFERS -#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) -# define MAVLINK_COMM_NUM_BUFFERS 16 -#else -# define MAVLINK_COMM_NUM_BUFFERS 4 -#endif -#endif - -typedef enum { - MAVLINK_PARSE_STATE_UNINIT=0, - MAVLINK_PARSE_STATE_IDLE, - MAVLINK_PARSE_STATE_GOT_STX, - MAVLINK_PARSE_STATE_GOT_SEQ, - MAVLINK_PARSE_STATE_GOT_LENGTH, - MAVLINK_PARSE_STATE_GOT_SYSID, - MAVLINK_PARSE_STATE_GOT_COMPID, - MAVLINK_PARSE_STATE_GOT_MSGID, - MAVLINK_PARSE_STATE_GOT_PAYLOAD, - MAVLINK_PARSE_STATE_GOT_CRC1 -} mavlink_parse_state_t; ///< The state machine for the comm parser - -typedef struct __mavlink_status { - uint8_t msg_received; ///< Number of received messages - uint8_t buffer_overrun; ///< Number of buffer overruns - uint8_t parse_error; ///< Number of parse errors - mavlink_parse_state_t parse_state; ///< Parsing state machine - uint8_t packet_idx; ///< Index in current packet - uint8_t current_rx_seq; ///< Sequence number of last packet received - uint8_t current_tx_seq; ///< Sequence number of last packet sent - uint16_t packet_rx_success_count; ///< Received packets - uint16_t packet_rx_drop_count; ///< Number of packet drops -} mavlink_status_t; - -#define MAVLINK_BIG_ENDIAN 0 -#define MAVLINK_LITTLE_ENDIAN 1 - -#endif /* MAVLINK_TYPES_H_ */ diff --git a/mavlink/include/v0.9/minimal/minimal.h b/mavlink/include/v0.9/minimal/minimal.h deleted file mode 100644 index c70668bca540635df16322b7ad9e445a57248ca1..0000000000000000000000000000000000000000 --- a/mavlink/include/v0.9/minimal/minimal.h +++ /dev/null @@ -1,53 +0,0 @@ -/** @file - * @brief MAVLink comm protocol generated from minimal.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef MINIMAL_H -#define MINIMAL_H - -#ifdef __cplusplus -extern "C" { -#endif - -// MESSAGE LENGTHS AND CRCS - -#ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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 {72, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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_HEARTBEAT, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {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_MINIMAL - - - -// MAVLINK VERSION - -#ifndef MAVLINK_VERSION -#define MAVLINK_VERSION 2 -#endif - -#if (MAVLINK_VERSION == 0) -#undef MAVLINK_VERSION -#define MAVLINK_VERSION 2 -#endif - -// ENUM DEFINITIONS - - - -// MESSAGE DEFINITIONS -#include "./mavlink_msg_heartbeat.h" - -#ifdef __cplusplus -} -#endif // __cplusplus -#endif // MINIMAL_H diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_position_control_offset_set.h b/mavlink/include/v0.9/pixhawk/mavlink_msg_position_control_offset_set.h deleted file mode 100644 index 2d5f400e44ddeca6c8f686a7a981f6836773c543..0000000000000000000000000000000000000000 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_position_control_offset_set.h +++ /dev/null @@ -1,254 +0,0 @@ -// MESSAGE POSITION_CONTROL_OFFSET_SET PACKING - -#define MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET 160 - -typedef struct __mavlink_position_control_offset_set_t -{ - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - float x; ///< x position offset - float y; ///< y position offset - float z; ///< z position offset - float yaw; ///< yaw orientation offset in radians, 0 = NORTH -} mavlink_position_control_offset_set_t; - -#define MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET_LEN 18 -#define MAVLINK_MSG_ID_160_LEN 18 - - - -#define MAVLINK_MESSAGE_INFO_POSITION_CONTROL_OFFSET_SET { \ - "POSITION_CONTROL_OFFSET_SET", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_position_control_offset_set_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_position_control_offset_set_t, target_component) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 2, offsetof(mavlink_position_control_offset_set_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_position_control_offset_set_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_position_control_offset_set_t, z) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_position_control_offset_set_t, yaw) }, \ - } \ -} - - -/** - * @brief Pack a position_control_offset_set 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 target_system System ID - * @param target_component Component ID - * @param x x position offset - * @param y y position offset - * @param z z position offset - * @param yaw yaw orientation offset in radians, 0 = NORTH - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_position_control_offset_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_float(buf, 2, x); - _mav_put_float(buf, 6, y); - _mav_put_float(buf, 10, z); - _mav_put_float(buf, 14, yaw); - - memcpy(_MAV_PAYLOAD(msg), buf, 18); -#else - mavlink_position_control_offset_set_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.x = x; - packet.y = y; - packet.z = z; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD(msg), &packet, 18); -#endif - - msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET; - return mavlink_finalize_message(msg, system_id, component_id, 18); -} - -/** - * @brief Pack a position_control_offset_set 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 target_system System ID - * @param target_component Component ID - * @param x x position offset - * @param y y position offset - * @param z z position offset - * @param yaw yaw orientation offset in radians, 0 = NORTH - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_position_control_offset_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,float x,float y,float z,float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_float(buf, 2, x); - _mav_put_float(buf, 6, y); - _mav_put_float(buf, 10, z); - _mav_put_float(buf, 14, yaw); - - memcpy(_MAV_PAYLOAD(msg), buf, 18); -#else - mavlink_position_control_offset_set_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.x = x; - packet.y = y; - packet.z = z; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD(msg), &packet, 18); -#endif - - msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18); -} - -/** - * @brief Encode a position_control_offset_set 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 position_control_offset_set C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_position_control_offset_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_offset_set_t* position_control_offset_set) -{ - return mavlink_msg_position_control_offset_set_pack(system_id, component_id, msg, position_control_offset_set->target_system, position_control_offset_set->target_component, position_control_offset_set->x, position_control_offset_set->y, position_control_offset_set->z, position_control_offset_set->yaw); -} - -/** - * @brief Send a position_control_offset_set message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param x x position offset - * @param y y position offset - * @param z z position offset - * @param yaw yaw orientation offset in radians, 0 = NORTH - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_position_control_offset_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[18]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_float(buf, 2, x); - _mav_put_float(buf, 6, y); - _mav_put_float(buf, 10, z); - _mav_put_float(buf, 14, yaw); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET, buf, 18); -#else - mavlink_position_control_offset_set_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.x = x; - packet.y = y; - packet.z = z; - packet.yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET, (const char *)&packet, 18); -#endif -} - -#endif - -// MESSAGE POSITION_CONTROL_OFFSET_SET UNPACKING - - -/** - * @brief Get field target_system from position_control_offset_set message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_position_control_offset_set_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from position_control_offset_set message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_position_control_offset_set_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field x from position_control_offset_set message - * - * @return x position offset - */ -static inline float mavlink_msg_position_control_offset_set_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 2); -} - -/** - * @brief Get field y from position_control_offset_set message - * - * @return y position offset - */ -static inline float mavlink_msg_position_control_offset_set_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 6); -} - -/** - * @brief Get field z from position_control_offset_set message - * - * @return z position offset - */ -static inline float mavlink_msg_position_control_offset_set_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 10); -} - -/** - * @brief Get field yaw from position_control_offset_set message - * - * @return yaw orientation offset in radians, 0 = NORTH - */ -static inline float mavlink_msg_position_control_offset_set_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 14); -} - -/** - * @brief Decode a position_control_offset_set message into a struct - * - * @param msg The message to decode - * @param position_control_offset_set C-struct to decode the message contents into - */ -static inline void mavlink_msg_position_control_offset_set_decode(const mavlink_message_t* msg, mavlink_position_control_offset_set_t* position_control_offset_set) -{ -#if MAVLINK_NEED_BYTE_SWAP - position_control_offset_set->target_system = mavlink_msg_position_control_offset_set_get_target_system(msg); - position_control_offset_set->target_component = mavlink_msg_position_control_offset_set_get_target_component(msg); - position_control_offset_set->x = mavlink_msg_position_control_offset_set_get_x(msg); - position_control_offset_set->y = mavlink_msg_position_control_offset_set_get_y(msg); - position_control_offset_set->z = mavlink_msg_position_control_offset_set_get_z(msg); - position_control_offset_set->yaw = mavlink_msg_position_control_offset_set_get_yaw(msg); -#else - memcpy(position_control_offset_set, _MAV_PAYLOAD(msg), 18); -#endif -} diff --git a/mavlink/include/v0.9/pixhawk/mavlink_msg_position_control_setpoint_set.h b/mavlink/include/v0.9/pixhawk/mavlink_msg_position_control_setpoint_set.h deleted file mode 100644 index e2369202732b181cddd4c8f4a249ffa0b89d3471..0000000000000000000000000000000000000000 --- a/mavlink/include/v0.9/pixhawk/mavlink_msg_position_control_setpoint_set.h +++ /dev/null @@ -1,276 +0,0 @@ -// MESSAGE POSITION_CONTROL_SETPOINT_SET PACKING - -#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET 159 - -typedef struct __mavlink_position_control_setpoint_set_t -{ - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - uint16_t id; ///< ID of waypoint, 0 for plain position - float x; ///< x position - float y; ///< y position - float z; ///< z position - float yaw; ///< yaw orientation in radians, 0 = NORTH -} mavlink_position_control_setpoint_set_t; - -#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET_LEN 20 -#define MAVLINK_MSG_ID_159_LEN 20 - - - -#define MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT_SET { \ - "POSITION_CONTROL_SETPOINT_SET", \ - 7, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_position_control_setpoint_set_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_position_control_setpoint_set_t, target_component) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_position_control_setpoint_set_t, id) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_control_setpoint_set_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_control_setpoint_set_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_control_setpoint_set_t, z) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_control_setpoint_set_t, yaw) }, \ - } \ -} - - -/** - * @brief Pack a position_control_setpoint_set 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 target_system System ID - * @param target_component Component ID - * @param id ID of waypoint, 0 for plain position - * @param x x position - * @param y y position - * @param z z position - * @param yaw yaw orientation in radians, 0 = NORTH - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_position_control_setpoint_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t id, float x, float y, float z, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint16_t(buf, 2, id); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, yaw); - - memcpy(_MAV_PAYLOAD(msg), buf, 20); -#else - mavlink_position_control_setpoint_set_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.id = id; - packet.x = x; - packet.y = y; - packet.z = z; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD(msg), &packet, 20); -#endif - - msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET; - return mavlink_finalize_message(msg, system_id, component_id, 20); -} - -/** - * @brief Pack a position_control_setpoint_set 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 target_system System ID - * @param target_component Component ID - * @param id ID of waypoint, 0 for plain position - * @param x x position - * @param y y position - * @param z z position - * @param yaw yaw orientation in radians, 0 = NORTH - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_position_control_setpoint_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t id,float x,float y,float z,float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint16_t(buf, 2, id); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, yaw); - - memcpy(_MAV_PAYLOAD(msg), buf, 20); -#else - mavlink_position_control_setpoint_set_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.id = id; - packet.x = x; - packet.y = y; - packet.z = z; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD(msg), &packet, 20); -#endif - - msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20); -} - -/** - * @brief Encode a position_control_setpoint_set 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 position_control_setpoint_set C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_position_control_setpoint_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_setpoint_set_t* position_control_setpoint_set) -{ - return mavlink_msg_position_control_setpoint_set_pack(system_id, component_id, msg, position_control_setpoint_set->target_system, position_control_setpoint_set->target_component, position_control_setpoint_set->id, position_control_setpoint_set->x, position_control_setpoint_set->y, position_control_setpoint_set->z, position_control_setpoint_set->yaw); -} - -/** - * @brief Send a position_control_setpoint_set message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param id ID of waypoint, 0 for plain position - * @param x x position - * @param y y position - * @param z z position - * @param yaw yaw orientation in radians, 0 = NORTH - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_position_control_setpoint_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, float x, float y, float z, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[20]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint16_t(buf, 2, id); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, yaw); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET, buf, 20); -#else - mavlink_position_control_setpoint_set_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.id = id; - packet.x = x; - packet.y = y; - packet.z = z; - packet.yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET, (const char *)&packet, 20); -#endif -} - -#endif - -// MESSAGE POSITION_CONTROL_SETPOINT_SET UNPACKING - - -/** - * @brief Get field target_system from position_control_setpoint_set message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_position_control_setpoint_set_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from position_control_setpoint_set message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_position_control_setpoint_set_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field id from position_control_setpoint_set message - * - * @return ID of waypoint, 0 for plain position - */ -static inline uint16_t mavlink_msg_position_control_setpoint_set_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field x from position_control_setpoint_set message - * - * @return x position - */ -static inline float mavlink_msg_position_control_setpoint_set_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field y from position_control_setpoint_set message - * - * @return y position - */ -static inline float mavlink_msg_position_control_setpoint_set_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field z from position_control_setpoint_set message - * - * @return z position - */ -static inline float mavlink_msg_position_control_setpoint_set_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field yaw from position_control_setpoint_set message - * - * @return yaw orientation in radians, 0 = NORTH - */ -static inline float mavlink_msg_position_control_setpoint_set_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a position_control_setpoint_set message into a struct - * - * @param msg The message to decode - * @param position_control_setpoint_set C-struct to decode the message contents into - */ -static inline void mavlink_msg_position_control_setpoint_set_decode(const mavlink_message_t* msg, mavlink_position_control_setpoint_set_t* position_control_setpoint_set) -{ -#if MAVLINK_NEED_BYTE_SWAP - position_control_setpoint_set->target_system = mavlink_msg_position_control_setpoint_set_get_target_system(msg); - position_control_setpoint_set->target_component = mavlink_msg_position_control_setpoint_set_get_target_component(msg); - position_control_setpoint_set->id = mavlink_msg_position_control_setpoint_set_get_id(msg); - position_control_setpoint_set->x = mavlink_msg_position_control_setpoint_set_get_x(msg); - position_control_setpoint_set->y = mavlink_msg_position_control_setpoint_set_get_y(msg); - position_control_setpoint_set->z = mavlink_msg_position_control_setpoint_set_get_z(msg); - position_control_setpoint_set->yaw = mavlink_msg_position_control_setpoint_set_get_yaw(msg); -#else - memcpy(position_control_setpoint_set, _MAV_PAYLOAD(msg), 20); -#endif -} diff --git a/mavlink/include/v0.9/pixhawk/pixhawk.h b/mavlink/include/v0.9/pixhawk/pixhawk.h deleted file mode 100644 index 0500695e17572cd75b1b847320510e456d200f44..0000000000000000000000000000000000000000 --- a/mavlink/include/v0.9/pixhawk/pixhawk.h +++ /dev/null @@ -1,86 +0,0 @@ -/** @file - * @brief MAVLink comm protocol generated from pixhawk.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef PIXHAWK_H -#define PIXHAWK_H - -#ifdef __cplusplus -extern "C" { -#endif - -// MESSAGE LENGTHS AND CRCS - -#ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 11, 52, 1, 92, 0, 32, 32, 20, 20, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 26, 16, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 0, 0, 0, 0, 0, 0, 106, 43, 55, 8, 255, 53, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5} -#endif - -#ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 86, 95, 49, 0, 158, 56, 208, 218, 115, 0, 0, 0, 0, 0, 0, 0, 0, 0, 220, 136, 140, 0, 0, 0, 0, 0, 0, 0, 153, 110, 92, 188, 0, 0, 0, 0, 0, 0, 106, 154, 83, 98, 223, 254, 0, 0, 0, 0, 84, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7} -#endif - -#ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_BOOT, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, MAVLINK_MESSAGE_INFO_ACTION_ACK, MAVLINK_MESSAGE_INFO_ACTION, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_SET_NAV_MODE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, {NULL}, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_LOCAL_POSITION, MAVLINK_MESSAGE_INFO_GPS_RAW, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_WAYPOINT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST, MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT, MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL, MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED, MAVLINK_MESSAGE_INFO_WAYPOINT_ACK, MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_CONTROL_STATUS, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_POSITION_TARGET, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_SET_ALTITUDE, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SET_CAM_SHUTTER, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGERED, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGER_CONTROL, MAVLINK_MESSAGE_INFO_IMAGE_AVAILABLE, {NULL}, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT_SET, MAVLINK_MESSAGE_INFO_POSITION_CONTROL_OFFSET_SET, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT, MAVLINK_MESSAGE_INFO_MARKER, MAVLINK_MESSAGE_INFO_RAW_AUX, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_WATCHDOG_HEARTBEAT, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_INFO, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS, MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PATTERN_DETECTED, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST_CONNECTION, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_BRIEF_FEATURE, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_ATTITUDE_CONTROL, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG} -#endif - -#include "../protocol.h" - -#define MAVLINK_ENABLED_PIXHAWK - -#include "../common/common.h" - -// MAVLINK VERSION - -#ifndef MAVLINK_VERSION -#define MAVLINK_VERSION 2 -#endif - -#if (MAVLINK_VERSION == 0) -#undef MAVLINK_VERSION -#define MAVLINK_VERSION 2 -#endif - -// ENUM DEFINITIONS - - -/** @brief Content Types for data transmission handshake */ -#ifndef HAVE_ENUM_DATA_TYPES -#define HAVE_ENUM_DATA_TYPES -enum DATA_TYPES -{ - DATA_TYPE_JPEG_IMAGE=1, /* | */ - DATA_TYPE_RAW_IMAGE=2, /* | */ - DATA_TYPE_KINECT=3, /* | */ - DATA_TYPES_ENUM_END=4, /* | */ -}; -#endif - -// MESSAGE DEFINITIONS -#include "./mavlink_msg_set_cam_shutter.h" -#include "./mavlink_msg_image_triggered.h" -#include "./mavlink_msg_image_trigger_control.h" -#include "./mavlink_msg_image_available.h" -#include "./mavlink_msg_vision_position_estimate.h" -#include "./mavlink_msg_vicon_position_estimate.h" -#include "./mavlink_msg_vision_speed_estimate.h" -#include "./mavlink_msg_position_control_setpoint_set.h" -#include "./mavlink_msg_position_control_offset_set.h" -#include "./mavlink_msg_position_control_setpoint.h" -#include "./mavlink_msg_marker.h" -#include "./mavlink_msg_raw_aux.h" -#include "./mavlink_msg_watchdog_heartbeat.h" -#include "./mavlink_msg_watchdog_process_info.h" -#include "./mavlink_msg_watchdog_process_status.h" -#include "./mavlink_msg_watchdog_command.h" -#include "./mavlink_msg_pattern_detected.h" -#include "./mavlink_msg_point_of_interest.h" -#include "./mavlink_msg_point_of_interest_connection.h" -#include "./mavlink_msg_data_transmission_handshake.h" -#include "./mavlink_msg_encapsulated_data.h" -#include "./mavlink_msg_brief_feature.h" -#include "./mavlink_msg_attitude_control.h" - -#ifdef __cplusplus -} -#endif // __cplusplus -#endif // PIXHAWK_H diff --git a/mavlink/include/v0.9/protocol.h b/mavlink/include/v0.9/protocol.h deleted file mode 100644 index 05195c36919d04a5bf50c9799ee724af011a20f0..0000000000000000000000000000000000000000 --- a/mavlink/include/v0.9/protocol.h +++ /dev/null @@ -1,319 +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; imsgid = MAVLINK_MSG_ID_AHRS; + return mavlink_finalize_message(msg, system_id, component_id, 28, 127); +} + +/** + * @brief Pack a ahrs 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 omegaIx X gyro drift estimate rad/s + * @param omegaIy Y gyro drift estimate rad/s + * @param omegaIz Z gyro drift estimate rad/s + * @param accel_weight average accel_weight + * @param renorm_val average renormalisation value + * @param error_rp average error_roll_pitch value + * @param error_yaw average error_yaw value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ahrs_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float omegaIx,float omegaIy,float omegaIz,float accel_weight,float renorm_val,float error_rp,float error_yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_float(buf, 0, omegaIx); + _mav_put_float(buf, 4, omegaIy); + _mav_put_float(buf, 8, omegaIz); + _mav_put_float(buf, 12, accel_weight); + _mav_put_float(buf, 16, renorm_val); + _mav_put_float(buf, 20, error_rp); + _mav_put_float(buf, 24, error_yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28); +#else + mavlink_ahrs_t packet; + packet.omegaIx = omegaIx; + packet.omegaIy = omegaIy; + packet.omegaIz = omegaIz; + packet.accel_weight = accel_weight; + packet.renorm_val = renorm_val; + packet.error_rp = error_rp; + packet.error_yaw = error_yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_AHRS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 127); +} + +/** + * @brief Encode a ahrs 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 ahrs C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_ahrs_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ahrs_t* ahrs) +{ + return mavlink_msg_ahrs_pack(system_id, component_id, msg, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw); +} + +/** + * @brief Send a ahrs message + * @param chan MAVLink channel to send the message + * + * @param omegaIx X gyro drift estimate rad/s + * @param omegaIy Y gyro drift estimate rad/s + * @param omegaIz Z gyro drift estimate rad/s + * @param accel_weight average accel_weight + * @param renorm_val average renormalisation value + * @param error_rp average error_roll_pitch value + * @param error_yaw average error_yaw value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_ahrs_send(mavlink_channel_t chan, float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_float(buf, 0, omegaIx); + _mav_put_float(buf, 4, omegaIy); + _mav_put_float(buf, 8, omegaIz); + _mav_put_float(buf, 12, accel_weight); + _mav_put_float(buf, 16, renorm_val); + _mav_put_float(buf, 20, error_rp); + _mav_put_float(buf, 24, error_yaw); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, 28, 127); +#else + mavlink_ahrs_t packet; + packet.omegaIx = omegaIx; + packet.omegaIy = omegaIy; + packet.omegaIz = omegaIz; + packet.accel_weight = accel_weight; + packet.renorm_val = renorm_val; + packet.error_rp = error_rp; + packet.error_yaw = error_yaw; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)&packet, 28, 127); +#endif +} + +#endif + +// MESSAGE AHRS UNPACKING + + +/** + * @brief Get field omegaIx from ahrs message + * + * @return X gyro drift estimate rad/s + */ +static inline float mavlink_msg_ahrs_get_omegaIx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field omegaIy from ahrs message + * + * @return Y gyro drift estimate rad/s + */ +static inline float mavlink_msg_ahrs_get_omegaIy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field omegaIz from ahrs message + * + * @return Z gyro drift estimate rad/s + */ +static inline float mavlink_msg_ahrs_get_omegaIz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field accel_weight from ahrs message + * + * @return average accel_weight + */ +static inline float mavlink_msg_ahrs_get_accel_weight(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field renorm_val from ahrs message + * + * @return average renormalisation value + */ +static inline float mavlink_msg_ahrs_get_renorm_val(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field error_rp from ahrs message + * + * @return average error_roll_pitch value + */ +static inline float mavlink_msg_ahrs_get_error_rp(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field error_yaw from ahrs message + * + * @return average error_yaw value + */ +static inline float mavlink_msg_ahrs_get_error_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a ahrs message into a struct + * + * @param msg The message to decode + * @param ahrs C-struct to decode the message contents into + */ +static inline void mavlink_msg_ahrs_decode(const mavlink_message_t* msg, mavlink_ahrs_t* ahrs) +{ +#if MAVLINK_NEED_BYTE_SWAP + ahrs->omegaIx = mavlink_msg_ahrs_get_omegaIx(msg); + ahrs->omegaIy = mavlink_msg_ahrs_get_omegaIy(msg); + ahrs->omegaIz = mavlink_msg_ahrs_get_omegaIz(msg); + ahrs->accel_weight = mavlink_msg_ahrs_get_accel_weight(msg); + ahrs->renorm_val = mavlink_msg_ahrs_get_renorm_val(msg); + ahrs->error_rp = mavlink_msg_ahrs_get_error_rp(msg); + ahrs->error_yaw = mavlink_msg_ahrs_get_error_yaw(msg); +#else + memcpy(ahrs, _MAV_PAYLOAD(msg), 28); +#endif +} diff --git a/mavlink/include/v1.0/ardupilotmega/mavlink_msg_hwstatus.h b/mavlink/include/v1.0/ardupilotmega/mavlink_msg_hwstatus.h new file mode 100644 index 0000000000000000000000000000000000000000..952e65951be20ef7f2f4c3efde64251f672107b1 --- /dev/null +++ b/mavlink/include/v1.0/ardupilotmega/mavlink_msg_hwstatus.h @@ -0,0 +1,166 @@ +// MESSAGE HWSTATUS PACKING + +#define MAVLINK_MSG_ID_HWSTATUS 165 + +typedef struct __mavlink_hwstatus_t +{ + uint16_t Vcc; ///< board voltage (mV) + uint8_t I2Cerr; ///< I2C error count +} mavlink_hwstatus_t; + +#define MAVLINK_MSG_ID_HWSTATUS_LEN 3 +#define MAVLINK_MSG_ID_165_LEN 3 + + + +#define MAVLINK_MESSAGE_INFO_HWSTATUS { \ + "HWSTATUS", \ + 2, \ + { { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_hwstatus_t, Vcc) }, \ + { "I2Cerr", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_hwstatus_t, I2Cerr) }, \ + } \ +} + + +/** + * @brief Pack a hwstatus 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 Vcc board voltage (mV) + * @param I2Cerr I2C error count + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hwstatus_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t Vcc, uint8_t I2Cerr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint16_t(buf, 0, Vcc); + _mav_put_uint8_t(buf, 2, I2Cerr); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); +#else + mavlink_hwstatus_t packet; + packet.Vcc = Vcc; + packet.I2Cerr = I2Cerr; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_HWSTATUS; + return mavlink_finalize_message(msg, system_id, component_id, 3, 21); +} + +/** + * @brief Pack a hwstatus 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 Vcc board voltage (mV) + * @param I2Cerr I2C error count + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hwstatus_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t Vcc,uint8_t I2Cerr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint16_t(buf, 0, Vcc); + _mav_put_uint8_t(buf, 2, I2Cerr); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3); +#else + mavlink_hwstatus_t packet; + packet.Vcc = Vcc; + packet.I2Cerr = I2Cerr; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_HWSTATUS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 21); +} + +/** + * @brief Encode a hwstatus 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 hwstatus C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hwstatus_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hwstatus_t* hwstatus) +{ + return mavlink_msg_hwstatus_pack(system_id, component_id, msg, hwstatus->Vcc, hwstatus->I2Cerr); +} + +/** + * @brief Send a hwstatus message + * @param chan MAVLink channel to send the message + * + * @param Vcc board voltage (mV) + * @param I2Cerr I2C error count + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hwstatus_send(mavlink_channel_t chan, uint16_t Vcc, uint8_t I2Cerr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint16_t(buf, 0, Vcc); + _mav_put_uint8_t(buf, 2, I2Cerr); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, buf, 3, 21); +#else + mavlink_hwstatus_t packet; + packet.Vcc = Vcc; + packet.I2Cerr = I2Cerr; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)&packet, 3, 21); +#endif +} + +#endif + +// MESSAGE HWSTATUS UNPACKING + + +/** + * @brief Get field Vcc from hwstatus message + * + * @return board voltage (mV) + */ +static inline uint16_t mavlink_msg_hwstatus_get_Vcc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field I2Cerr from hwstatus message + * + * @return I2C error count + */ +static inline uint8_t mavlink_msg_hwstatus_get_I2Cerr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Decode a hwstatus message into a struct + * + * @param msg The message to decode + * @param hwstatus C-struct to decode the message contents into + */ +static inline void mavlink_msg_hwstatus_decode(const mavlink_message_t* msg, mavlink_hwstatus_t* hwstatus) +{ +#if MAVLINK_NEED_BYTE_SWAP + hwstatus->Vcc = mavlink_msg_hwstatus_get_Vcc(msg); + hwstatus->I2Cerr = mavlink_msg_hwstatus_get_I2Cerr(msg); +#else + memcpy(hwstatus, _MAV_PAYLOAD(msg), 3); +#endif +} diff --git a/mavlink/include/v1.0/ardupilotmega/mavlink_msg_radio.h b/mavlink/include/v1.0/ardupilotmega/mavlink_msg_radio.h new file mode 100644 index 0000000000000000000000000000000000000000..0f3d03c0a64a8f08711f8a9dfc1d9976c05d9804 --- /dev/null +++ b/mavlink/include/v1.0/ardupilotmega/mavlink_msg_radio.h @@ -0,0 +1,276 @@ +// MESSAGE RADIO PACKING + +#define MAVLINK_MSG_ID_RADIO 166 + +typedef struct __mavlink_radio_t +{ + uint16_t rxerrors; ///< receive errors + uint16_t fixed; ///< count of error corrected packets + uint8_t rssi; ///< local signal strength + uint8_t remrssi; ///< remote signal strength + uint8_t txbuf; ///< how full the tx buffer is as a percentage + uint8_t noise; ///< background noise level + uint8_t remnoise; ///< remote background noise level +} mavlink_radio_t; + +#define MAVLINK_MSG_ID_RADIO_LEN 9 +#define MAVLINK_MSG_ID_166_LEN 9 + + + +#define MAVLINK_MESSAGE_INFO_RADIO { \ + "RADIO", \ + 7, \ + { { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_t, rxerrors) }, \ + { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_t, fixed) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_t, rssi) }, \ + { "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_t, remrssi) }, \ + { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_t, txbuf) }, \ + { "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_t, noise) }, \ + { "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_t, remnoise) }, \ + } \ +} + + +/** + * @brief Pack a radio 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 rssi local signal strength + * @param remrssi remote signal strength + * @param txbuf how full the tx buffer is as a percentage + * @param noise background noise level + * @param remnoise remote background noise level + * @param rxerrors receive errors + * @param fixed count of error corrected packets + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint16_t(buf, 0, rxerrors); + _mav_put_uint16_t(buf, 2, fixed); + _mav_put_uint8_t(buf, 4, rssi); + _mav_put_uint8_t(buf, 5, remrssi); + _mav_put_uint8_t(buf, 6, txbuf); + _mav_put_uint8_t(buf, 7, noise); + _mav_put_uint8_t(buf, 8, remnoise); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); +#else + mavlink_radio_t packet; + packet.rxerrors = rxerrors; + packet.fixed = fixed; + packet.rssi = rssi; + packet.remrssi = remrssi; + packet.txbuf = txbuf; + packet.noise = noise; + packet.remnoise = remnoise; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); +#endif + + msg->msgid = MAVLINK_MSG_ID_RADIO; + return mavlink_finalize_message(msg, system_id, component_id, 9, 21); +} + +/** + * @brief Pack a radio 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 rssi local signal strength + * @param remrssi remote signal strength + * @param txbuf how full the tx buffer is as a percentage + * @param noise background noise level + * @param remnoise remote background noise level + * @param rxerrors receive errors + * @param fixed count of error corrected packets + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint8_t noise,uint8_t remnoise,uint16_t rxerrors,uint16_t fixed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint16_t(buf, 0, rxerrors); + _mav_put_uint16_t(buf, 2, fixed); + _mav_put_uint8_t(buf, 4, rssi); + _mav_put_uint8_t(buf, 5, remrssi); + _mav_put_uint8_t(buf, 6, txbuf); + _mav_put_uint8_t(buf, 7, noise); + _mav_put_uint8_t(buf, 8, remnoise); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9); +#else + mavlink_radio_t packet; + packet.rxerrors = rxerrors; + packet.fixed = fixed; + packet.rssi = rssi; + packet.remrssi = remrssi; + packet.txbuf = txbuf; + packet.noise = noise; + packet.remnoise = remnoise; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9); +#endif + + msg->msgid = MAVLINK_MSG_ID_RADIO; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 21); +} + +/** + * @brief Encode a radio 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 radio C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_radio_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_t* radio) +{ + return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed); +} + +/** + * @brief Send a radio message + * @param chan MAVLink channel to send the message + * + * @param rssi local signal strength + * @param remrssi remote signal strength + * @param txbuf how full the tx buffer is as a percentage + * @param noise background noise level + * @param remnoise remote background noise level + * @param rxerrors receive errors + * @param fixed count of error corrected packets + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint16_t(buf, 0, rxerrors); + _mav_put_uint16_t(buf, 2, fixed); + _mav_put_uint8_t(buf, 4, rssi); + _mav_put_uint8_t(buf, 5, remrssi); + _mav_put_uint8_t(buf, 6, txbuf); + _mav_put_uint8_t(buf, 7, noise); + _mav_put_uint8_t(buf, 8, remnoise); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, 9, 21); +#else + mavlink_radio_t packet; + packet.rxerrors = rxerrors; + packet.fixed = fixed; + packet.rssi = rssi; + packet.remrssi = remrssi; + packet.txbuf = txbuf; + packet.noise = noise; + packet.remnoise = remnoise; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, 9, 21); +#endif +} + +#endif + +// MESSAGE RADIO UNPACKING + + +/** + * @brief Get field rssi from radio message + * + * @return local signal strength + */ +static inline uint8_t mavlink_msg_radio_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field remrssi from radio message + * + * @return remote signal strength + */ +static inline uint8_t mavlink_msg_radio_get_remrssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field txbuf from radio message + * + * @return how full the tx buffer is as a percentage + */ +static inline uint8_t mavlink_msg_radio_get_txbuf(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field noise from radio message + * + * @return background noise level + */ +static inline uint8_t mavlink_msg_radio_get_noise(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field remnoise from radio message + * + * @return remote background noise level + */ +static inline uint8_t mavlink_msg_radio_get_remnoise(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Get field rxerrors from radio message + * + * @return receive errors + */ +static inline uint16_t mavlink_msg_radio_get_rxerrors(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field fixed from radio message + * + * @return count of error corrected packets + */ +static inline uint16_t mavlink_msg_radio_get_fixed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Decode a radio message into a struct + * + * @param msg The message to decode + * @param radio C-struct to decode the message contents into + */ +static inline void mavlink_msg_radio_decode(const mavlink_message_t* msg, mavlink_radio_t* radio) +{ +#if MAVLINK_NEED_BYTE_SWAP + radio->rxerrors = mavlink_msg_radio_get_rxerrors(msg); + radio->fixed = mavlink_msg_radio_get_fixed(msg); + radio->rssi = mavlink_msg_radio_get_rssi(msg); + radio->remrssi = mavlink_msg_radio_get_remrssi(msg); + radio->txbuf = mavlink_msg_radio_get_txbuf(msg); + radio->noise = mavlink_msg_radio_get_noise(msg); + radio->remnoise = mavlink_msg_radio_get_remnoise(msg); +#else + memcpy(radio, _MAV_PAYLOAD(msg), 9); +#endif +} diff --git a/mavlink/include/v1.0/ardupilotmega/mavlink_msg_simstate.h b/mavlink/include/v1.0/ardupilotmega/mavlink_msg_simstate.h new file mode 100644 index 0000000000000000000000000000000000000000..dfcddfc2b6c8ef8d54c411017e69f83942228654 --- /dev/null +++ b/mavlink/include/v1.0/ardupilotmega/mavlink_msg_simstate.h @@ -0,0 +1,320 @@ +// MESSAGE SIMSTATE PACKING + +#define MAVLINK_MSG_ID_SIMSTATE 164 + +typedef struct __mavlink_simstate_t +{ + float roll; ///< Roll angle (rad) + float pitch; ///< Pitch angle (rad) + float yaw; ///< Yaw angle (rad) + float xacc; ///< X acceleration m/s/s + float yacc; ///< Y acceleration m/s/s + float zacc; ///< Z acceleration m/s/s + float xgyro; ///< Angular speed around X axis rad/s + float ygyro; ///< Angular speed around Y axis rad/s + float zgyro; ///< Angular speed around Z axis rad/s +} mavlink_simstate_t; + +#define MAVLINK_MSG_ID_SIMSTATE_LEN 36 +#define MAVLINK_MSG_ID_164_LEN 36 + + + +#define MAVLINK_MESSAGE_INFO_SIMSTATE { \ + "SIMSTATE", \ + 9, \ + { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_simstate_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_simstate_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_simstate_t, yaw) }, \ + { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_simstate_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_simstate_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_simstate_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_simstate_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_simstate_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_simstate_t, zgyro) }, \ + } \ +} + + +/** + * @brief Pack a simstate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param xacc X acceleration m/s/s + * @param yacc Y acceleration m/s/s + * @param zacc Z acceleration m/s/s + * @param xgyro Angular speed around X axis rad/s + * @param ygyro Angular speed around Y axis rad/s + * @param zgyro Angular speed around Z axis rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, xacc); + _mav_put_float(buf, 16, yacc); + _mav_put_float(buf, 20, zacc); + _mav_put_float(buf, 24, xgyro); + _mav_put_float(buf, 28, ygyro); + _mav_put_float(buf, 32, zgyro); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); +#else + mavlink_simstate_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); +#endif + + msg->msgid = MAVLINK_MSG_ID_SIMSTATE; + return mavlink_finalize_message(msg, system_id, component_id, 36, 42); +} + +/** + * @brief Pack a simstate 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 roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param xacc X acceleration m/s/s + * @param yacc Y acceleration m/s/s + * @param zacc Z acceleration m/s/s + * @param xgyro Angular speed around X axis rad/s + * @param ygyro Angular speed around Y axis rad/s + * @param zgyro Angular speed around Z axis rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, xacc); + _mav_put_float(buf, 16, yacc); + _mav_put_float(buf, 20, zacc); + _mav_put_float(buf, 24, xgyro); + _mav_put_float(buf, 28, ygyro); + _mav_put_float(buf, 32, zgyro); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36); +#else + mavlink_simstate_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36); +#endif + + msg->msgid = MAVLINK_MSG_ID_SIMSTATE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36, 42); +} + +/** + * @brief Encode a simstate 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 simstate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_simstate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_simstate_t* simstate) +{ + return mavlink_msg_simstate_pack(system_id, component_id, msg, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro); +} + +/** + * @brief Send a simstate message + * @param chan MAVLink channel to send the message + * + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param xacc X acceleration m/s/s + * @param yacc Y acceleration m/s/s + * @param zacc Z acceleration m/s/s + * @param xgyro Angular speed around X axis rad/s + * @param ygyro Angular speed around Y axis rad/s + * @param zgyro Angular speed around Z axis rad/s + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, xacc); + _mav_put_float(buf, 16, yacc); + _mav_put_float(buf, 20, zacc); + _mav_put_float(buf, 24, xgyro); + _mav_put_float(buf, 28, ygyro); + _mav_put_float(buf, 32, zgyro); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, 36, 42); +#else + mavlink_simstate_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)&packet, 36, 42); +#endif +} + +#endif + +// MESSAGE SIMSTATE UNPACKING + + +/** + * @brief Get field roll from simstate message + * + * @return Roll angle (rad) + */ +static inline float mavlink_msg_simstate_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field pitch from simstate message + * + * @return Pitch angle (rad) + */ +static inline float mavlink_msg_simstate_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field yaw from simstate message + * + * @return Yaw angle (rad) + */ +static inline float mavlink_msg_simstate_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field xacc from simstate message + * + * @return X acceleration m/s/s + */ +static inline float mavlink_msg_simstate_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field yacc from simstate message + * + * @return Y acceleration m/s/s + */ +static inline float mavlink_msg_simstate_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field zacc from simstate message + * + * @return Z acceleration m/s/s + */ +static inline float mavlink_msg_simstate_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field xgyro from simstate message + * + * @return Angular speed around X axis rad/s + */ +static inline float mavlink_msg_simstate_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field ygyro from simstate message + * + * @return Angular speed around Y axis rad/s + */ +static inline float mavlink_msg_simstate_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field zgyro from simstate message + * + * @return Angular speed around Z axis rad/s + */ +static inline float mavlink_msg_simstate_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Decode a simstate message into a struct + * + * @param msg The message to decode + * @param simstate C-struct to decode the message contents into + */ +static inline void mavlink_msg_simstate_decode(const mavlink_message_t* msg, mavlink_simstate_t* simstate) +{ +#if MAVLINK_NEED_BYTE_SWAP + simstate->roll = mavlink_msg_simstate_get_roll(msg); + simstate->pitch = mavlink_msg_simstate_get_pitch(msg); + simstate->yaw = mavlink_msg_simstate_get_yaw(msg); + simstate->xacc = mavlink_msg_simstate_get_xacc(msg); + simstate->yacc = mavlink_msg_simstate_get_yacc(msg); + simstate->zacc = mavlink_msg_simstate_get_zacc(msg); + simstate->xgyro = mavlink_msg_simstate_get_xgyro(msg); + simstate->ygyro = mavlink_msg_simstate_get_ygyro(msg); + simstate->zgyro = mavlink_msg_simstate_get_zgyro(msg); +#else + memcpy(simstate, _MAV_PAYLOAD(msg), 36); +#endif +} diff --git a/mavlink/include/v1.0/ardupilotmega/testsuite.h b/mavlink/include/v1.0/ardupilotmega/testsuite.h index ae0014c72bcd5c66c92b1aace86a7e22c0d3d683..aa83889d66a663989466b58b90f799ca445d6c7e 100644 --- a/mavlink/include/v1.0/ardupilotmega/testsuite.h +++ b/mavlink/include/v1.0/ardupilotmega/testsuite.h @@ -668,6 +668,220 @@ static void mavlink_test_fence_status(uint8_t system_id, uint8_t component_id, m MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } +static void mavlink_test_ahrs(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_ahrs_t packet_in = { + 17.0, + 45.0, + 73.0, + 101.0, + 129.0, + 157.0, + 185.0, + }; + mavlink_ahrs_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.omegaIx = packet_in.omegaIx; + packet1.omegaIy = packet_in.omegaIy; + packet1.omegaIz = packet_in.omegaIz; + packet1.accel_weight = packet_in.accel_weight; + packet1.renorm_val = packet_in.renorm_val; + packet1.error_rp = packet_in.error_rp; + packet1.error_yaw = packet_in.error_yaw; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_ahrs_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_ahrs_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_ahrs_pack(system_id, component_id, &msg , packet1.omegaIx , packet1.omegaIy , packet1.omegaIz , packet1.accel_weight , packet1.renorm_val , packet1.error_rp , packet1.error_yaw ); + mavlink_msg_ahrs_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_ahrs_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.omegaIx , packet1.omegaIy , packet1.omegaIz , packet1.accel_weight , packet1.renorm_val , packet1.error_rp , packet1.error_yaw ); + mavlink_msg_ahrs_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 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the - vehicle itself. This can then be used by the vehicles control - system to control the vehicle attitude and the attitude of various - sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ - MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ - MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */ - MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ - MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ - MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ - MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ - MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ - MAV_CMD_ENUM_END=401, /* | */ -}; -#endif - /** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey - the recommended messages. - */ + the recommended messages. */ #ifndef HAVE_ENUM_MAV_DATA_STREAM #define HAVE_ENUM_MAV_DATA_STREAM enum MAV_DATA_STREAM @@ -311,8 +261,7 @@ enum MAV_DATA_STREAM /** @brief The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see - MAV_CMD_NAV_ROI). - */ + MAV_CMD_NAV_ROI). */ #ifndef HAVE_ENUM_MAV_ROI #define HAVE_ENUM_MAV_ROI enum MAV_ROI @@ -398,6 +347,23 @@ enum MAV_MISSION_RESULT }; #endif +/** @brief Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. */ +#ifndef HAVE_ENUM_MAV_SEVERITY +#define HAVE_ENUM_MAV_SEVERITY +enum MAV_SEVERITY +{ + MAV_SEVERITY_EMERGENCY=0, /* System is unusable. This is a "panic" condition. | */ + MAV_SEVERITY_ALERT=1, /* Action should be taken immediately. Indicates error in non-critical systems. | */ + MAV_SEVERITY_CRITICAL=2, /* Action must be taken immediately. Indicates failure in a primary system. | */ + MAV_SEVERITY_ERROR=3, /* Indicates an error in secondary/redundant systems. | */ + MAV_SEVERITY_WARNING=4, /* Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. | */ + MAV_SEVERITY_NOTICE=5, /* An unusual event has occured, though not an error condition. This should be investigated for the root cause. | */ + MAV_SEVERITY_INFO=6, /* Normal operational messages. Useful for logging. No action is required for these messages. | */ + MAV_SEVERITY_DEBUG=7, /* Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | */ + MAV_SEVERITY_ENUM_END=8, /* | */ +}; +#endif + // MESSAGE DEFINITIONS #include "./mavlink_msg_heartbeat.h" #include "./mavlink_msg_sys_status.h" diff --git a/mavlink/include/v1.0/common/mavlink_msg_heartbeat.h b/mavlink/include/v1.0/common/mavlink_msg_heartbeat.h index 4ad62b0a7cb3a682392f1846a0ba4c678f2712a9..599ea0bc5e9f6b95e1f290ec004610066b1e773a 100644 --- a/mavlink/include/v1.0/common/mavlink_msg_heartbeat.h +++ b/mavlink/include/v1.0/common/mavlink_msg_heartbeat.h @@ -4,12 +4,12 @@ typedef struct __mavlink_heartbeat_t { - uint32_t custom_mode; ///< Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. + uint32_t custom_mode; ///< A bitfield for use for autopilot-specific flags. uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - uint8_t autopilot; ///< Autopilot type / class. defined in MAV_CLASS ENUM + uint8_t autopilot; ///< Autopilot type / class. defined in MAV_AUTOPILOT ENUM uint8_t base_mode; ///< System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h - uint8_t system_status; ///< System status flag, see MAV_STATUS ENUM - uint8_t mavlink_version; ///< MAVLink version + uint8_t system_status; ///< System status flag, see MAV_STATE ENUM + uint8_t mavlink_version; ///< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version } mavlink_heartbeat_t; #define MAVLINK_MSG_ID_HEARTBEAT_LEN 9 @@ -37,10 +37,10 @@ typedef struct __mavlink_heartbeat_t * @param msg The MAVLink message to compress the data into * * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM + * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h - * @param custom_mode Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. - * @param system_status System status flag, see MAV_STATUS ENUM + * @param custom_mode A bitfield for use for autopilot-specific flags. + * @param system_status System status flag, see MAV_STATE ENUM * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, @@ -79,10 +79,10 @@ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t com * @param chan The MAVLink channel this message was sent over * @param msg The MAVLink message to compress the data into * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM + * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h - * @param custom_mode Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. - * @param system_status System status flag, see MAV_STATUS ENUM + * @param custom_mode A bitfield for use for autopilot-specific flags. + * @param system_status System status flag, see MAV_STATE ENUM * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, @@ -133,10 +133,10 @@ static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t c * @param chan MAVLink channel to send the message * * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM + * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h - * @param custom_mode Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. - * @param system_status System status flag, see MAV_STATUS ENUM + * @param custom_mode A bitfield for use for autopilot-specific flags. + * @param system_status System status flag, see MAV_STATE ENUM */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -183,7 +183,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* ms /** * @brief Get field autopilot from heartbeat message * - * @return Autopilot type / class. defined in MAV_CLASS ENUM + * @return Autopilot type / class. defined in MAV_AUTOPILOT ENUM */ static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg) { @@ -203,7 +203,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_ /** * @brief Get field custom_mode from heartbeat message * - * @return Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. + * @return A bitfield for use for autopilot-specific flags. */ static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg) { @@ -213,7 +213,7 @@ static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_messa /** * @brief Get field system_status from heartbeat message * - * @return System status flag, see MAV_STATUS ENUM + * @return System status flag, see MAV_STATE ENUM */ static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg) { @@ -223,7 +223,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_mess /** * @brief Get field mavlink_version from heartbeat message * - * @return MAVLink version + * @return MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version */ static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg) { diff --git a/mavlink/include/v1.0/common/mavlink_msg_optical_flow.h b/mavlink/include/v1.0/common/mavlink_msg_optical_flow.h index c93f07451d15b17b1d958074f29a4d09888aa1b2..b277cab5124965b179ed0c13c570954811d02ea1 100644 --- a/mavlink/include/v1.0/common/mavlink_msg_optical_flow.h +++ b/mavlink/include/v1.0/common/mavlink_msg_optical_flow.h @@ -5,27 +5,31 @@ typedef struct __mavlink_optical_flow_t { uint64_t time_usec; ///< Timestamp (UNIX) - float flow_x; ///< Flow in x-sensor direction - float flow_y; ///< Flow in y-sensor direction - float ground_distance; ///< Ground distance in meters (-1 for unknown, flow is then in pixel / arbitrary scale) + float flow_comp_m_x; ///< Flow in meters in x-sensor direction, angular-speed compensated + float flow_comp_m_y; ///< Flow in meters in y-sensor direction, angular-speed compensated + float ground_distance; ///< Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + int16_t flow_x; ///< Flow in pixels in x-sensor direction + int16_t flow_y; ///< Flow in pixels in y-sensor direction uint8_t sensor_id; ///< Sensor ID uint8_t quality; ///< Optical flow quality / confidence. 0: bad, 255: maximum quality } mavlink_optical_flow_t; -#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 22 -#define MAVLINK_MSG_ID_100_LEN 22 +#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 26 +#define MAVLINK_MSG_ID_100_LEN 26 #define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \ "OPTICAL_FLOW", \ - 6, \ + 8, \ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \ - { "flow_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_x) }, \ - { "flow_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_y) }, \ + { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \ + { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \ { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_optical_flow_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_optical_flow_t, quality) }, \ + { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \ + { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \ + { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \ + { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \ } \ } @@ -38,39 +42,45 @@ typedef struct __mavlink_optical_flow_t * * @param time_usec Timestamp (UNIX) * @param sensor_id Sensor ID - * @param flow_x Flow in x-sensor direction - * @param flow_y Flow in y-sensor direction + * @param flow_x Flow in pixels in x-sensor direction + * @param flow_y Flow in pixels in y-sensor direction + * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated + * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance Ground distance in meters (-1 for unknown, flow is then in pixel / arbitrary scale) + * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t sensor_id, float flow_x, float flow_y, uint8_t quality, float ground_distance) + uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[22]; + char buf[26]; _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, flow_x); - _mav_put_float(buf, 12, flow_y); + _mav_put_float(buf, 8, flow_comp_m_x); + _mav_put_float(buf, 12, flow_comp_m_y); _mav_put_float(buf, 16, ground_distance); - _mav_put_uint8_t(buf, 20, sensor_id); - _mav_put_uint8_t(buf, 21, quality); + _mav_put_int16_t(buf, 20, flow_x); + _mav_put_int16_t(buf, 22, flow_y); + _mav_put_uint8_t(buf, 24, sensor_id); + _mav_put_uint8_t(buf, 25, quality); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); #else mavlink_optical_flow_t packet; packet.time_usec = time_usec; + packet.flow_comp_m_x = flow_comp_m_x; + packet.flow_comp_m_y = flow_comp_m_y; + packet.ground_distance = ground_distance; packet.flow_x = flow_x; packet.flow_y = flow_y; - packet.ground_distance = ground_distance; packet.sensor_id = sensor_id; packet.quality = quality; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); #endif msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW; - return mavlink_finalize_message(msg, system_id, component_id, 22, 31); + return mavlink_finalize_message(msg, system_id, component_id, 26, 175); } /** @@ -81,40 +91,46 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t * @param msg The MAVLink message to compress the data into * @param time_usec Timestamp (UNIX) * @param sensor_id Sensor ID - * @param flow_x Flow in x-sensor direction - * @param flow_y Flow in y-sensor direction + * @param flow_x Flow in pixels in x-sensor direction + * @param flow_y Flow in pixels in y-sensor direction + * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated + * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance Ground distance in meters (-1 for unknown, flow is then in pixel / arbitrary scale) + * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, - uint64_t time_usec,uint8_t sensor_id,float flow_x,float flow_y,uint8_t quality,float ground_distance) + uint64_t time_usec,uint8_t sensor_id,int16_t flow_x,int16_t flow_y,float flow_comp_m_x,float flow_comp_m_y,uint8_t quality,float ground_distance) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[22]; + char buf[26]; _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, flow_x); - _mav_put_float(buf, 12, flow_y); + _mav_put_float(buf, 8, flow_comp_m_x); + _mav_put_float(buf, 12, flow_comp_m_y); _mav_put_float(buf, 16, ground_distance); - _mav_put_uint8_t(buf, 20, sensor_id); - _mav_put_uint8_t(buf, 21, quality); + _mav_put_int16_t(buf, 20, flow_x); + _mav_put_int16_t(buf, 22, flow_y); + _mav_put_uint8_t(buf, 24, sensor_id); + _mav_put_uint8_t(buf, 25, quality); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26); #else mavlink_optical_flow_t packet; packet.time_usec = time_usec; + packet.flow_comp_m_x = flow_comp_m_x; + packet.flow_comp_m_y = flow_comp_m_y; + packet.ground_distance = ground_distance; packet.flow_x = flow_x; packet.flow_y = flow_y; - packet.ground_distance = ground_distance; packet.sensor_id = sensor_id; packet.quality = quality; - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26); #endif msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 31); + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26, 175); } /** @@ -127,7 +143,7 @@ static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uin */ static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow) { - return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->quality, optical_flow->ground_distance); + return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance); } /** @@ -136,35 +152,41 @@ static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_ * * @param time_usec Timestamp (UNIX) * @param sensor_id Sensor ID - * @param flow_x Flow in x-sensor direction - * @param flow_y Flow in y-sensor direction + * @param flow_x Flow in pixels in x-sensor direction + * @param flow_y Flow in pixels in y-sensor direction + * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated + * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance Ground distance in meters (-1 for unknown, flow is then in pixel / arbitrary scale) + * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, float flow_x, float flow_y, uint8_t quality, float ground_distance) +static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[22]; + char buf[26]; _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, flow_x); - _mav_put_float(buf, 12, flow_y); + _mav_put_float(buf, 8, flow_comp_m_x); + _mav_put_float(buf, 12, flow_comp_m_y); _mav_put_float(buf, 16, ground_distance); - _mav_put_uint8_t(buf, 20, sensor_id); - _mav_put_uint8_t(buf, 21, quality); + _mav_put_int16_t(buf, 20, flow_x); + _mav_put_int16_t(buf, 22, flow_y); + _mav_put_uint8_t(buf, 24, sensor_id); + _mav_put_uint8_t(buf, 25, quality); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, 22, 31); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, 26, 175); #else mavlink_optical_flow_t packet; packet.time_usec = time_usec; + packet.flow_comp_m_x = flow_comp_m_x; + packet.flow_comp_m_y = flow_comp_m_y; + packet.ground_distance = ground_distance; packet.flow_x = flow_x; packet.flow_y = flow_y; - packet.ground_distance = ground_distance; packet.sensor_id = sensor_id; packet.quality = quality; - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, 22, 31); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, 26, 175); #endif } @@ -190,25 +212,45 @@ static inline uint64_t mavlink_msg_optical_flow_get_time_usec(const mavlink_mess */ static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 20); + return _MAV_RETURN_uint8_t(msg, 24); } /** * @brief Get field flow_x from optical_flow message * - * @return Flow in x-sensor direction + * @return Flow in pixels in x-sensor direction */ -static inline float mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg) +static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg) { - return _MAV_RETURN_float(msg, 8); + return _MAV_RETURN_int16_t(msg, 20); } /** * @brief Get field flow_y from optical_flow message * - * @return Flow in y-sensor direction + * @return Flow in pixels in y-sensor direction + */ +static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 22); +} + +/** + * @brief Get field flow_comp_m_x from optical_flow message + * + * @return Flow in meters in x-sensor direction, angular-speed compensated */ -static inline float mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg) +static inline float mavlink_msg_optical_flow_get_flow_comp_m_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field flow_comp_m_y from optical_flow message + * + * @return Flow in meters in y-sensor direction, angular-speed compensated + */ +static inline float mavlink_msg_optical_flow_get_flow_comp_m_y(const mavlink_message_t* msg) { return _MAV_RETURN_float(msg, 12); } @@ -220,13 +262,13 @@ static inline float mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* */ static inline uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 21); + return _MAV_RETURN_uint8_t(msg, 25); } /** * @brief Get field ground_distance from optical_flow message * - * @return Ground distance in meters (-1 for unknown, flow is then in pixel / arbitrary scale) + * @return Ground distance in meters. Positive value: distance known. Negative value: Unknown distance */ static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_message_t* msg) { @@ -243,12 +285,14 @@ static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* msg, { #if MAVLINK_NEED_BYTE_SWAP optical_flow->time_usec = mavlink_msg_optical_flow_get_time_usec(msg); + optical_flow->flow_comp_m_x = mavlink_msg_optical_flow_get_flow_comp_m_x(msg); + optical_flow->flow_comp_m_y = mavlink_msg_optical_flow_get_flow_comp_m_y(msg); + optical_flow->ground_distance = mavlink_msg_optical_flow_get_ground_distance(msg); optical_flow->flow_x = mavlink_msg_optical_flow_get_flow_x(msg); optical_flow->flow_y = mavlink_msg_optical_flow_get_flow_y(msg); - optical_flow->ground_distance = mavlink_msg_optical_flow_get_ground_distance(msg); optical_flow->sensor_id = mavlink_msg_optical_flow_get_sensor_id(msg); optical_flow->quality = mavlink_msg_optical_flow_get_quality(msg); #else - memcpy(optical_flow, _MAV_PAYLOAD(msg), 22); + memcpy(optical_flow, _MAV_PAYLOAD(msg), 26); #endif } diff --git a/mavlink/include/v1.0/common/mavlink_msg_statustext.h b/mavlink/include/v1.0/common/mavlink_msg_statustext.h index e6dac6374ac5ba830f6c11546a5a8f0b7624bdf8..7c65d448f436d7331bb52d0f84293d1695982c55 100644 --- a/mavlink/include/v1.0/common/mavlink_msg_statustext.h +++ b/mavlink/include/v1.0/common/mavlink_msg_statustext.h @@ -4,7 +4,7 @@ typedef struct __mavlink_statustext_t { - uint8_t severity; ///< Severity of status, 0 = info message, 255 = critical fault + uint8_t severity; ///< Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. char text[50]; ///< Status text message, without null termination character } mavlink_statustext_t; @@ -28,7 +28,7 @@ typedef struct __mavlink_statustext_t * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * - * @param severity Severity of status, 0 = info message, 255 = critical fault + * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. * @param text Status text message, without null termination character * @return length of the message in bytes (excluding serial stream start sign) */ @@ -57,7 +57,7 @@ static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t co * @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 severity Severity of status, 0 = info message, 255 = critical fault + * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. * @param text Status text message, without null termination character * @return length of the message in bytes (excluding serial stream start sign) */ @@ -98,7 +98,7 @@ static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t * @brief Send a statustext message * @param chan MAVLink channel to send the message * - * @param severity Severity of status, 0 = info message, 255 = critical fault + * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. * @param text Status text message, without null termination character */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS @@ -126,7 +126,7 @@ static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t s /** * @brief Get field severity from statustext message * - * @return Severity of status, 0 = info message, 255 = critical fault + * @return Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. */ static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_t* msg) { diff --git a/mavlink/include/v1.0/common/testsuite.h b/mavlink/include/v1.0/common/testsuite.h index 4a37fe385db94aeeec34b2d477e6e4a0c7fc50d4..5459a61a5adab2e4d00e37715f3ccfc2ace4989e 100644 --- a/mavlink/include/v1.0/common/testsuite.h +++ b/mavlink/include/v1.0/common/testsuite.h @@ -3393,15 +3393,19 @@ static void mavlink_test_optical_flow(uint8_t system_id, uint8_t component_id, m 73.0, 101.0, 129.0, - 65, - 132, + 18275, + 18379, + 77, + 144, }; mavlink_optical_flow_t packet1, packet2; memset(&packet1, 0, sizeof(packet1)); packet1.time_usec = packet_in.time_usec; + packet1.flow_comp_m_x = packet_in.flow_comp_m_x; + packet1.flow_comp_m_y = packet_in.flow_comp_m_y; + packet1.ground_distance = packet_in.ground_distance; packet1.flow_x = packet_in.flow_x; packet1.flow_y = packet_in.flow_y; - packet1.ground_distance = packet_in.ground_distance; packet1.sensor_id = packet_in.sensor_id; packet1.quality = packet_in.quality; @@ -3413,12 +3417,12 @@ static void mavlink_test_optical_flow(uint8_t system_id, uint8_t component_id, m MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.quality , packet1.ground_distance ); + mavlink_msg_optical_flow_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance ); mavlink_msg_optical_flow_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.quality , packet1.ground_distance ); + mavlink_msg_optical_flow_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance ); mavlink_msg_optical_flow_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); @@ -3431,7 +3435,7 @@ static void mavlink_test_optical_flow(uint8_t system_id, uint8_t component_id, m MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.quality , packet1.ground_distance ); + mavlink_msg_optical_flow_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance ); mavlink_msg_optical_flow_decode(last_msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } diff --git a/mavlink/include/v1.0/common/version.h b/mavlink/include/v1.0/common/version.h index 49e7ff03c9fb8376c67b7939fee752ce5c250282..824cefe861f1f758d36991573804c97d4373d46b 100644 --- a/mavlink/include/v1.0/common/version.h +++ b/mavlink/include/v1.0/common/version.h @@ -5,8 +5,8 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Sun Feb 26 16:49:33 2012" +#define MAVLINK_BUILD_DATE "Fri Apr 20 10:01:01 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" -#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 +#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 #endif // MAVLINK_VERSION_H diff --git a/mavlink/include/v1.0/mavlink_types.h b/mavlink/include/v1.0/mavlink_types.h index 1060be832700ff81b5ea8091a5394969e55ef040..5fbde97f7363ad203981483c7bf88828e4bf5faf 100644 --- a/mavlink/include/v1.0/mavlink_types.h +++ b/mavlink/include/v1.0/mavlink_types.h @@ -17,7 +17,15 @@ #define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255 #define MAVLINK_EXTENDED_HEADER_LEN 14 -#define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507 + +#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 { diff --git a/mavlink/include/v1.0/pixhawk/pixhawk.h b/mavlink/include/v1.0/pixhawk/pixhawk.h index bffc47264978839af4056d31d357574a1e5f1aed..aa96e0bd7ac0b1c135055706e00d4a24ed3c23a6 100644 --- a/mavlink/include/v1.0/pixhawk/pixhawk.h +++ b/mavlink/include/v1.0/pixhawk/pixhawk.h @@ -12,11 +12,11 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 54, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 22, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 11, 52, 1, 92, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 26, 16, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 0, 0, 0, 0, 0, 0, 106, 43, 55, 12, 255, 53, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 54, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 11, 52, 1, 92, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 26, 16, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 0, 0, 0, 0, 0, 0, 106, 43, 55, 12, 255, 53, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 200, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 31, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 108, 86, 95, 224, 0, 0, 0, 0, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 249, 182, 0, 0, 0, 0, 0, 0, 0, 153, 16, 29, 162, 0, 0, 0, 0, 0, 0, 90, 95, 36, 23, 223, 88, 0, 0, 0, 0, 254, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 200, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 108, 86, 95, 224, 0, 0, 0, 0, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 249, 182, 0, 0, 0, 0, 0, 0, 0, 153, 16, 29, 162, 0, 0, 0, 0, 0, 0, 90, 95, 36, 23, 223, 88, 0, 0, 0, 0, 254, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} #endif #ifndef MAVLINK_MESSAGE_INFO diff --git a/mavlink/include/v1.0/pixhawk/version.h b/mavlink/include/v1.0/pixhawk/version.h index 966aaed5573ffeaab408112fcde5e2718dfb8ef7..5ebcb2aaa0a1587beb22e4f686f293c4ce51d759 100644 --- a/mavlink/include/v1.0/pixhawk/version.h +++ b/mavlink/include/v1.0/pixhawk/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Sun Feb 26 16:49:33 2012" +#define MAVLINK_BUILD_DATE "Fri Apr 20 10:00:51 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 diff --git a/mavlink/share/mavlink/src/v1.0/pixhawk/pixhawk.pb.cc b/mavlink/share/mavlink/src/v1.0/pixhawk/pixhawk.pb.cc new file mode 100644 index 0000000000000000000000000000000000000000..e984f512af21c5887512715425f30a1ea27303aa --- /dev/null +++ b/mavlink/share/mavlink/src/v1.0/pixhawk/pixhawk.pb.cc @@ -0,0 +1,5431 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! + +#define INTERNAL_SUPPRESS_PROTOBUF_FIELD_DEPRECATION +#include "pixhawk.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +// @@protoc_insertion_point(includes) + +namespace px { + +namespace { + +const ::google::protobuf::Descriptor* HeaderInfo_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + HeaderInfo_reflection_ = NULL; +const ::google::protobuf::Descriptor* GLOverlay_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + GLOverlay_reflection_ = NULL; +const ::google::protobuf::EnumDescriptor* GLOverlay_CoordinateFrameType_descriptor_ = NULL; +const ::google::protobuf::EnumDescriptor* GLOverlay_Mode_descriptor_ = NULL; +const ::google::protobuf::EnumDescriptor* GLOverlay_Identifier_descriptor_ = NULL; +const ::google::protobuf::Descriptor* Obstacle_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + Obstacle_reflection_ = NULL; +const ::google::protobuf::Descriptor* ObstacleList_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + ObstacleList_reflection_ = NULL; +const ::google::protobuf::Descriptor* ObstacleMap_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + ObstacleMap_reflection_ = NULL; +const ::google::protobuf::Descriptor* Path_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + Path_reflection_ = NULL; +const ::google::protobuf::Descriptor* PointCloudXYZI_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + PointCloudXYZI_reflection_ = NULL; +const ::google::protobuf::Descriptor* PointCloudXYZI_PointXYZI_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + PointCloudXYZI_PointXYZI_reflection_ = NULL; +const ::google::protobuf::Descriptor* PointCloudXYZRGB_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + PointCloudXYZRGB_reflection_ = NULL; +const ::google::protobuf::Descriptor* PointCloudXYZRGB_PointXYZRGB_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + PointCloudXYZRGB_PointXYZRGB_reflection_ = NULL; +const ::google::protobuf::Descriptor* RGBDImage_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + RGBDImage_reflection_ = NULL; +const ::google::protobuf::Descriptor* Waypoint_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + Waypoint_reflection_ = NULL; + +} // namespace + + +void protobuf_AssignDesc_pixhawk_2eproto() { + protobuf_AddDesc_pixhawk_2eproto(); + const ::google::protobuf::FileDescriptor* file = + ::google::protobuf::DescriptorPool::generated_pool()->FindFileByName( + "pixhawk.proto"); + GOOGLE_CHECK(file != NULL); + HeaderInfo_descriptor_ = file->message_type(0); + static const int HeaderInfo_offsets_[3] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, source_sysid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, source_compid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, timestamp_), + }; + HeaderInfo_reflection_ = + new ::google::protobuf::internal::GeneratedMessageReflection( + HeaderInfo_descriptor_, + HeaderInfo::default_instance_, + HeaderInfo_offsets_, + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, _has_bits_[0]), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, _unknown_fields_), + -1, + ::google::protobuf::DescriptorPool::generated_pool(), + ::google::protobuf::MessageFactory::generated_factory(), + sizeof(HeaderInfo)); + GLOverlay_descriptor_ = file->message_type(1); + static const int GLOverlay_offsets_[7] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, name_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, coordinateframetype_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, origin_x_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, origin_y_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, origin_z_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, data_), + }; + GLOverlay_reflection_ = + new ::google::protobuf::internal::GeneratedMessageReflection( + GLOverlay_descriptor_, + GLOverlay::default_instance_, + GLOverlay_offsets_, + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, _has_bits_[0]), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, _unknown_fields_), + -1, + ::google::protobuf::DescriptorPool::generated_pool(), + ::google::protobuf::MessageFactory::generated_factory(), + sizeof(GLOverlay)); + GLOverlay_CoordinateFrameType_descriptor_ = GLOverlay_descriptor_->enum_type(0); + GLOverlay_Mode_descriptor_ = GLOverlay_descriptor_->enum_type(1); + GLOverlay_Identifier_descriptor_ = GLOverlay_descriptor_->enum_type(2); + Obstacle_descriptor_ = file->message_type(2); + static const int Obstacle_offsets_[6] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, x_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, y_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, z_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, length_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, width_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, height_), + }; + Obstacle_reflection_ = + new ::google::protobuf::internal::GeneratedMessageReflection( + Obstacle_descriptor_, + Obstacle::default_instance_, + Obstacle_offsets_, + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, _has_bits_[0]), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, _unknown_fields_), + -1, + ::google::protobuf::DescriptorPool::generated_pool(), + ::google::protobuf::MessageFactory::generated_factory(), + sizeof(Obstacle)); + ObstacleList_descriptor_ = file->message_type(3); + static const int ObstacleList_offsets_[2] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, obstacles_), + }; + ObstacleList_reflection_ = + new ::google::protobuf::internal::GeneratedMessageReflection( + ObstacleList_descriptor_, + ObstacleList::default_instance_, + ObstacleList_offsets_, + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, _has_bits_[0]), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, _unknown_fields_), + -1, + ::google::protobuf::DescriptorPool::generated_pool(), + ::google::protobuf::MessageFactory::generated_factory(), + sizeof(ObstacleList)); + ObstacleMap_descriptor_ = file->message_type(4); + static const int ObstacleMap_offsets_[10] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, type_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, resolution_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, rows_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, cols_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, mapr0_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, mapc0_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, arrayr0_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, arrayc0_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, data_), + }; + ObstacleMap_reflection_ = + new ::google::protobuf::internal::GeneratedMessageReflection( + ObstacleMap_descriptor_, + ObstacleMap::default_instance_, + ObstacleMap_offsets_, + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, _has_bits_[0]), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, _unknown_fields_), + -1, + ::google::protobuf::DescriptorPool::generated_pool(), + ::google::protobuf::MessageFactory::generated_factory(), + sizeof(ObstacleMap)); + Path_descriptor_ = file->message_type(5); + static const int Path_offsets_[2] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, waypoints_), + }; + Path_reflection_ = + new ::google::protobuf::internal::GeneratedMessageReflection( + Path_descriptor_, + Path::default_instance_, + Path_offsets_, + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, _has_bits_[0]), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, _unknown_fields_), + -1, + ::google::protobuf::DescriptorPool::generated_pool(), + ::google::protobuf::MessageFactory::generated_factory(), + sizeof(Path)); + PointCloudXYZI_descriptor_ = file->message_type(6); + static const int PointCloudXYZI_offsets_[2] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, points_), + }; + PointCloudXYZI_reflection_ = + new ::google::protobuf::internal::GeneratedMessageReflection( + PointCloudXYZI_descriptor_, + PointCloudXYZI::default_instance_, + PointCloudXYZI_offsets_, + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, _has_bits_[0]), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, _unknown_fields_), + -1, + ::google::protobuf::DescriptorPool::generated_pool(), + ::google::protobuf::MessageFactory::generated_factory(), + sizeof(PointCloudXYZI)); + PointCloudXYZI_PointXYZI_descriptor_ = PointCloudXYZI_descriptor_->nested_type(0); + static const int PointCloudXYZI_PointXYZI_offsets_[4] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, x_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, y_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, z_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, intensity_), + }; + PointCloudXYZI_PointXYZI_reflection_ = + new ::google::protobuf::internal::GeneratedMessageReflection( + PointCloudXYZI_PointXYZI_descriptor_, + PointCloudXYZI_PointXYZI::default_instance_, + PointCloudXYZI_PointXYZI_offsets_, + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, _has_bits_[0]), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, _unknown_fields_), + -1, + ::google::protobuf::DescriptorPool::generated_pool(), + ::google::protobuf::MessageFactory::generated_factory(), + sizeof(PointCloudXYZI_PointXYZI)); + PointCloudXYZRGB_descriptor_ = file->message_type(7); + static const int PointCloudXYZRGB_offsets_[2] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, points_), + }; + PointCloudXYZRGB_reflection_ = + new ::google::protobuf::internal::GeneratedMessageReflection( + PointCloudXYZRGB_descriptor_, + PointCloudXYZRGB::default_instance_, + PointCloudXYZRGB_offsets_, + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, _has_bits_[0]), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, _unknown_fields_), + -1, + ::google::protobuf::DescriptorPool::generated_pool(), + ::google::protobuf::MessageFactory::generated_factory(), + sizeof(PointCloudXYZRGB)); + PointCloudXYZRGB_PointXYZRGB_descriptor_ = PointCloudXYZRGB_descriptor_->nested_type(0); + static const int PointCloudXYZRGB_PointXYZRGB_offsets_[4] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, x_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, y_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, z_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, rgb_), + }; + PointCloudXYZRGB_PointXYZRGB_reflection_ = + new ::google::protobuf::internal::GeneratedMessageReflection( + PointCloudXYZRGB_PointXYZRGB_descriptor_, + PointCloudXYZRGB_PointXYZRGB::default_instance_, + PointCloudXYZRGB_PointXYZRGB_offsets_, + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, _has_bits_[0]), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, _unknown_fields_), + -1, + ::google::protobuf::DescriptorPool::generated_pool(), + ::google::protobuf::MessageFactory::generated_factory(), + sizeof(PointCloudXYZRGB_PointXYZRGB)); + RGBDImage_descriptor_ = file->message_type(8); + static const int RGBDImage_offsets_[21] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, cols_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, rows_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, step1_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, type1_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, imagedata1_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, step2_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, type2_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, imagedata2_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, camera_config_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, camera_type_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, roll_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, pitch_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, yaw_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, lon_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, lat_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, alt_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, ground_x_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, ground_y_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, ground_z_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, camera_matrix_), + }; + RGBDImage_reflection_ = + new ::google::protobuf::internal::GeneratedMessageReflection( + RGBDImage_descriptor_, + RGBDImage::default_instance_, + RGBDImage_offsets_, + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, _has_bits_[0]), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, _unknown_fields_), + -1, + ::google::protobuf::DescriptorPool::generated_pool(), + ::google::protobuf::MessageFactory::generated_factory(), + sizeof(RGBDImage)); + Waypoint_descriptor_ = file->message_type(9); + static const int Waypoint_offsets_[6] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, x_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, y_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, z_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, roll_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, pitch_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, yaw_), + }; + Waypoint_reflection_ = + new ::google::protobuf::internal::GeneratedMessageReflection( + Waypoint_descriptor_, + Waypoint::default_instance_, + Waypoint_offsets_, + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, _has_bits_[0]), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, _unknown_fields_), + -1, + ::google::protobuf::DescriptorPool::generated_pool(), + ::google::protobuf::MessageFactory::generated_factory(), + sizeof(Waypoint)); +} + +namespace { + +GOOGLE_PROTOBUF_DECLARE_ONCE(protobuf_AssignDescriptors_once_); +inline void protobuf_AssignDescriptorsOnce() { + ::google::protobuf::GoogleOnceInit(&protobuf_AssignDescriptors_once_, + &protobuf_AssignDesc_pixhawk_2eproto); +} + +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + HeaderInfo_descriptor_, &HeaderInfo::default_instance()); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + GLOverlay_descriptor_, &GLOverlay::default_instance()); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + Obstacle_descriptor_, &Obstacle::default_instance()); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + ObstacleList_descriptor_, &ObstacleList::default_instance()); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + ObstacleMap_descriptor_, &ObstacleMap::default_instance()); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + Path_descriptor_, &Path::default_instance()); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + PointCloudXYZI_descriptor_, &PointCloudXYZI::default_instance()); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + PointCloudXYZI_PointXYZI_descriptor_, &PointCloudXYZI_PointXYZI::default_instance()); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + PointCloudXYZRGB_descriptor_, &PointCloudXYZRGB::default_instance()); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + PointCloudXYZRGB_PointXYZRGB_descriptor_, &PointCloudXYZRGB_PointXYZRGB::default_instance()); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + RGBDImage_descriptor_, &RGBDImage::default_instance()); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + Waypoint_descriptor_, &Waypoint::default_instance()); +} + +} // namespace + +void protobuf_ShutdownFile_pixhawk_2eproto() { + delete HeaderInfo::default_instance_; + delete HeaderInfo_reflection_; + delete GLOverlay::default_instance_; + delete GLOverlay_reflection_; + delete Obstacle::default_instance_; + delete Obstacle_reflection_; + delete ObstacleList::default_instance_; + delete ObstacleList_reflection_; + delete ObstacleMap::default_instance_; + delete ObstacleMap_reflection_; + delete Path::default_instance_; + delete Path_reflection_; + delete PointCloudXYZI::default_instance_; + delete PointCloudXYZI_reflection_; + delete PointCloudXYZI_PointXYZI::default_instance_; + delete PointCloudXYZI_PointXYZI_reflection_; + delete PointCloudXYZRGB::default_instance_; + delete PointCloudXYZRGB_reflection_; + delete PointCloudXYZRGB_PointXYZRGB::default_instance_; + delete PointCloudXYZRGB_PointXYZRGB_reflection_; + delete RGBDImage::default_instance_; + delete RGBDImage_reflection_; + delete Waypoint::default_instance_; + delete Waypoint_reflection_; +} + +void protobuf_AddDesc_pixhawk_2eproto() { + static bool already_here = false; + if (already_here) return; + already_here = true; + GOOGLE_PROTOBUF_VERIFY_VERSION; + + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + "\n\rpixhawk.proto\022\002px\"L\n\nHeaderInfo\022\024\n\014sou" + "rce_sysid\030\001 \002(\005\022\025\n\rsource_compid\030\002 \002(\005\022\021" + "\n\ttimestamp\030\003 \002(\001\"\377\004\n\tGLOverlay\022\036\n\006heade" + "r\030\001 \002(\0132\016.px.HeaderInfo\022\014\n\004name\030\002 \001(\t\022>\n" + "\023coordinateFrameType\030\003 \001(\0162!.px.GLOverla" + "y.CoordinateFrameType\022\020\n\010origin_x\030\004 \001(\001\022" + "\020\n\010origin_y\030\005 \001(\001\022\020\n\010origin_z\030\006 \001(\001\022\014\n\004d" + "ata\030\007 \001(\014\",\n\023CoordinateFrameType\022\n\n\006GLOB" + "AL\020\000\022\t\n\005LOCAL\020\001\"\333\001\n\004Mode\022\n\n\006POINTS\020\000\022\t\n\005" + "LINES\020\001\022\016\n\nLINE_STRIP\020\002\022\r\n\tLINE_LOOP\020\003\022\r" + "\n\tTRIANGLES\020\004\022\022\n\016TRIANGLE_STRIP\020\005\022\020\n\014TRI" + "ANGLE_FAN\020\006\022\t\n\005QUADS\020\007\022\016\n\nQUAD_STRIP\020\010\022\013" + "\n\007POLYGON\020\t\022\020\n\014SOLID_CIRCLE\020\n\022\017\n\013WIRE_CI" + "RCLE\020\013\022\016\n\nSOLID_CUBE\020\014\022\r\n\tWIRE_CUBE\020\r\"\263\001" + "\n\nIdentifier\022\007\n\003END\020\016\022\014\n\010VERTEX2F\020\017\022\014\n\010V" + "ERTEX3F\020\020\022\013\n\007ROTATEF\020\021\022\016\n\nTRANSLATEF\020\022\022\n" + "\n\006SCALEF\020\023\022\017\n\013PUSH_MATRIX\020\024\022\016\n\nPOP_MATRI" + "X\020\025\022\013\n\007COLOR3F\020\026\022\013\n\007COLOR4F\020\027\022\r\n\tPOINTSI" + "ZE\020\030\022\r\n\tLINEWIDTH\020\031\"Z\n\010Obstacle\022\t\n\001x\030\001 \001" + "(\002\022\t\n\001y\030\002 \001(\002\022\t\n\001z\030\003 \001(\002\022\016\n\006length\030\004 \001(\002" + "\022\r\n\005width\030\005 \001(\002\022\016\n\006height\030\006 \001(\002\"O\n\014Obsta" + "cleList\022\036\n\006header\030\001 \002(\0132\016.px.HeaderInfo\022" + "\037\n\tobstacles\030\002 \003(\0132\014.px.Obstacle\"\271\001\n\013Obs" + "tacleMap\022\036\n\006header\030\001 \002(\0132\016.px.HeaderInfo" + "\022\014\n\004type\030\002 \002(\005\022\022\n\nresolution\030\003 \001(\002\022\014\n\004ro" + "ws\030\004 \001(\005\022\014\n\004cols\030\005 \001(\005\022\r\n\005mapR0\030\006 \001(\005\022\r\n" + "\005mapC0\030\007 \001(\005\022\017\n\007arrayR0\030\010 \001(\005\022\017\n\007arrayC0" + "\030\t \001(\005\022\014\n\004data\030\n \001(\014\"G\n\004Path\022\036\n\006header\030\001" + " \002(\0132\016.px.HeaderInfo\022\037\n\twaypoints\030\002 \003(\0132" + "\014.px.Waypoint\"\237\001\n\016PointCloudXYZI\022\036\n\006head" + "er\030\001 \002(\0132\016.px.HeaderInfo\022,\n\006points\030\002 \003(\013" + "2\034.px.PointCloudXYZI.PointXYZI\032\?\n\tPointX" + "YZI\022\t\n\001x\030\001 \002(\002\022\t\n\001y\030\002 \002(\002\022\t\n\001z\030\003 \002(\002\022\021\n\t" + "intensity\030\004 \002(\002\"\241\001\n\020PointCloudXYZRGB\022\036\n\006" + "header\030\001 \002(\0132\016.px.HeaderInfo\0220\n\006points\030\002" + " \003(\0132 .px.PointCloudXYZRGB.PointXYZRGB\032;" + "\n\013PointXYZRGB\022\t\n\001x\030\001 \002(\002\022\t\n\001y\030\002 \002(\002\022\t\n\001z" + "\030\003 \002(\002\022\013\n\003rgb\030\004 \002(\002\"\365\002\n\tRGBDImage\022\036\n\006hea" + "der\030\001 \002(\0132\016.px.HeaderInfo\022\014\n\004cols\030\002 \002(\r\022" + "\014\n\004rows\030\003 \002(\r\022\r\n\005step1\030\004 \002(\r\022\r\n\005type1\030\005 " + "\002(\r\022\022\n\nimageData1\030\006 \002(\014\022\r\n\005step2\030\007 \002(\r\022\r" + "\n\005type2\030\010 \002(\r\022\022\n\nimageData2\030\t \002(\014\022\025\n\rcam" + "era_config\030\n \001(\r\022\023\n\013camera_type\030\013 \001(\r\022\014\n" + "\004roll\030\014 \001(\002\022\r\n\005pitch\030\r \001(\002\022\013\n\003yaw\030\016 \001(\002\022" + "\013\n\003lon\030\017 \001(\002\022\013\n\003lat\030\020 \001(\002\022\013\n\003alt\030\021 \001(\002\022\020" + "\n\010ground_x\030\022 \001(\002\022\020\n\010ground_y\030\023 \001(\002\022\020\n\010gr" + "ound_z\030\024 \001(\002\022\025\n\rcamera_matrix\030\025 \003(\002\"U\n\010W" + "aypoint\022\t\n\001x\030\001 \002(\001\022\t\n\001y\030\002 \002(\001\022\t\n\001z\030\003 \001(\001" + "\022\014\n\004roll\030\004 \001(\001\022\r\n\005pitch\030\005 \001(\001\022\013\n\003yaw\030\006 \001" + "(\001", 1962); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "pixhawk.proto", &protobuf_RegisterTypes); + HeaderInfo::default_instance_ = new HeaderInfo(); + GLOverlay::default_instance_ = new GLOverlay(); + Obstacle::default_instance_ = new Obstacle(); + ObstacleList::default_instance_ = new ObstacleList(); + ObstacleMap::default_instance_ = new ObstacleMap(); + Path::default_instance_ = new Path(); + PointCloudXYZI::default_instance_ = new PointCloudXYZI(); + PointCloudXYZI_PointXYZI::default_instance_ = new PointCloudXYZI_PointXYZI(); + PointCloudXYZRGB::default_instance_ = new PointCloudXYZRGB(); + PointCloudXYZRGB_PointXYZRGB::default_instance_ = new PointCloudXYZRGB_PointXYZRGB(); + RGBDImage::default_instance_ = new RGBDImage(); + Waypoint::default_instance_ = new Waypoint(); + HeaderInfo::default_instance_->InitAsDefaultInstance(); + GLOverlay::default_instance_->InitAsDefaultInstance(); + Obstacle::default_instance_->InitAsDefaultInstance(); + ObstacleList::default_instance_->InitAsDefaultInstance(); + ObstacleMap::default_instance_->InitAsDefaultInstance(); + Path::default_instance_->InitAsDefaultInstance(); + PointCloudXYZI::default_instance_->InitAsDefaultInstance(); + PointCloudXYZI_PointXYZI::default_instance_->InitAsDefaultInstance(); + PointCloudXYZRGB::default_instance_->InitAsDefaultInstance(); + PointCloudXYZRGB_PointXYZRGB::default_instance_->InitAsDefaultInstance(); + RGBDImage::default_instance_->InitAsDefaultInstance(); + Waypoint::default_instance_->InitAsDefaultInstance(); + ::google::protobuf::internal::OnShutdown(&protobuf_ShutdownFile_pixhawk_2eproto); +} + +// Force AddDescriptors() to be called at static initialization time. +struct StaticDescriptorInitializer_pixhawk_2eproto { + StaticDescriptorInitializer_pixhawk_2eproto() { + protobuf_AddDesc_pixhawk_2eproto(); + } +} static_descriptor_initializer_pixhawk_2eproto_; + + +// =================================================================== + +#ifndef _MSC_VER +const int HeaderInfo::kSourceSysidFieldNumber; +const int HeaderInfo::kSourceCompidFieldNumber; +const int HeaderInfo::kTimestampFieldNumber; +#endif // !_MSC_VER + +HeaderInfo::HeaderInfo() + : ::google::protobuf::Message() { + SharedCtor(); +} + +void HeaderInfo::InitAsDefaultInstance() { +} + +HeaderInfo::HeaderInfo(const HeaderInfo& from) + : ::google::protobuf::Message() { + SharedCtor(); + MergeFrom(from); +} + +void HeaderInfo::SharedCtor() { + _cached_size_ = 0; + source_sysid_ = 0; + source_compid_ = 0; + timestamp_ = 0; + ::memset(_has_bits_, 0, sizeof(_has_bits_)); +} + +HeaderInfo::~HeaderInfo() { + SharedDtor(); +} + +void HeaderInfo::SharedDtor() { + if (this != default_instance_) { + } +} + +void HeaderInfo::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* HeaderInfo::descriptor() { + protobuf_AssignDescriptorsOnce(); + return HeaderInfo_descriptor_; +} + +const HeaderInfo& HeaderInfo::default_instance() { + if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; +} + +HeaderInfo* HeaderInfo::default_instance_ = NULL; + +HeaderInfo* HeaderInfo::New() const { + return new HeaderInfo; +} + +void HeaderInfo::Clear() { + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + source_sysid_ = 0; + source_compid_ = 0; + timestamp_ = 0; + } + ::memset(_has_bits_, 0, sizeof(_has_bits_)); + mutable_unknown_fields()->Clear(); +} + +bool HeaderInfo::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!(EXPRESSION)) return false + ::google::protobuf::uint32 tag; + while ((tag = input->ReadTag()) != 0) { + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // required int32 source_sysid = 1; + case 1: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &source_sysid_))); + set_has_source_sysid(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(16)) goto parse_source_compid; + break; + } + + // required int32 source_compid = 2; + case 2: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { + parse_source_compid: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &source_compid_))); + set_has_source_compid(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(25)) goto parse_timestamp; + break; + } + + // required double timestamp = 3; + case 3: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { + parse_timestamp: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, ×tamp_))); + set_has_timestamp(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectAtEnd()) return true; + break; + } + + default: { + handle_uninterpreted: + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + return true; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, mutable_unknown_fields())); + break; + } + } + } + return true; +#undef DO_ +} + +void HeaderInfo::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // required int32 source_sysid = 1; + if (has_source_sysid()) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->source_sysid(), output); + } + + // required int32 source_compid = 2; + if (has_source_compid()) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->source_compid(), output); + } + + // required double timestamp = 3; + if (has_timestamp()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->timestamp(), output); + } + + if (!unknown_fields().empty()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + unknown_fields(), output); + } +} + +::google::protobuf::uint8* HeaderInfo::SerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // required int32 source_sysid = 1; + if (has_source_sysid()) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->source_sysid(), target); + } + + // required int32 source_compid = 2; + if (has_source_compid()) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->source_compid(), target); + } + + // required double timestamp = 3; + if (has_timestamp()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->timestamp(), target); + } + + if (!unknown_fields().empty()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + unknown_fields(), target); + } + return target; +} + +int HeaderInfo::ByteSize() const { + int total_size = 0; + + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + // required int32 source_sysid = 1; + if (has_source_sysid()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->source_sysid()); + } + + // required int32 source_compid = 2; + if (has_source_compid()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->source_compid()); + } + + // required double timestamp = 3; + if (has_timestamp()) { + total_size += 1 + 8; + } + + } + if (!unknown_fields().empty()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + unknown_fields()); + } + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = total_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void HeaderInfo::MergeFrom(const ::google::protobuf::Message& from) { + GOOGLE_CHECK_NE(&from, this); + const HeaderInfo* source = + ::google::protobuf::internal::dynamic_cast_if_available( + &from); + if (source == NULL) { + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + MergeFrom(*source); + } +} + +void HeaderInfo::MergeFrom(const HeaderInfo& from) { + GOOGLE_CHECK_NE(&from, this); + if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (from.has_source_sysid()) { + set_source_sysid(from.source_sysid()); + } + if (from.has_source_compid()) { + set_source_compid(from.source_compid()); + } + if (from.has_timestamp()) { + set_timestamp(from.timestamp()); + } + } + mutable_unknown_fields()->MergeFrom(from.unknown_fields()); +} + +void HeaderInfo::CopyFrom(const ::google::protobuf::Message& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void HeaderInfo::CopyFrom(const HeaderInfo& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool HeaderInfo::IsInitialized() const { + if ((_has_bits_[0] & 0x00000007) != 0x00000007) return false; + + return true; +} + +void HeaderInfo::Swap(HeaderInfo* other) { + if (other != this) { + std::swap(source_sysid_, other->source_sysid_); + std::swap(source_compid_, other->source_compid_); + std::swap(timestamp_, other->timestamp_); + std::swap(_has_bits_[0], other->_has_bits_[0]); + _unknown_fields_.Swap(&other->_unknown_fields_); + std::swap(_cached_size_, other->_cached_size_); + } +} + +::google::protobuf::Metadata HeaderInfo::GetMetadata() const { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::Metadata metadata; + metadata.descriptor = HeaderInfo_descriptor_; + metadata.reflection = HeaderInfo_reflection_; + return metadata; +} + + +// =================================================================== + +const ::google::protobuf::EnumDescriptor* GLOverlay_CoordinateFrameType_descriptor() { + protobuf_AssignDescriptorsOnce(); + return GLOverlay_CoordinateFrameType_descriptor_; +} +bool GLOverlay_CoordinateFrameType_IsValid(int value) { + switch(value) { + case 0: + case 1: + return true; + default: + return false; + } +} + +#ifndef _MSC_VER +const GLOverlay_CoordinateFrameType GLOverlay::GLOBAL; +const GLOverlay_CoordinateFrameType GLOverlay::LOCAL; +const GLOverlay_CoordinateFrameType GLOverlay::CoordinateFrameType_MIN; +const GLOverlay_CoordinateFrameType GLOverlay::CoordinateFrameType_MAX; +const int GLOverlay::CoordinateFrameType_ARRAYSIZE; +#endif // _MSC_VER +const ::google::protobuf::EnumDescriptor* GLOverlay_Mode_descriptor() { + protobuf_AssignDescriptorsOnce(); + return GLOverlay_Mode_descriptor_; +} +bool GLOverlay_Mode_IsValid(int value) { + switch(value) { + case 0: + case 1: + case 2: + case 3: + case 4: + case 5: + case 6: + case 7: + case 8: + case 9: + case 10: + case 11: + case 12: + case 13: + return true; + default: + return false; + } +} + +#ifndef _MSC_VER +const GLOverlay_Mode GLOverlay::POINTS; +const GLOverlay_Mode GLOverlay::LINES; +const GLOverlay_Mode GLOverlay::LINE_STRIP; +const GLOverlay_Mode GLOverlay::LINE_LOOP; +const GLOverlay_Mode GLOverlay::TRIANGLES; +const GLOverlay_Mode GLOverlay::TRIANGLE_STRIP; +const GLOverlay_Mode GLOverlay::TRIANGLE_FAN; +const GLOverlay_Mode GLOverlay::QUADS; +const GLOverlay_Mode GLOverlay::QUAD_STRIP; +const GLOverlay_Mode GLOverlay::POLYGON; +const GLOverlay_Mode GLOverlay::SOLID_CIRCLE; +const GLOverlay_Mode GLOverlay::WIRE_CIRCLE; +const GLOverlay_Mode GLOverlay::SOLID_CUBE; +const GLOverlay_Mode GLOverlay::WIRE_CUBE; +const GLOverlay_Mode GLOverlay::Mode_MIN; +const GLOverlay_Mode GLOverlay::Mode_MAX; +const int GLOverlay::Mode_ARRAYSIZE; +#endif // _MSC_VER +const ::google::protobuf::EnumDescriptor* GLOverlay_Identifier_descriptor() { + protobuf_AssignDescriptorsOnce(); + return GLOverlay_Identifier_descriptor_; +} +bool GLOverlay_Identifier_IsValid(int value) { + switch(value) { + case 14: + case 15: + case 16: + case 17: + case 18: + case 19: + case 20: + case 21: + case 22: + case 23: + case 24: + case 25: + return true; + default: + return false; + } +} + +#ifndef _MSC_VER +const GLOverlay_Identifier GLOverlay::END; +const GLOverlay_Identifier GLOverlay::VERTEX2F; +const GLOverlay_Identifier GLOverlay::VERTEX3F; +const GLOverlay_Identifier GLOverlay::ROTATEF; +const GLOverlay_Identifier GLOverlay::TRANSLATEF; +const GLOverlay_Identifier GLOverlay::SCALEF; +const GLOverlay_Identifier GLOverlay::PUSH_MATRIX; +const GLOverlay_Identifier GLOverlay::POP_MATRIX; +const GLOverlay_Identifier GLOverlay::COLOR3F; +const GLOverlay_Identifier GLOverlay::COLOR4F; +const GLOverlay_Identifier GLOverlay::POINTSIZE; +const GLOverlay_Identifier GLOverlay::LINEWIDTH; +const GLOverlay_Identifier GLOverlay::Identifier_MIN; +const GLOverlay_Identifier GLOverlay::Identifier_MAX; +const int GLOverlay::Identifier_ARRAYSIZE; +#endif // _MSC_VER +#ifndef _MSC_VER +const int GLOverlay::kHeaderFieldNumber; +const int GLOverlay::kNameFieldNumber; +const int GLOverlay::kCoordinateFrameTypeFieldNumber; +const int GLOverlay::kOriginXFieldNumber; +const int GLOverlay::kOriginYFieldNumber; +const int GLOverlay::kOriginZFieldNumber; +const int GLOverlay::kDataFieldNumber; +#endif // !_MSC_VER + +GLOverlay::GLOverlay() + : ::google::protobuf::Message() { + SharedCtor(); +} + +void GLOverlay::InitAsDefaultInstance() { + header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); +} + +GLOverlay::GLOverlay(const GLOverlay& from) + : ::google::protobuf::Message() { + SharedCtor(); + MergeFrom(from); +} + +void GLOverlay::SharedCtor() { + _cached_size_ = 0; + header_ = NULL; + name_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); + coordinateframetype_ = 0; + origin_x_ = 0; + origin_y_ = 0; + origin_z_ = 0; + data_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); + ::memset(_has_bits_, 0, sizeof(_has_bits_)); +} + +GLOverlay::~GLOverlay() { + SharedDtor(); +} + +void GLOverlay::SharedDtor() { + if (name_ != &::google::protobuf::internal::kEmptyString) { + delete name_; + } + if (data_ != &::google::protobuf::internal::kEmptyString) { + delete data_; + } + if (this != default_instance_) { + delete header_; + } +} + +void GLOverlay::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* GLOverlay::descriptor() { + protobuf_AssignDescriptorsOnce(); + return GLOverlay_descriptor_; +} + +const GLOverlay& GLOverlay::default_instance() { + if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; +} + +GLOverlay* GLOverlay::default_instance_ = NULL; + +GLOverlay* GLOverlay::New() const { + return new GLOverlay; +} + +void GLOverlay::Clear() { + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (has_header()) { + if (header_ != NULL) header_->::px::HeaderInfo::Clear(); + } + if (has_name()) { + if (name_ != &::google::protobuf::internal::kEmptyString) { + name_->clear(); + } + } + coordinateframetype_ = 0; + origin_x_ = 0; + origin_y_ = 0; + origin_z_ = 0; + if (has_data()) { + if (data_ != &::google::protobuf::internal::kEmptyString) { + data_->clear(); + } + } + } + ::memset(_has_bits_, 0, sizeof(_has_bits_)); + mutable_unknown_fields()->Clear(); +} + +bool GLOverlay::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!(EXPRESSION)) return false + ::google::protobuf::uint32 tag; + while ((tag = input->ReadTag()) != 0) { + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // required .px.HeaderInfo header = 1; + case 1: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_header())); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(18)) goto parse_name; + break; + } + + // optional string name = 2; + case 2: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { + parse_name: + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_name())); + ::google::protobuf::internal::WireFormat::VerifyUTF8String( + this->name().data(), this->name().length(), + ::google::protobuf::internal::WireFormat::PARSE); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(24)) goto parse_coordinateFrameType; + break; + } + + // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3; + case 3: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { + parse_coordinateFrameType: + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + if (::px::GLOverlay_CoordinateFrameType_IsValid(value)) { + set_coordinateframetype(static_cast< ::px::GLOverlay_CoordinateFrameType >(value)); + } else { + mutable_unknown_fields()->AddVarint(3, value); + } + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(33)) goto parse_origin_x; + break; + } + + // optional double origin_x = 4; + case 4: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { + parse_origin_x: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &origin_x_))); + set_has_origin_x(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(41)) goto parse_origin_y; + break; + } + + // optional double origin_y = 5; + case 5: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { + parse_origin_y: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &origin_y_))); + set_has_origin_y(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(49)) goto parse_origin_z; + break; + } + + // optional double origin_z = 6; + case 6: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { + parse_origin_z: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &origin_z_))); + set_has_origin_z(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(58)) goto parse_data; + break; + } + + // optional bytes data = 7; + case 7: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { + parse_data: + DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( + input, this->mutable_data())); + } else { + goto handle_uninterpreted; + } + if (input->ExpectAtEnd()) return true; + break; + } + + default: { + handle_uninterpreted: + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + return true; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, mutable_unknown_fields())); + break; + } + } + } + return true; +#undef DO_ +} + +void GLOverlay::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // required .px.HeaderInfo header = 1; + if (has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->header(), output); + } + + // optional string name = 2; + if (has_name()) { + ::google::protobuf::internal::WireFormat::VerifyUTF8String( + this->name().data(), this->name().length(), + ::google::protobuf::internal::WireFormat::SERIALIZE); + ::google::protobuf::internal::WireFormatLite::WriteString( + 2, this->name(), output); + } + + // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3; + if (has_coordinateframetype()) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 3, this->coordinateframetype(), output); + } + + // optional double origin_x = 4; + if (has_origin_x()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->origin_x(), output); + } + + // optional double origin_y = 5; + if (has_origin_y()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->origin_y(), output); + } + + // optional double origin_z = 6; + if (has_origin_z()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->origin_z(), output); + } + + // optional bytes data = 7; + if (has_data()) { + ::google::protobuf::internal::WireFormatLite::WriteBytes( + 7, this->data(), output); + } + + if (!unknown_fields().empty()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + unknown_fields(), output); + } +} + +::google::protobuf::uint8* GLOverlay::SerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // required .px.HeaderInfo header = 1; + if (has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteMessageNoVirtualToArray( + 1, this->header(), target); + } + + // optional string name = 2; + if (has_name()) { + ::google::protobuf::internal::WireFormat::VerifyUTF8String( + this->name().data(), this->name().length(), + ::google::protobuf::internal::WireFormat::SERIALIZE); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 2, this->name(), target); + } + + // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3; + if (has_coordinateframetype()) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 3, this->coordinateframetype(), target); + } + + // optional double origin_x = 4; + if (has_origin_x()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->origin_x(), target); + } + + // optional double origin_y = 5; + if (has_origin_y()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->origin_y(), target); + } + + // optional double origin_z = 6; + if (has_origin_z()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->origin_z(), target); + } + + // optional bytes data = 7; + if (has_data()) { + target = + ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( + 7, this->data(), target); + } + + if (!unknown_fields().empty()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + unknown_fields(), target); + } + return target; +} + +int GLOverlay::ByteSize() const { + int total_size = 0; + + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + // required .px.HeaderInfo header = 1; + if (has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + this->header()); + } + + // optional string name = 2; + if (has_name()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->name()); + } + + // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3; + if (has_coordinateframetype()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->coordinateframetype()); + } + + // optional double origin_x = 4; + if (has_origin_x()) { + total_size += 1 + 8; + } + + // optional double origin_y = 5; + if (has_origin_y()) { + total_size += 1 + 8; + } + + // optional double origin_z = 6; + if (has_origin_z()) { + total_size += 1 + 8; + } + + // optional bytes data = 7; + if (has_data()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::BytesSize( + this->data()); + } + + } + if (!unknown_fields().empty()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + unknown_fields()); + } + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = total_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void GLOverlay::MergeFrom(const ::google::protobuf::Message& from) { + GOOGLE_CHECK_NE(&from, this); + const GLOverlay* source = + ::google::protobuf::internal::dynamic_cast_if_available( + &from); + if (source == NULL) { + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + MergeFrom(*source); + } +} + +void GLOverlay::MergeFrom(const GLOverlay& from) { + GOOGLE_CHECK_NE(&from, this); + if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (from.has_header()) { + mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); + } + if (from.has_name()) { + set_name(from.name()); + } + if (from.has_coordinateframetype()) { + set_coordinateframetype(from.coordinateframetype()); + } + if (from.has_origin_x()) { + set_origin_x(from.origin_x()); + } + if (from.has_origin_y()) { + set_origin_y(from.origin_y()); + } + if (from.has_origin_z()) { + set_origin_z(from.origin_z()); + } + if (from.has_data()) { + set_data(from.data()); + } + } + mutable_unknown_fields()->MergeFrom(from.unknown_fields()); +} + +void GLOverlay::CopyFrom(const ::google::protobuf::Message& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void GLOverlay::CopyFrom(const GLOverlay& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool GLOverlay::IsInitialized() const { + if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false; + + if (has_header()) { + if (!this->header().IsInitialized()) return false; + } + return true; +} + +void GLOverlay::Swap(GLOverlay* other) { + if (other != this) { + std::swap(header_, other->header_); + std::swap(name_, other->name_); + std::swap(coordinateframetype_, other->coordinateframetype_); + std::swap(origin_x_, other->origin_x_); + std::swap(origin_y_, other->origin_y_); + std::swap(origin_z_, other->origin_z_); + std::swap(data_, other->data_); + std::swap(_has_bits_[0], other->_has_bits_[0]); + _unknown_fields_.Swap(&other->_unknown_fields_); + std::swap(_cached_size_, other->_cached_size_); + } +} + +::google::protobuf::Metadata GLOverlay::GetMetadata() const { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::Metadata metadata; + metadata.descriptor = GLOverlay_descriptor_; + metadata.reflection = GLOverlay_reflection_; + return metadata; +} + + +// =================================================================== + +#ifndef _MSC_VER +const int Obstacle::kXFieldNumber; +const int Obstacle::kYFieldNumber; +const int Obstacle::kZFieldNumber; +const int Obstacle::kLengthFieldNumber; +const int Obstacle::kWidthFieldNumber; +const int Obstacle::kHeightFieldNumber; +#endif // !_MSC_VER + +Obstacle::Obstacle() + : ::google::protobuf::Message() { + SharedCtor(); +} + +void Obstacle::InitAsDefaultInstance() { +} + +Obstacle::Obstacle(const Obstacle& from) + : ::google::protobuf::Message() { + SharedCtor(); + MergeFrom(from); +} + +void Obstacle::SharedCtor() { + _cached_size_ = 0; + x_ = 0; + y_ = 0; + z_ = 0; + length_ = 0; + width_ = 0; + height_ = 0; + ::memset(_has_bits_, 0, sizeof(_has_bits_)); +} + +Obstacle::~Obstacle() { + SharedDtor(); +} + +void Obstacle::SharedDtor() { + if (this != default_instance_) { + } +} + +void Obstacle::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* Obstacle::descriptor() { + protobuf_AssignDescriptorsOnce(); + return Obstacle_descriptor_; +} + +const Obstacle& Obstacle::default_instance() { + if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; +} + +Obstacle* Obstacle::default_instance_ = NULL; + +Obstacle* Obstacle::New() const { + return new Obstacle; +} + +void Obstacle::Clear() { + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + x_ = 0; + y_ = 0; + z_ = 0; + length_ = 0; + width_ = 0; + height_ = 0; + } + ::memset(_has_bits_, 0, sizeof(_has_bits_)); + mutable_unknown_fields()->Clear(); +} + +bool Obstacle::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!(EXPRESSION)) return false + ::google::protobuf::uint32 tag; + while ((tag = input->ReadTag()) != 0) { + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // optional float x = 1; + case 1: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &x_))); + set_has_x(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(21)) goto parse_y; + break; + } + + // optional float y = 2; + case 2: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_y: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &y_))); + set_has_y(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(29)) goto parse_z; + break; + } + + // optional float z = 3; + case 3: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_z: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &z_))); + set_has_z(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(37)) goto parse_length; + break; + } + + // optional float length = 4; + case 4: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_length: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &length_))); + set_has_length(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(45)) goto parse_width; + break; + } + + // optional float width = 5; + case 5: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_width: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &width_))); + set_has_width(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(53)) goto parse_height; + break; + } + + // optional float height = 6; + case 6: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_height: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &height_))); + set_has_height(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectAtEnd()) return true; + break; + } + + default: { + handle_uninterpreted: + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + return true; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, mutable_unknown_fields())); + break; + } + } + } + return true; +#undef DO_ +} + +void Obstacle::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // optional float x = 1; + if (has_x()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->x(), output); + } + + // optional float y = 2; + if (has_y()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->y(), output); + } + + // optional float z = 3; + if (has_z()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->z(), output); + } + + // optional float length = 4; + if (has_length()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->length(), output); + } + + // optional float width = 5; + if (has_width()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(5, this->width(), output); + } + + // optional float height = 6; + if (has_height()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(6, this->height(), output); + } + + if (!unknown_fields().empty()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + unknown_fields(), output); + } +} + +::google::protobuf::uint8* Obstacle::SerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // optional float x = 1; + if (has_x()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->x(), target); + } + + // optional float y = 2; + if (has_y()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->y(), target); + } + + // optional float z = 3; + if (has_z()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->z(), target); + } + + // optional float length = 4; + if (has_length()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->length(), target); + } + + // optional float width = 5; + if (has_width()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(5, this->width(), target); + } + + // optional float height = 6; + if (has_height()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(6, this->height(), target); + } + + if (!unknown_fields().empty()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + unknown_fields(), target); + } + return target; +} + +int Obstacle::ByteSize() const { + int total_size = 0; + + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + // optional float x = 1; + if (has_x()) { + total_size += 1 + 4; + } + + // optional float y = 2; + if (has_y()) { + total_size += 1 + 4; + } + + // optional float z = 3; + if (has_z()) { + total_size += 1 + 4; + } + + // optional float length = 4; + if (has_length()) { + total_size += 1 + 4; + } + + // optional float width = 5; + if (has_width()) { + total_size += 1 + 4; + } + + // optional float height = 6; + if (has_height()) { + total_size += 1 + 4; + } + + } + if (!unknown_fields().empty()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + unknown_fields()); + } + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = total_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void Obstacle::MergeFrom(const ::google::protobuf::Message& from) { + GOOGLE_CHECK_NE(&from, this); + const Obstacle* source = + ::google::protobuf::internal::dynamic_cast_if_available( + &from); + if (source == NULL) { + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + MergeFrom(*source); + } +} + +void Obstacle::MergeFrom(const Obstacle& from) { + GOOGLE_CHECK_NE(&from, this); + if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (from.has_x()) { + set_x(from.x()); + } + if (from.has_y()) { + set_y(from.y()); + } + if (from.has_z()) { + set_z(from.z()); + } + if (from.has_length()) { + set_length(from.length()); + } + if (from.has_width()) { + set_width(from.width()); + } + if (from.has_height()) { + set_height(from.height()); + } + } + mutable_unknown_fields()->MergeFrom(from.unknown_fields()); +} + +void Obstacle::CopyFrom(const ::google::protobuf::Message& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Obstacle::CopyFrom(const Obstacle& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Obstacle::IsInitialized() const { + + return true; +} + +void Obstacle::Swap(Obstacle* other) { + if (other != this) { + std::swap(x_, other->x_); + std::swap(y_, other->y_); + std::swap(z_, other->z_); + std::swap(length_, other->length_); + std::swap(width_, other->width_); + std::swap(height_, other->height_); + std::swap(_has_bits_[0], other->_has_bits_[0]); + _unknown_fields_.Swap(&other->_unknown_fields_); + std::swap(_cached_size_, other->_cached_size_); + } +} + +::google::protobuf::Metadata Obstacle::GetMetadata() const { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::Metadata metadata; + metadata.descriptor = Obstacle_descriptor_; + metadata.reflection = Obstacle_reflection_; + return metadata; +} + + +// =================================================================== + +#ifndef _MSC_VER +const int ObstacleList::kHeaderFieldNumber; +const int ObstacleList::kObstaclesFieldNumber; +#endif // !_MSC_VER + +ObstacleList::ObstacleList() + : ::google::protobuf::Message() { + SharedCtor(); +} + +void ObstacleList::InitAsDefaultInstance() { + header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); +} + +ObstacleList::ObstacleList(const ObstacleList& from) + : ::google::protobuf::Message() { + SharedCtor(); + MergeFrom(from); +} + +void ObstacleList::SharedCtor() { + _cached_size_ = 0; + header_ = NULL; + ::memset(_has_bits_, 0, sizeof(_has_bits_)); +} + +ObstacleList::~ObstacleList() { + SharedDtor(); +} + +void ObstacleList::SharedDtor() { + if (this != default_instance_) { + delete header_; + } +} + +void ObstacleList::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* ObstacleList::descriptor() { + protobuf_AssignDescriptorsOnce(); + return ObstacleList_descriptor_; +} + +const ObstacleList& ObstacleList::default_instance() { + if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; +} + +ObstacleList* ObstacleList::default_instance_ = NULL; + +ObstacleList* ObstacleList::New() const { + return new ObstacleList; +} + +void ObstacleList::Clear() { + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (has_header()) { + if (header_ != NULL) header_->::px::HeaderInfo::Clear(); + } + } + obstacles_.Clear(); + ::memset(_has_bits_, 0, sizeof(_has_bits_)); + mutable_unknown_fields()->Clear(); +} + +bool ObstacleList::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!(EXPRESSION)) return false + ::google::protobuf::uint32 tag; + while ((tag = input->ReadTag()) != 0) { + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // required .px.HeaderInfo header = 1; + case 1: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_header())); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(18)) goto parse_obstacles; + break; + } + + // repeated .px.Obstacle obstacles = 2; + case 2: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { + parse_obstacles: + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, add_obstacles())); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(18)) goto parse_obstacles; + if (input->ExpectAtEnd()) return true; + break; + } + + default: { + handle_uninterpreted: + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + return true; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, mutable_unknown_fields())); + break; + } + } + } + return true; +#undef DO_ +} + +void ObstacleList::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // required .px.HeaderInfo header = 1; + if (has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->header(), output); + } + + // repeated .px.Obstacle obstacles = 2; + for (int i = 0; i < this->obstacles_size(); i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->obstacles(i), output); + } + + if (!unknown_fields().empty()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + unknown_fields(), output); + } +} + +::google::protobuf::uint8* ObstacleList::SerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // required .px.HeaderInfo header = 1; + if (has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteMessageNoVirtualToArray( + 1, this->header(), target); + } + + // repeated .px.Obstacle obstacles = 2; + for (int i = 0; i < this->obstacles_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteMessageNoVirtualToArray( + 2, this->obstacles(i), target); + } + + if (!unknown_fields().empty()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + unknown_fields(), target); + } + return target; +} + +int ObstacleList::ByteSize() const { + int total_size = 0; + + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + // required .px.HeaderInfo header = 1; + if (has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + this->header()); + } + + } + // repeated .px.Obstacle obstacles = 2; + total_size += 1 * this->obstacles_size(); + for (int i = 0; i < this->obstacles_size(); i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + this->obstacles(i)); + } + + if (!unknown_fields().empty()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + unknown_fields()); + } + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = total_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void ObstacleList::MergeFrom(const ::google::protobuf::Message& from) { + GOOGLE_CHECK_NE(&from, this); + const ObstacleList* source = + ::google::protobuf::internal::dynamic_cast_if_available( + &from); + if (source == NULL) { + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + MergeFrom(*source); + } +} + +void ObstacleList::MergeFrom(const ObstacleList& from) { + GOOGLE_CHECK_NE(&from, this); + obstacles_.MergeFrom(from.obstacles_); + if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (from.has_header()) { + mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); + } + } + mutable_unknown_fields()->MergeFrom(from.unknown_fields()); +} + +void ObstacleList::CopyFrom(const ::google::protobuf::Message& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ObstacleList::CopyFrom(const ObstacleList& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ObstacleList::IsInitialized() const { + if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false; + + if (has_header()) { + if (!this->header().IsInitialized()) return false; + } + return true; +} + +void ObstacleList::Swap(ObstacleList* other) { + if (other != this) { + std::swap(header_, other->header_); + obstacles_.Swap(&other->obstacles_); + std::swap(_has_bits_[0], other->_has_bits_[0]); + _unknown_fields_.Swap(&other->_unknown_fields_); + std::swap(_cached_size_, other->_cached_size_); + } +} + +::google::protobuf::Metadata ObstacleList::GetMetadata() const { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::Metadata metadata; + metadata.descriptor = ObstacleList_descriptor_; + metadata.reflection = ObstacleList_reflection_; + return metadata; +} + + +// =================================================================== + +#ifndef _MSC_VER +const int ObstacleMap::kHeaderFieldNumber; +const int ObstacleMap::kTypeFieldNumber; +const int ObstacleMap::kResolutionFieldNumber; +const int ObstacleMap::kRowsFieldNumber; +const int ObstacleMap::kColsFieldNumber; +const int ObstacleMap::kMapR0FieldNumber; +const int ObstacleMap::kMapC0FieldNumber; +const int ObstacleMap::kArrayR0FieldNumber; +const int ObstacleMap::kArrayC0FieldNumber; +const int ObstacleMap::kDataFieldNumber; +#endif // !_MSC_VER + +ObstacleMap::ObstacleMap() + : ::google::protobuf::Message() { + SharedCtor(); +} + +void ObstacleMap::InitAsDefaultInstance() { + header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); +} + +ObstacleMap::ObstacleMap(const ObstacleMap& from) + : ::google::protobuf::Message() { + SharedCtor(); + MergeFrom(from); +} + +void ObstacleMap::SharedCtor() { + _cached_size_ = 0; + header_ = NULL; + type_ = 0; + resolution_ = 0; + rows_ = 0; + cols_ = 0; + mapr0_ = 0; + mapc0_ = 0; + arrayr0_ = 0; + arrayc0_ = 0; + data_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); + ::memset(_has_bits_, 0, sizeof(_has_bits_)); +} + +ObstacleMap::~ObstacleMap() { + SharedDtor(); +} + +void ObstacleMap::SharedDtor() { + if (data_ != &::google::protobuf::internal::kEmptyString) { + delete data_; + } + if (this != default_instance_) { + delete header_; + } +} + +void ObstacleMap::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* ObstacleMap::descriptor() { + protobuf_AssignDescriptorsOnce(); + return ObstacleMap_descriptor_; +} + +const ObstacleMap& ObstacleMap::default_instance() { + if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; +} + +ObstacleMap* ObstacleMap::default_instance_ = NULL; + +ObstacleMap* ObstacleMap::New() const { + return new ObstacleMap; +} + +void ObstacleMap::Clear() { + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (has_header()) { + if (header_ != NULL) header_->::px::HeaderInfo::Clear(); + } + type_ = 0; + resolution_ = 0; + rows_ = 0; + cols_ = 0; + mapr0_ = 0; + mapc0_ = 0; + arrayr0_ = 0; + } + if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) { + arrayc0_ = 0; + if (has_data()) { + if (data_ != &::google::protobuf::internal::kEmptyString) { + data_->clear(); + } + } + } + ::memset(_has_bits_, 0, sizeof(_has_bits_)); + mutable_unknown_fields()->Clear(); +} + +bool ObstacleMap::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!(EXPRESSION)) return false + ::google::protobuf::uint32 tag; + while ((tag = input->ReadTag()) != 0) { + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // required .px.HeaderInfo header = 1; + case 1: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_header())); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(16)) goto parse_type; + break; + } + + // required int32 type = 2; + case 2: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { + parse_type: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &type_))); + set_has_type(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(29)) goto parse_resolution; + break; + } + + // optional float resolution = 3; + case 3: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_resolution: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &resolution_))); + set_has_resolution(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(32)) goto parse_rows; + break; + } + + // optional int32 rows = 4; + case 4: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { + parse_rows: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &rows_))); + set_has_rows(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(40)) goto parse_cols; + break; + } + + // optional int32 cols = 5; + case 5: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { + parse_cols: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &cols_))); + set_has_cols(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(48)) goto parse_mapR0; + break; + } + + // optional int32 mapR0 = 6; + case 6: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { + parse_mapR0: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &mapr0_))); + set_has_mapr0(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(56)) goto parse_mapC0; + break; + } + + // optional int32 mapC0 = 7; + case 7: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { + parse_mapC0: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &mapc0_))); + set_has_mapc0(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(64)) goto parse_arrayR0; + break; + } + + // optional int32 arrayR0 = 8; + case 8: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { + parse_arrayR0: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &arrayr0_))); + set_has_arrayr0(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(72)) goto parse_arrayC0; + break; + } + + // optional int32 arrayC0 = 9; + case 9: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { + parse_arrayC0: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &arrayc0_))); + set_has_arrayc0(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(82)) goto parse_data; + break; + } + + // optional bytes data = 10; + case 10: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { + parse_data: + DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( + input, this->mutable_data())); + } else { + goto handle_uninterpreted; + } + if (input->ExpectAtEnd()) return true; + break; + } + + default: { + handle_uninterpreted: + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + return true; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, mutable_unknown_fields())); + break; + } + } + } + return true; +#undef DO_ +} + +void ObstacleMap::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // required .px.HeaderInfo header = 1; + if (has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->header(), output); + } + + // required int32 type = 2; + if (has_type()) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->type(), output); + } + + // optional float resolution = 3; + if (has_resolution()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->resolution(), output); + } + + // optional int32 rows = 4; + if (has_rows()) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(4, this->rows(), output); + } + + // optional int32 cols = 5; + if (has_cols()) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(5, this->cols(), output); + } + + // optional int32 mapR0 = 6; + if (has_mapr0()) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(6, this->mapr0(), output); + } + + // optional int32 mapC0 = 7; + if (has_mapc0()) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(7, this->mapc0(), output); + } + + // optional int32 arrayR0 = 8; + if (has_arrayr0()) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(8, this->arrayr0(), output); + } + + // optional int32 arrayC0 = 9; + if (has_arrayc0()) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(9, this->arrayc0(), output); + } + + // optional bytes data = 10; + if (has_data()) { + ::google::protobuf::internal::WireFormatLite::WriteBytes( + 10, this->data(), output); + } + + if (!unknown_fields().empty()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + unknown_fields(), output); + } +} + +::google::protobuf::uint8* ObstacleMap::SerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // required .px.HeaderInfo header = 1; + if (has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteMessageNoVirtualToArray( + 1, this->header(), target); + } + + // required int32 type = 2; + if (has_type()) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->type(), target); + } + + // optional float resolution = 3; + if (has_resolution()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->resolution(), target); + } + + // optional int32 rows = 4; + if (has_rows()) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(4, this->rows(), target); + } + + // optional int32 cols = 5; + if (has_cols()) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(5, this->cols(), target); + } + + // optional int32 mapR0 = 6; + if (has_mapr0()) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(6, this->mapr0(), target); + } + + // optional int32 mapC0 = 7; + if (has_mapc0()) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(7, this->mapc0(), target); + } + + // optional int32 arrayR0 = 8; + if (has_arrayr0()) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(8, this->arrayr0(), target); + } + + // optional int32 arrayC0 = 9; + if (has_arrayc0()) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(9, this->arrayc0(), target); + } + + // optional bytes data = 10; + if (has_data()) { + target = + ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( + 10, this->data(), target); + } + + if (!unknown_fields().empty()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + unknown_fields(), target); + } + return target; +} + +int ObstacleMap::ByteSize() const { + int total_size = 0; + + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + // required .px.HeaderInfo header = 1; + if (has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + this->header()); + } + + // required int32 type = 2; + if (has_type()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->type()); + } + + // optional float resolution = 3; + if (has_resolution()) { + total_size += 1 + 4; + } + + // optional int32 rows = 4; + if (has_rows()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->rows()); + } + + // optional int32 cols = 5; + if (has_cols()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->cols()); + } + + // optional int32 mapR0 = 6; + if (has_mapr0()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->mapr0()); + } + + // optional int32 mapC0 = 7; + if (has_mapc0()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->mapc0()); + } + + // optional int32 arrayR0 = 8; + if (has_arrayr0()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->arrayr0()); + } + + } + if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) { + // optional int32 arrayC0 = 9; + if (has_arrayc0()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->arrayc0()); + } + + // optional bytes data = 10; + if (has_data()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::BytesSize( + this->data()); + } + + } + if (!unknown_fields().empty()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + unknown_fields()); + } + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = total_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void ObstacleMap::MergeFrom(const ::google::protobuf::Message& from) { + GOOGLE_CHECK_NE(&from, this); + const ObstacleMap* source = + ::google::protobuf::internal::dynamic_cast_if_available( + &from); + if (source == NULL) { + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + MergeFrom(*source); + } +} + +void ObstacleMap::MergeFrom(const ObstacleMap& from) { + GOOGLE_CHECK_NE(&from, this); + if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (from.has_header()) { + mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); + } + if (from.has_type()) { + set_type(from.type()); + } + if (from.has_resolution()) { + set_resolution(from.resolution()); + } + if (from.has_rows()) { + set_rows(from.rows()); + } + if (from.has_cols()) { + set_cols(from.cols()); + } + if (from.has_mapr0()) { + set_mapr0(from.mapr0()); + } + if (from.has_mapc0()) { + set_mapc0(from.mapc0()); + } + if (from.has_arrayr0()) { + set_arrayr0(from.arrayr0()); + } + } + if (from._has_bits_[8 / 32] & (0xffu << (8 % 32))) { + if (from.has_arrayc0()) { + set_arrayc0(from.arrayc0()); + } + if (from.has_data()) { + set_data(from.data()); + } + } + mutable_unknown_fields()->MergeFrom(from.unknown_fields()); +} + +void ObstacleMap::CopyFrom(const ::google::protobuf::Message& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ObstacleMap::CopyFrom(const ObstacleMap& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ObstacleMap::IsInitialized() const { + if ((_has_bits_[0] & 0x00000003) != 0x00000003) return false; + + if (has_header()) { + if (!this->header().IsInitialized()) return false; + } + return true; +} + +void ObstacleMap::Swap(ObstacleMap* other) { + if (other != this) { + std::swap(header_, other->header_); + std::swap(type_, other->type_); + std::swap(resolution_, other->resolution_); + std::swap(rows_, other->rows_); + std::swap(cols_, other->cols_); + std::swap(mapr0_, other->mapr0_); + std::swap(mapc0_, other->mapc0_); + std::swap(arrayr0_, other->arrayr0_); + std::swap(arrayc0_, other->arrayc0_); + std::swap(data_, other->data_); + std::swap(_has_bits_[0], other->_has_bits_[0]); + _unknown_fields_.Swap(&other->_unknown_fields_); + std::swap(_cached_size_, other->_cached_size_); + } +} + +::google::protobuf::Metadata ObstacleMap::GetMetadata() const { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::Metadata metadata; + metadata.descriptor = ObstacleMap_descriptor_; + metadata.reflection = ObstacleMap_reflection_; + return metadata; +} + + +// =================================================================== + +#ifndef _MSC_VER +const int Path::kHeaderFieldNumber; +const int Path::kWaypointsFieldNumber; +#endif // !_MSC_VER + +Path::Path() + : ::google::protobuf::Message() { + SharedCtor(); +} + +void Path::InitAsDefaultInstance() { + header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); +} + +Path::Path(const Path& from) + : ::google::protobuf::Message() { + SharedCtor(); + MergeFrom(from); +} + +void Path::SharedCtor() { + _cached_size_ = 0; + header_ = NULL; + ::memset(_has_bits_, 0, sizeof(_has_bits_)); +} + +Path::~Path() { + SharedDtor(); +} + +void Path::SharedDtor() { + if (this != default_instance_) { + delete header_; + } +} + +void Path::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* Path::descriptor() { + protobuf_AssignDescriptorsOnce(); + return Path_descriptor_; +} + +const Path& Path::default_instance() { + if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; +} + +Path* Path::default_instance_ = NULL; + +Path* Path::New() const { + return new Path; +} + +void Path::Clear() { + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (has_header()) { + if (header_ != NULL) header_->::px::HeaderInfo::Clear(); + } + } + waypoints_.Clear(); + ::memset(_has_bits_, 0, sizeof(_has_bits_)); + mutable_unknown_fields()->Clear(); +} + +bool Path::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!(EXPRESSION)) return false + ::google::protobuf::uint32 tag; + while ((tag = input->ReadTag()) != 0) { + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // required .px.HeaderInfo header = 1; + case 1: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_header())); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(18)) goto parse_waypoints; + break; + } + + // repeated .px.Waypoint waypoints = 2; + case 2: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { + parse_waypoints: + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, add_waypoints())); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(18)) goto parse_waypoints; + if (input->ExpectAtEnd()) return true; + break; + } + + default: { + handle_uninterpreted: + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + return true; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, mutable_unknown_fields())); + break; + } + } + } + return true; +#undef DO_ +} + +void Path::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // required .px.HeaderInfo header = 1; + if (has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->header(), output); + } + + // repeated .px.Waypoint waypoints = 2; + for (int i = 0; i < this->waypoints_size(); i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->waypoints(i), output); + } + + if (!unknown_fields().empty()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + unknown_fields(), output); + } +} + +::google::protobuf::uint8* Path::SerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // required .px.HeaderInfo header = 1; + if (has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteMessageNoVirtualToArray( + 1, this->header(), target); + } + + // repeated .px.Waypoint waypoints = 2; + for (int i = 0; i < this->waypoints_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteMessageNoVirtualToArray( + 2, this->waypoints(i), target); + } + + if (!unknown_fields().empty()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + unknown_fields(), target); + } + return target; +} + +int Path::ByteSize() const { + int total_size = 0; + + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + // required .px.HeaderInfo header = 1; + if (has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + this->header()); + } + + } + // repeated .px.Waypoint waypoints = 2; + total_size += 1 * this->waypoints_size(); + for (int i = 0; i < this->waypoints_size(); i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + this->waypoints(i)); + } + + if (!unknown_fields().empty()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + unknown_fields()); + } + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = total_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void Path::MergeFrom(const ::google::protobuf::Message& from) { + GOOGLE_CHECK_NE(&from, this); + const Path* source = + ::google::protobuf::internal::dynamic_cast_if_available( + &from); + if (source == NULL) { + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + MergeFrom(*source); + } +} + +void Path::MergeFrom(const Path& from) { + GOOGLE_CHECK_NE(&from, this); + waypoints_.MergeFrom(from.waypoints_); + if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (from.has_header()) { + mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); + } + } + mutable_unknown_fields()->MergeFrom(from.unknown_fields()); +} + +void Path::CopyFrom(const ::google::protobuf::Message& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Path::CopyFrom(const Path& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Path::IsInitialized() const { + if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false; + + if (has_header()) { + if (!this->header().IsInitialized()) return false; + } + for (int i = 0; i < waypoints_size(); i++) { + if (!this->waypoints(i).IsInitialized()) return false; + } + return true; +} + +void Path::Swap(Path* other) { + if (other != this) { + std::swap(header_, other->header_); + waypoints_.Swap(&other->waypoints_); + std::swap(_has_bits_[0], other->_has_bits_[0]); + _unknown_fields_.Swap(&other->_unknown_fields_); + std::swap(_cached_size_, other->_cached_size_); + } +} + +::google::protobuf::Metadata Path::GetMetadata() const { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::Metadata metadata; + metadata.descriptor = Path_descriptor_; + metadata.reflection = Path_reflection_; + return metadata; +} + + +// =================================================================== + +#ifndef _MSC_VER +const int PointCloudXYZI_PointXYZI::kXFieldNumber; +const int PointCloudXYZI_PointXYZI::kYFieldNumber; +const int PointCloudXYZI_PointXYZI::kZFieldNumber; +const int PointCloudXYZI_PointXYZI::kIntensityFieldNumber; +#endif // !_MSC_VER + +PointCloudXYZI_PointXYZI::PointCloudXYZI_PointXYZI() + : ::google::protobuf::Message() { + SharedCtor(); +} + +void PointCloudXYZI_PointXYZI::InitAsDefaultInstance() { +} + +PointCloudXYZI_PointXYZI::PointCloudXYZI_PointXYZI(const PointCloudXYZI_PointXYZI& from) + : ::google::protobuf::Message() { + SharedCtor(); + MergeFrom(from); +} + +void PointCloudXYZI_PointXYZI::SharedCtor() { + _cached_size_ = 0; + x_ = 0; + y_ = 0; + z_ = 0; + intensity_ = 0; + ::memset(_has_bits_, 0, sizeof(_has_bits_)); +} + +PointCloudXYZI_PointXYZI::~PointCloudXYZI_PointXYZI() { + SharedDtor(); +} + +void PointCloudXYZI_PointXYZI::SharedDtor() { + if (this != default_instance_) { + } +} + +void PointCloudXYZI_PointXYZI::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* PointCloudXYZI_PointXYZI::descriptor() { + protobuf_AssignDescriptorsOnce(); + return PointCloudXYZI_PointXYZI_descriptor_; +} + +const PointCloudXYZI_PointXYZI& PointCloudXYZI_PointXYZI::default_instance() { + if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; +} + +PointCloudXYZI_PointXYZI* PointCloudXYZI_PointXYZI::default_instance_ = NULL; + +PointCloudXYZI_PointXYZI* PointCloudXYZI_PointXYZI::New() const { + return new PointCloudXYZI_PointXYZI; +} + +void PointCloudXYZI_PointXYZI::Clear() { + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + x_ = 0; + y_ = 0; + z_ = 0; + intensity_ = 0; + } + ::memset(_has_bits_, 0, sizeof(_has_bits_)); + mutable_unknown_fields()->Clear(); +} + +bool PointCloudXYZI_PointXYZI::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!(EXPRESSION)) return false + ::google::protobuf::uint32 tag; + while ((tag = input->ReadTag()) != 0) { + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // required float x = 1; + case 1: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &x_))); + set_has_x(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(21)) goto parse_y; + break; + } + + // required float y = 2; + case 2: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_y: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &y_))); + set_has_y(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(29)) goto parse_z; + break; + } + + // required float z = 3; + case 3: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_z: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &z_))); + set_has_z(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(37)) goto parse_intensity; + break; + } + + // required float intensity = 4; + case 4: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_intensity: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &intensity_))); + set_has_intensity(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectAtEnd()) return true; + break; + } + + default: { + handle_uninterpreted: + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + return true; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, mutable_unknown_fields())); + break; + } + } + } + return true; +#undef DO_ +} + +void PointCloudXYZI_PointXYZI::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // required float x = 1; + if (has_x()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->x(), output); + } + + // required float y = 2; + if (has_y()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->y(), output); + } + + // required float z = 3; + if (has_z()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->z(), output); + } + + // required float intensity = 4; + if (has_intensity()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->intensity(), output); + } + + if (!unknown_fields().empty()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + unknown_fields(), output); + } +} + +::google::protobuf::uint8* PointCloudXYZI_PointXYZI::SerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // required float x = 1; + if (has_x()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->x(), target); + } + + // required float y = 2; + if (has_y()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->y(), target); + } + + // required float z = 3; + if (has_z()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->z(), target); + } + + // required float intensity = 4; + if (has_intensity()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->intensity(), target); + } + + if (!unknown_fields().empty()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + unknown_fields(), target); + } + return target; +} + +int PointCloudXYZI_PointXYZI::ByteSize() const { + int total_size = 0; + + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + // required float x = 1; + if (has_x()) { + total_size += 1 + 4; + } + + // required float y = 2; + if (has_y()) { + total_size += 1 + 4; + } + + // required float z = 3; + if (has_z()) { + total_size += 1 + 4; + } + + // required float intensity = 4; + if (has_intensity()) { + total_size += 1 + 4; + } + + } + if (!unknown_fields().empty()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + unknown_fields()); + } + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = total_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void PointCloudXYZI_PointXYZI::MergeFrom(const ::google::protobuf::Message& from) { + GOOGLE_CHECK_NE(&from, this); + const PointCloudXYZI_PointXYZI* source = + ::google::protobuf::internal::dynamic_cast_if_available( + &from); + if (source == NULL) { + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + MergeFrom(*source); + } +} + +void PointCloudXYZI_PointXYZI::MergeFrom(const PointCloudXYZI_PointXYZI& from) { + GOOGLE_CHECK_NE(&from, this); + if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (from.has_x()) { + set_x(from.x()); + } + if (from.has_y()) { + set_y(from.y()); + } + if (from.has_z()) { + set_z(from.z()); + } + if (from.has_intensity()) { + set_intensity(from.intensity()); + } + } + mutable_unknown_fields()->MergeFrom(from.unknown_fields()); +} + +void PointCloudXYZI_PointXYZI::CopyFrom(const ::google::protobuf::Message& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PointCloudXYZI_PointXYZI::CopyFrom(const PointCloudXYZI_PointXYZI& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PointCloudXYZI_PointXYZI::IsInitialized() const { + if ((_has_bits_[0] & 0x0000000f) != 0x0000000f) return false; + + return true; +} + +void PointCloudXYZI_PointXYZI::Swap(PointCloudXYZI_PointXYZI* other) { + if (other != this) { + std::swap(x_, other->x_); + std::swap(y_, other->y_); + std::swap(z_, other->z_); + std::swap(intensity_, other->intensity_); + std::swap(_has_bits_[0], other->_has_bits_[0]); + _unknown_fields_.Swap(&other->_unknown_fields_); + std::swap(_cached_size_, other->_cached_size_); + } +} + +::google::protobuf::Metadata PointCloudXYZI_PointXYZI::GetMetadata() const { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::Metadata metadata; + metadata.descriptor = PointCloudXYZI_PointXYZI_descriptor_; + metadata.reflection = PointCloudXYZI_PointXYZI_reflection_; + return metadata; +} + + +// ------------------------------------------------------------------- + +#ifndef _MSC_VER +const int PointCloudXYZI::kHeaderFieldNumber; +const int PointCloudXYZI::kPointsFieldNumber; +#endif // !_MSC_VER + +PointCloudXYZI::PointCloudXYZI() + : ::google::protobuf::Message() { + SharedCtor(); +} + +void PointCloudXYZI::InitAsDefaultInstance() { + header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); +} + +PointCloudXYZI::PointCloudXYZI(const PointCloudXYZI& from) + : ::google::protobuf::Message() { + SharedCtor(); + MergeFrom(from); +} + +void PointCloudXYZI::SharedCtor() { + _cached_size_ = 0; + header_ = NULL; + ::memset(_has_bits_, 0, sizeof(_has_bits_)); +} + +PointCloudXYZI::~PointCloudXYZI() { + SharedDtor(); +} + +void PointCloudXYZI::SharedDtor() { + if (this != default_instance_) { + delete header_; + } +} + +void PointCloudXYZI::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* PointCloudXYZI::descriptor() { + protobuf_AssignDescriptorsOnce(); + return PointCloudXYZI_descriptor_; +} + +const PointCloudXYZI& PointCloudXYZI::default_instance() { + if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; +} + +PointCloudXYZI* PointCloudXYZI::default_instance_ = NULL; + +PointCloudXYZI* PointCloudXYZI::New() const { + return new PointCloudXYZI; +} + +void PointCloudXYZI::Clear() { + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (has_header()) { + if (header_ != NULL) header_->::px::HeaderInfo::Clear(); + } + } + points_.Clear(); + ::memset(_has_bits_, 0, sizeof(_has_bits_)); + mutable_unknown_fields()->Clear(); +} + +bool PointCloudXYZI::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!(EXPRESSION)) return false + ::google::protobuf::uint32 tag; + while ((tag = input->ReadTag()) != 0) { + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // required .px.HeaderInfo header = 1; + case 1: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_header())); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(18)) goto parse_points; + break; + } + + // repeated .px.PointCloudXYZI.PointXYZI points = 2; + case 2: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { + parse_points: + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, add_points())); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(18)) goto parse_points; + if (input->ExpectAtEnd()) return true; + break; + } + + default: { + handle_uninterpreted: + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + return true; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, mutable_unknown_fields())); + break; + } + } + } + return true; +#undef DO_ +} + +void PointCloudXYZI::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // required .px.HeaderInfo header = 1; + if (has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->header(), output); + } + + // repeated .px.PointCloudXYZI.PointXYZI points = 2; + for (int i = 0; i < this->points_size(); i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->points(i), output); + } + + if (!unknown_fields().empty()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + unknown_fields(), output); + } +} + +::google::protobuf::uint8* PointCloudXYZI::SerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // required .px.HeaderInfo header = 1; + if (has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteMessageNoVirtualToArray( + 1, this->header(), target); + } + + // repeated .px.PointCloudXYZI.PointXYZI points = 2; + for (int i = 0; i < this->points_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteMessageNoVirtualToArray( + 2, this->points(i), target); + } + + if (!unknown_fields().empty()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + unknown_fields(), target); + } + return target; +} + +int PointCloudXYZI::ByteSize() const { + int total_size = 0; + + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + // required .px.HeaderInfo header = 1; + if (has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + this->header()); + } + + } + // repeated .px.PointCloudXYZI.PointXYZI points = 2; + total_size += 1 * this->points_size(); + for (int i = 0; i < this->points_size(); i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + this->points(i)); + } + + if (!unknown_fields().empty()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + unknown_fields()); + } + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = total_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void PointCloudXYZI::MergeFrom(const ::google::protobuf::Message& from) { + GOOGLE_CHECK_NE(&from, this); + const PointCloudXYZI* source = + ::google::protobuf::internal::dynamic_cast_if_available( + &from); + if (source == NULL) { + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + MergeFrom(*source); + } +} + +void PointCloudXYZI::MergeFrom(const PointCloudXYZI& from) { + GOOGLE_CHECK_NE(&from, this); + points_.MergeFrom(from.points_); + if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (from.has_header()) { + mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); + } + } + mutable_unknown_fields()->MergeFrom(from.unknown_fields()); +} + +void PointCloudXYZI::CopyFrom(const ::google::protobuf::Message& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PointCloudXYZI::CopyFrom(const PointCloudXYZI& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PointCloudXYZI::IsInitialized() const { + if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false; + + if (has_header()) { + if (!this->header().IsInitialized()) return false; + } + for (int i = 0; i < points_size(); i++) { + if (!this->points(i).IsInitialized()) return false; + } + return true; +} + +void PointCloudXYZI::Swap(PointCloudXYZI* other) { + if (other != this) { + std::swap(header_, other->header_); + points_.Swap(&other->points_); + std::swap(_has_bits_[0], other->_has_bits_[0]); + _unknown_fields_.Swap(&other->_unknown_fields_); + std::swap(_cached_size_, other->_cached_size_); + } +} + +::google::protobuf::Metadata PointCloudXYZI::GetMetadata() const { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::Metadata metadata; + metadata.descriptor = PointCloudXYZI_descriptor_; + metadata.reflection = PointCloudXYZI_reflection_; + return metadata; +} + + +// =================================================================== + +#ifndef _MSC_VER +const int PointCloudXYZRGB_PointXYZRGB::kXFieldNumber; +const int PointCloudXYZRGB_PointXYZRGB::kYFieldNumber; +const int PointCloudXYZRGB_PointXYZRGB::kZFieldNumber; +const int PointCloudXYZRGB_PointXYZRGB::kRgbFieldNumber; +#endif // !_MSC_VER + +PointCloudXYZRGB_PointXYZRGB::PointCloudXYZRGB_PointXYZRGB() + : ::google::protobuf::Message() { + SharedCtor(); +} + +void PointCloudXYZRGB_PointXYZRGB::InitAsDefaultInstance() { +} + +PointCloudXYZRGB_PointXYZRGB::PointCloudXYZRGB_PointXYZRGB(const PointCloudXYZRGB_PointXYZRGB& from) + : ::google::protobuf::Message() { + SharedCtor(); + MergeFrom(from); +} + +void PointCloudXYZRGB_PointXYZRGB::SharedCtor() { + _cached_size_ = 0; + x_ = 0; + y_ = 0; + z_ = 0; + rgb_ = 0; + ::memset(_has_bits_, 0, sizeof(_has_bits_)); +} + +PointCloudXYZRGB_PointXYZRGB::~PointCloudXYZRGB_PointXYZRGB() { + SharedDtor(); +} + +void PointCloudXYZRGB_PointXYZRGB::SharedDtor() { + if (this != default_instance_) { + } +} + +void PointCloudXYZRGB_PointXYZRGB::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* PointCloudXYZRGB_PointXYZRGB::descriptor() { + protobuf_AssignDescriptorsOnce(); + return PointCloudXYZRGB_PointXYZRGB_descriptor_; +} + +const PointCloudXYZRGB_PointXYZRGB& PointCloudXYZRGB_PointXYZRGB::default_instance() { + if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; +} + +PointCloudXYZRGB_PointXYZRGB* PointCloudXYZRGB_PointXYZRGB::default_instance_ = NULL; + +PointCloudXYZRGB_PointXYZRGB* PointCloudXYZRGB_PointXYZRGB::New() const { + return new PointCloudXYZRGB_PointXYZRGB; +} + +void PointCloudXYZRGB_PointXYZRGB::Clear() { + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + x_ = 0; + y_ = 0; + z_ = 0; + rgb_ = 0; + } + ::memset(_has_bits_, 0, sizeof(_has_bits_)); + mutable_unknown_fields()->Clear(); +} + +bool PointCloudXYZRGB_PointXYZRGB::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!(EXPRESSION)) return false + ::google::protobuf::uint32 tag; + while ((tag = input->ReadTag()) != 0) { + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // required float x = 1; + case 1: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &x_))); + set_has_x(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(21)) goto parse_y; + break; + } + + // required float y = 2; + case 2: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_y: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &y_))); + set_has_y(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(29)) goto parse_z; + break; + } + + // required float z = 3; + case 3: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_z: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &z_))); + set_has_z(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(37)) goto parse_rgb; + break; + } + + // required float rgb = 4; + case 4: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_rgb: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &rgb_))); + set_has_rgb(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectAtEnd()) return true; + break; + } + + default: { + handle_uninterpreted: + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + return true; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, mutable_unknown_fields())); + break; + } + } + } + return true; +#undef DO_ +} + +void PointCloudXYZRGB_PointXYZRGB::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // required float x = 1; + if (has_x()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->x(), output); + } + + // required float y = 2; + if (has_y()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->y(), output); + } + + // required float z = 3; + if (has_z()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->z(), output); + } + + // required float rgb = 4; + if (has_rgb()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->rgb(), output); + } + + if (!unknown_fields().empty()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + unknown_fields(), output); + } +} + +::google::protobuf::uint8* PointCloudXYZRGB_PointXYZRGB::SerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // required float x = 1; + if (has_x()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->x(), target); + } + + // required float y = 2; + if (has_y()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->y(), target); + } + + // required float z = 3; + if (has_z()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->z(), target); + } + + // required float rgb = 4; + if (has_rgb()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->rgb(), target); + } + + if (!unknown_fields().empty()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + unknown_fields(), target); + } + return target; +} + +int PointCloudXYZRGB_PointXYZRGB::ByteSize() const { + int total_size = 0; + + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + // required float x = 1; + if (has_x()) { + total_size += 1 + 4; + } + + // required float y = 2; + if (has_y()) { + total_size += 1 + 4; + } + + // required float z = 3; + if (has_z()) { + total_size += 1 + 4; + } + + // required float rgb = 4; + if (has_rgb()) { + total_size += 1 + 4; + } + + } + if (!unknown_fields().empty()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + unknown_fields()); + } + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = total_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void PointCloudXYZRGB_PointXYZRGB::MergeFrom(const ::google::protobuf::Message& from) { + GOOGLE_CHECK_NE(&from, this); + const PointCloudXYZRGB_PointXYZRGB* source = + ::google::protobuf::internal::dynamic_cast_if_available( + &from); + if (source == NULL) { + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + MergeFrom(*source); + } +} + +void PointCloudXYZRGB_PointXYZRGB::MergeFrom(const PointCloudXYZRGB_PointXYZRGB& from) { + GOOGLE_CHECK_NE(&from, this); + if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (from.has_x()) { + set_x(from.x()); + } + if (from.has_y()) { + set_y(from.y()); + } + if (from.has_z()) { + set_z(from.z()); + } + if (from.has_rgb()) { + set_rgb(from.rgb()); + } + } + mutable_unknown_fields()->MergeFrom(from.unknown_fields()); +} + +void PointCloudXYZRGB_PointXYZRGB::CopyFrom(const ::google::protobuf::Message& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PointCloudXYZRGB_PointXYZRGB::CopyFrom(const PointCloudXYZRGB_PointXYZRGB& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PointCloudXYZRGB_PointXYZRGB::IsInitialized() const { + if ((_has_bits_[0] & 0x0000000f) != 0x0000000f) return false; + + return true; +} + +void PointCloudXYZRGB_PointXYZRGB::Swap(PointCloudXYZRGB_PointXYZRGB* other) { + if (other != this) { + std::swap(x_, other->x_); + std::swap(y_, other->y_); + std::swap(z_, other->z_); + std::swap(rgb_, other->rgb_); + std::swap(_has_bits_[0], other->_has_bits_[0]); + _unknown_fields_.Swap(&other->_unknown_fields_); + std::swap(_cached_size_, other->_cached_size_); + } +} + +::google::protobuf::Metadata PointCloudXYZRGB_PointXYZRGB::GetMetadata() const { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::Metadata metadata; + metadata.descriptor = PointCloudXYZRGB_PointXYZRGB_descriptor_; + metadata.reflection = PointCloudXYZRGB_PointXYZRGB_reflection_; + return metadata; +} + + +// ------------------------------------------------------------------- + +#ifndef _MSC_VER +const int PointCloudXYZRGB::kHeaderFieldNumber; +const int PointCloudXYZRGB::kPointsFieldNumber; +#endif // !_MSC_VER + +PointCloudXYZRGB::PointCloudXYZRGB() + : ::google::protobuf::Message() { + SharedCtor(); +} + +void PointCloudXYZRGB::InitAsDefaultInstance() { + header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); +} + +PointCloudXYZRGB::PointCloudXYZRGB(const PointCloudXYZRGB& from) + : ::google::protobuf::Message() { + SharedCtor(); + MergeFrom(from); +} + +void PointCloudXYZRGB::SharedCtor() { + _cached_size_ = 0; + header_ = NULL; + ::memset(_has_bits_, 0, sizeof(_has_bits_)); +} + +PointCloudXYZRGB::~PointCloudXYZRGB() { + SharedDtor(); +} + +void PointCloudXYZRGB::SharedDtor() { + if (this != default_instance_) { + delete header_; + } +} + +void PointCloudXYZRGB::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* PointCloudXYZRGB::descriptor() { + protobuf_AssignDescriptorsOnce(); + return PointCloudXYZRGB_descriptor_; +} + +const PointCloudXYZRGB& PointCloudXYZRGB::default_instance() { + if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; +} + +PointCloudXYZRGB* PointCloudXYZRGB::default_instance_ = NULL; + +PointCloudXYZRGB* PointCloudXYZRGB::New() const { + return new PointCloudXYZRGB; +} + +void PointCloudXYZRGB::Clear() { + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (has_header()) { + if (header_ != NULL) header_->::px::HeaderInfo::Clear(); + } + } + points_.Clear(); + ::memset(_has_bits_, 0, sizeof(_has_bits_)); + mutable_unknown_fields()->Clear(); +} + +bool PointCloudXYZRGB::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!(EXPRESSION)) return false + ::google::protobuf::uint32 tag; + while ((tag = input->ReadTag()) != 0) { + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // required .px.HeaderInfo header = 1; + case 1: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_header())); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(18)) goto parse_points; + break; + } + + // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2; + case 2: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { + parse_points: + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, add_points())); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(18)) goto parse_points; + if (input->ExpectAtEnd()) return true; + break; + } + + default: { + handle_uninterpreted: + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + return true; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, mutable_unknown_fields())); + break; + } + } + } + return true; +#undef DO_ +} + +void PointCloudXYZRGB::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // required .px.HeaderInfo header = 1; + if (has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->header(), output); + } + + // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2; + for (int i = 0; i < this->points_size(); i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->points(i), output); + } + + if (!unknown_fields().empty()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + unknown_fields(), output); + } +} + +::google::protobuf::uint8* PointCloudXYZRGB::SerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // required .px.HeaderInfo header = 1; + if (has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteMessageNoVirtualToArray( + 1, this->header(), target); + } + + // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2; + for (int i = 0; i < this->points_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteMessageNoVirtualToArray( + 2, this->points(i), target); + } + + if (!unknown_fields().empty()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + unknown_fields(), target); + } + return target; +} + +int PointCloudXYZRGB::ByteSize() const { + int total_size = 0; + + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + // required .px.HeaderInfo header = 1; + if (has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + this->header()); + } + + } + // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2; + total_size += 1 * this->points_size(); + for (int i = 0; i < this->points_size(); i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + this->points(i)); + } + + if (!unknown_fields().empty()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + unknown_fields()); + } + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = total_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void PointCloudXYZRGB::MergeFrom(const ::google::protobuf::Message& from) { + GOOGLE_CHECK_NE(&from, this); + const PointCloudXYZRGB* source = + ::google::protobuf::internal::dynamic_cast_if_available( + &from); + if (source == NULL) { + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + MergeFrom(*source); + } +} + +void PointCloudXYZRGB::MergeFrom(const PointCloudXYZRGB& from) { + GOOGLE_CHECK_NE(&from, this); + points_.MergeFrom(from.points_); + if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (from.has_header()) { + mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); + } + } + mutable_unknown_fields()->MergeFrom(from.unknown_fields()); +} + +void PointCloudXYZRGB::CopyFrom(const ::google::protobuf::Message& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PointCloudXYZRGB::CopyFrom(const PointCloudXYZRGB& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PointCloudXYZRGB::IsInitialized() const { + if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false; + + if (has_header()) { + if (!this->header().IsInitialized()) return false; + } + for (int i = 0; i < points_size(); i++) { + if (!this->points(i).IsInitialized()) return false; + } + return true; +} + +void PointCloudXYZRGB::Swap(PointCloudXYZRGB* other) { + if (other != this) { + std::swap(header_, other->header_); + points_.Swap(&other->points_); + std::swap(_has_bits_[0], other->_has_bits_[0]); + _unknown_fields_.Swap(&other->_unknown_fields_); + std::swap(_cached_size_, other->_cached_size_); + } +} + +::google::protobuf::Metadata PointCloudXYZRGB::GetMetadata() const { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::Metadata metadata; + metadata.descriptor = PointCloudXYZRGB_descriptor_; + metadata.reflection = PointCloudXYZRGB_reflection_; + return metadata; +} + + +// =================================================================== + +#ifndef _MSC_VER +const int RGBDImage::kHeaderFieldNumber; +const int RGBDImage::kColsFieldNumber; +const int RGBDImage::kRowsFieldNumber; +const int RGBDImage::kStep1FieldNumber; +const int RGBDImage::kType1FieldNumber; +const int RGBDImage::kImageData1FieldNumber; +const int RGBDImage::kStep2FieldNumber; +const int RGBDImage::kType2FieldNumber; +const int RGBDImage::kImageData2FieldNumber; +const int RGBDImage::kCameraConfigFieldNumber; +const int RGBDImage::kCameraTypeFieldNumber; +const int RGBDImage::kRollFieldNumber; +const int RGBDImage::kPitchFieldNumber; +const int RGBDImage::kYawFieldNumber; +const int RGBDImage::kLonFieldNumber; +const int RGBDImage::kLatFieldNumber; +const int RGBDImage::kAltFieldNumber; +const int RGBDImage::kGroundXFieldNumber; +const int RGBDImage::kGroundYFieldNumber; +const int RGBDImage::kGroundZFieldNumber; +const int RGBDImage::kCameraMatrixFieldNumber; +#endif // !_MSC_VER + +RGBDImage::RGBDImage() + : ::google::protobuf::Message() { + SharedCtor(); +} + +void RGBDImage::InitAsDefaultInstance() { + header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); +} + +RGBDImage::RGBDImage(const RGBDImage& from) + : ::google::protobuf::Message() { + SharedCtor(); + MergeFrom(from); +} + +void RGBDImage::SharedCtor() { + _cached_size_ = 0; + header_ = NULL; + cols_ = 0u; + rows_ = 0u; + step1_ = 0u; + type1_ = 0u; + imagedata1_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); + step2_ = 0u; + type2_ = 0u; + imagedata2_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); + camera_config_ = 0u; + camera_type_ = 0u; + roll_ = 0; + pitch_ = 0; + yaw_ = 0; + lon_ = 0; + lat_ = 0; + alt_ = 0; + ground_x_ = 0; + ground_y_ = 0; + ground_z_ = 0; + ::memset(_has_bits_, 0, sizeof(_has_bits_)); +} + +RGBDImage::~RGBDImage() { + SharedDtor(); +} + +void RGBDImage::SharedDtor() { + if (imagedata1_ != &::google::protobuf::internal::kEmptyString) { + delete imagedata1_; + } + if (imagedata2_ != &::google::protobuf::internal::kEmptyString) { + delete imagedata2_; + } + if (this != default_instance_) { + delete header_; + } +} + +void RGBDImage::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* RGBDImage::descriptor() { + protobuf_AssignDescriptorsOnce(); + return RGBDImage_descriptor_; +} + +const RGBDImage& RGBDImage::default_instance() { + if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; +} + +RGBDImage* RGBDImage::default_instance_ = NULL; + +RGBDImage* RGBDImage::New() const { + return new RGBDImage; +} + +void RGBDImage::Clear() { + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (has_header()) { + if (header_ != NULL) header_->::px::HeaderInfo::Clear(); + } + cols_ = 0u; + rows_ = 0u; + step1_ = 0u; + type1_ = 0u; + if (has_imagedata1()) { + if (imagedata1_ != &::google::protobuf::internal::kEmptyString) { + imagedata1_->clear(); + } + } + step2_ = 0u; + type2_ = 0u; + } + if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) { + if (has_imagedata2()) { + if (imagedata2_ != &::google::protobuf::internal::kEmptyString) { + imagedata2_->clear(); + } + } + camera_config_ = 0u; + camera_type_ = 0u; + roll_ = 0; + pitch_ = 0; + yaw_ = 0; + lon_ = 0; + lat_ = 0; + } + if (_has_bits_[16 / 32] & (0xffu << (16 % 32))) { + alt_ = 0; + ground_x_ = 0; + ground_y_ = 0; + ground_z_ = 0; + } + camera_matrix_.Clear(); + ::memset(_has_bits_, 0, sizeof(_has_bits_)); + mutable_unknown_fields()->Clear(); +} + +bool RGBDImage::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!(EXPRESSION)) return false + ::google::protobuf::uint32 tag; + while ((tag = input->ReadTag()) != 0) { + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // required .px.HeaderInfo header = 1; + case 1: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_header())); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(16)) goto parse_cols; + break; + } + + // required uint32 cols = 2; + case 2: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { + parse_cols: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &cols_))); + set_has_cols(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(24)) goto parse_rows; + break; + } + + // required uint32 rows = 3; + case 3: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { + parse_rows: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &rows_))); + set_has_rows(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(32)) goto parse_step1; + break; + } + + // required uint32 step1 = 4; + case 4: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { + parse_step1: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &step1_))); + set_has_step1(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(40)) goto parse_type1; + break; + } + + // required uint32 type1 = 5; + case 5: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { + parse_type1: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &type1_))); + set_has_type1(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(50)) goto parse_imageData1; + break; + } + + // required bytes imageData1 = 6; + case 6: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { + parse_imageData1: + DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( + input, this->mutable_imagedata1())); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(56)) goto parse_step2; + break; + } + + // required uint32 step2 = 7; + case 7: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { + parse_step2: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &step2_))); + set_has_step2(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(64)) goto parse_type2; + break; + } + + // required uint32 type2 = 8; + case 8: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { + parse_type2: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &type2_))); + set_has_type2(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(74)) goto parse_imageData2; + break; + } + + // required bytes imageData2 = 9; + case 9: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { + parse_imageData2: + DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( + input, this->mutable_imagedata2())); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(80)) goto parse_camera_config; + break; + } + + // optional uint32 camera_config = 10; + case 10: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { + parse_camera_config: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &camera_config_))); + set_has_camera_config(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(88)) goto parse_camera_type; + break; + } + + // optional uint32 camera_type = 11; + case 11: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { + parse_camera_type: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &camera_type_))); + set_has_camera_type(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(101)) goto parse_roll; + break; + } + + // optional float roll = 12; + case 12: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_roll: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &roll_))); + set_has_roll(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(109)) goto parse_pitch; + break; + } + + // optional float pitch = 13; + case 13: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_pitch: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &pitch_))); + set_has_pitch(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(117)) goto parse_yaw; + break; + } + + // optional float yaw = 14; + case 14: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_yaw: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &yaw_))); + set_has_yaw(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(125)) goto parse_lon; + break; + } + + // optional float lon = 15; + case 15: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_lon: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &lon_))); + set_has_lon(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(133)) goto parse_lat; + break; + } + + // optional float lat = 16; + case 16: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_lat: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &lat_))); + set_has_lat(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(141)) goto parse_alt; + break; + } + + // optional float alt = 17; + case 17: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_alt: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &alt_))); + set_has_alt(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(149)) goto parse_ground_x; + break; + } + + // optional float ground_x = 18; + case 18: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_ground_x: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &ground_x_))); + set_has_ground_x(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(157)) goto parse_ground_y; + break; + } + + // optional float ground_y = 19; + case 19: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_ground_y: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &ground_y_))); + set_has_ground_y(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(165)) goto parse_ground_z; + break; + } + + // optional float ground_z = 20; + case 20: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_ground_z: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &ground_z_))); + set_has_ground_z(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(173)) goto parse_camera_matrix; + break; + } + + // repeated float camera_matrix = 21; + case 21: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { + parse_camera_matrix: + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + 2, 173, input, this->mutable_camera_matrix()))); + } else if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) + == ::google::protobuf::internal::WireFormatLite:: + WIRETYPE_LENGTH_DELIMITED) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitiveNoInline< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, this->mutable_camera_matrix()))); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(173)) goto parse_camera_matrix; + if (input->ExpectAtEnd()) return true; + break; + } + + default: { + handle_uninterpreted: + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + return true; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, mutable_unknown_fields())); + break; + } + } + } + return true; +#undef DO_ +} + +void RGBDImage::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // required .px.HeaderInfo header = 1; + if (has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->header(), output); + } + + // required uint32 cols = 2; + if (has_cols()) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(2, this->cols(), output); + } + + // required uint32 rows = 3; + if (has_rows()) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(3, this->rows(), output); + } + + // required uint32 step1 = 4; + if (has_step1()) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(4, this->step1(), output); + } + + // required uint32 type1 = 5; + if (has_type1()) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(5, this->type1(), output); + } + + // required bytes imageData1 = 6; + if (has_imagedata1()) { + ::google::protobuf::internal::WireFormatLite::WriteBytes( + 6, this->imagedata1(), output); + } + + // required uint32 step2 = 7; + if (has_step2()) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(7, this->step2(), output); + } + + // required uint32 type2 = 8; + if (has_type2()) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(8, this->type2(), output); + } + + // required bytes imageData2 = 9; + if (has_imagedata2()) { + ::google::protobuf::internal::WireFormatLite::WriteBytes( + 9, this->imagedata2(), output); + } + + // optional uint32 camera_config = 10; + if (has_camera_config()) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(10, this->camera_config(), output); + } + + // optional uint32 camera_type = 11; + if (has_camera_type()) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(11, this->camera_type(), output); + } + + // optional float roll = 12; + if (has_roll()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(12, this->roll(), output); + } + + // optional float pitch = 13; + if (has_pitch()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(13, this->pitch(), output); + } + + // optional float yaw = 14; + if (has_yaw()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(14, this->yaw(), output); + } + + // optional float lon = 15; + if (has_lon()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(15, this->lon(), output); + } + + // optional float lat = 16; + if (has_lat()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(16, this->lat(), output); + } + + // optional float alt = 17; + if (has_alt()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(17, this->alt(), output); + } + + // optional float ground_x = 18; + if (has_ground_x()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(18, this->ground_x(), output); + } + + // optional float ground_y = 19; + if (has_ground_y()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(19, this->ground_y(), output); + } + + // optional float ground_z = 20; + if (has_ground_z()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(20, this->ground_z(), output); + } + + // repeated float camera_matrix = 21; + for (int i = 0; i < this->camera_matrix_size(); i++) { + ::google::protobuf::internal::WireFormatLite::WriteFloat( + 21, this->camera_matrix(i), output); + } + + if (!unknown_fields().empty()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + unknown_fields(), output); + } +} + +::google::protobuf::uint8* RGBDImage::SerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // required .px.HeaderInfo header = 1; + if (has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteMessageNoVirtualToArray( + 1, this->header(), target); + } + + // required uint32 cols = 2; + if (has_cols()) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(2, this->cols(), target); + } + + // required uint32 rows = 3; + if (has_rows()) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(3, this->rows(), target); + } + + // required uint32 step1 = 4; + if (has_step1()) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(4, this->step1(), target); + } + + // required uint32 type1 = 5; + if (has_type1()) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(5, this->type1(), target); + } + + // required bytes imageData1 = 6; + if (has_imagedata1()) { + target = + ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( + 6, this->imagedata1(), target); + } + + // required uint32 step2 = 7; + if (has_step2()) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(7, this->step2(), target); + } + + // required uint32 type2 = 8; + if (has_type2()) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(8, this->type2(), target); + } + + // required bytes imageData2 = 9; + if (has_imagedata2()) { + target = + ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( + 9, this->imagedata2(), target); + } + + // optional uint32 camera_config = 10; + if (has_camera_config()) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(10, this->camera_config(), target); + } + + // optional uint32 camera_type = 11; + if (has_camera_type()) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(11, this->camera_type(), target); + } + + // optional float roll = 12; + if (has_roll()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(12, this->roll(), target); + } + + // optional float pitch = 13; + if (has_pitch()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(13, this->pitch(), target); + } + + // optional float yaw = 14; + if (has_yaw()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(14, this->yaw(), target); + } + + // optional float lon = 15; + if (has_lon()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(15, this->lon(), target); + } + + // optional float lat = 16; + if (has_lat()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(16, this->lat(), target); + } + + // optional float alt = 17; + if (has_alt()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(17, this->alt(), target); + } + + // optional float ground_x = 18; + if (has_ground_x()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(18, this->ground_x(), target); + } + + // optional float ground_y = 19; + if (has_ground_y()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(19, this->ground_y(), target); + } + + // optional float ground_z = 20; + if (has_ground_z()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(20, this->ground_z(), target); + } + + // repeated float camera_matrix = 21; + for (int i = 0; i < this->camera_matrix_size(); i++) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteFloatToArray(21, this->camera_matrix(i), target); + } + + if (!unknown_fields().empty()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + unknown_fields(), target); + } + return target; +} + +int RGBDImage::ByteSize() const { + int total_size = 0; + + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + // required .px.HeaderInfo header = 1; + if (has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + this->header()); + } + + // required uint32 cols = 2; + if (has_cols()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->cols()); + } + + // required uint32 rows = 3; + if (has_rows()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->rows()); + } + + // required uint32 step1 = 4; + if (has_step1()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->step1()); + } + + // required uint32 type1 = 5; + if (has_type1()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->type1()); + } + + // required bytes imageData1 = 6; + if (has_imagedata1()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::BytesSize( + this->imagedata1()); + } + + // required uint32 step2 = 7; + if (has_step2()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->step2()); + } + + // required uint32 type2 = 8; + if (has_type2()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->type2()); + } + + } + if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) { + // required bytes imageData2 = 9; + if (has_imagedata2()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::BytesSize( + this->imagedata2()); + } + + // optional uint32 camera_config = 10; + if (has_camera_config()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->camera_config()); + } + + // optional uint32 camera_type = 11; + if (has_camera_type()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->camera_type()); + } + + // optional float roll = 12; + if (has_roll()) { + total_size += 1 + 4; + } + + // optional float pitch = 13; + if (has_pitch()) { + total_size += 1 + 4; + } + + // optional float yaw = 14; + if (has_yaw()) { + total_size += 1 + 4; + } + + // optional float lon = 15; + if (has_lon()) { + total_size += 1 + 4; + } + + // optional float lat = 16; + if (has_lat()) { + total_size += 2 + 4; + } + + } + if (_has_bits_[16 / 32] & (0xffu << (16 % 32))) { + // optional float alt = 17; + if (has_alt()) { + total_size += 2 + 4; + } + + // optional float ground_x = 18; + if (has_ground_x()) { + total_size += 2 + 4; + } + + // optional float ground_y = 19; + if (has_ground_y()) { + total_size += 2 + 4; + } + + // optional float ground_z = 20; + if (has_ground_z()) { + total_size += 2 + 4; + } + + } + // repeated float camera_matrix = 21; + { + int data_size = 0; + data_size = 4 * this->camera_matrix_size(); + total_size += 2 * this->camera_matrix_size() + data_size; + } + + if (!unknown_fields().empty()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + unknown_fields()); + } + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = total_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void RGBDImage::MergeFrom(const ::google::protobuf::Message& from) { + GOOGLE_CHECK_NE(&from, this); + const RGBDImage* source = + ::google::protobuf::internal::dynamic_cast_if_available( + &from); + if (source == NULL) { + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + MergeFrom(*source); + } +} + +void RGBDImage::MergeFrom(const RGBDImage& from) { + GOOGLE_CHECK_NE(&from, this); + camera_matrix_.MergeFrom(from.camera_matrix_); + if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (from.has_header()) { + mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); + } + if (from.has_cols()) { + set_cols(from.cols()); + } + if (from.has_rows()) { + set_rows(from.rows()); + } + if (from.has_step1()) { + set_step1(from.step1()); + } + if (from.has_type1()) { + set_type1(from.type1()); + } + if (from.has_imagedata1()) { + set_imagedata1(from.imagedata1()); + } + if (from.has_step2()) { + set_step2(from.step2()); + } + if (from.has_type2()) { + set_type2(from.type2()); + } + } + if (from._has_bits_[8 / 32] & (0xffu << (8 % 32))) { + if (from.has_imagedata2()) { + set_imagedata2(from.imagedata2()); + } + if (from.has_camera_config()) { + set_camera_config(from.camera_config()); + } + if (from.has_camera_type()) { + set_camera_type(from.camera_type()); + } + if (from.has_roll()) { + set_roll(from.roll()); + } + if (from.has_pitch()) { + set_pitch(from.pitch()); + } + if (from.has_yaw()) { + set_yaw(from.yaw()); + } + if (from.has_lon()) { + set_lon(from.lon()); + } + if (from.has_lat()) { + set_lat(from.lat()); + } + } + if (from._has_bits_[16 / 32] & (0xffu << (16 % 32))) { + if (from.has_alt()) { + set_alt(from.alt()); + } + if (from.has_ground_x()) { + set_ground_x(from.ground_x()); + } + if (from.has_ground_y()) { + set_ground_y(from.ground_y()); + } + if (from.has_ground_z()) { + set_ground_z(from.ground_z()); + } + } + mutable_unknown_fields()->MergeFrom(from.unknown_fields()); +} + +void RGBDImage::CopyFrom(const ::google::protobuf::Message& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void RGBDImage::CopyFrom(const RGBDImage& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RGBDImage::IsInitialized() const { + if ((_has_bits_[0] & 0x000001ff) != 0x000001ff) return false; + + if (has_header()) { + if (!this->header().IsInitialized()) return false; + } + return true; +} + +void RGBDImage::Swap(RGBDImage* other) { + if (other != this) { + std::swap(header_, other->header_); + std::swap(cols_, other->cols_); + std::swap(rows_, other->rows_); + std::swap(step1_, other->step1_); + std::swap(type1_, other->type1_); + std::swap(imagedata1_, other->imagedata1_); + std::swap(step2_, other->step2_); + std::swap(type2_, other->type2_); + std::swap(imagedata2_, other->imagedata2_); + std::swap(camera_config_, other->camera_config_); + std::swap(camera_type_, other->camera_type_); + std::swap(roll_, other->roll_); + std::swap(pitch_, other->pitch_); + std::swap(yaw_, other->yaw_); + std::swap(lon_, other->lon_); + std::swap(lat_, other->lat_); + std::swap(alt_, other->alt_); + std::swap(ground_x_, other->ground_x_); + std::swap(ground_y_, other->ground_y_); + std::swap(ground_z_, other->ground_z_); + camera_matrix_.Swap(&other->camera_matrix_); + std::swap(_has_bits_[0], other->_has_bits_[0]); + _unknown_fields_.Swap(&other->_unknown_fields_); + std::swap(_cached_size_, other->_cached_size_); + } +} + +::google::protobuf::Metadata RGBDImage::GetMetadata() const { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::Metadata metadata; + metadata.descriptor = RGBDImage_descriptor_; + metadata.reflection = RGBDImage_reflection_; + return metadata; +} + + +// =================================================================== + +#ifndef _MSC_VER +const int Waypoint::kXFieldNumber; +const int Waypoint::kYFieldNumber; +const int Waypoint::kZFieldNumber; +const int Waypoint::kRollFieldNumber; +const int Waypoint::kPitchFieldNumber; +const int Waypoint::kYawFieldNumber; +#endif // !_MSC_VER + +Waypoint::Waypoint() + : ::google::protobuf::Message() { + SharedCtor(); +} + +void Waypoint::InitAsDefaultInstance() { +} + +Waypoint::Waypoint(const Waypoint& from) + : ::google::protobuf::Message() { + SharedCtor(); + MergeFrom(from); +} + +void Waypoint::SharedCtor() { + _cached_size_ = 0; + x_ = 0; + y_ = 0; + z_ = 0; + roll_ = 0; + pitch_ = 0; + yaw_ = 0; + ::memset(_has_bits_, 0, sizeof(_has_bits_)); +} + +Waypoint::~Waypoint() { + SharedDtor(); +} + +void Waypoint::SharedDtor() { + if (this != default_instance_) { + } +} + +void Waypoint::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* Waypoint::descriptor() { + protobuf_AssignDescriptorsOnce(); + return Waypoint_descriptor_; +} + +const Waypoint& Waypoint::default_instance() { + if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; +} + +Waypoint* Waypoint::default_instance_ = NULL; + +Waypoint* Waypoint::New() const { + return new Waypoint; +} + +void Waypoint::Clear() { + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + x_ = 0; + y_ = 0; + z_ = 0; + roll_ = 0; + pitch_ = 0; + yaw_ = 0; + } + ::memset(_has_bits_, 0, sizeof(_has_bits_)); + mutable_unknown_fields()->Clear(); +} + +bool Waypoint::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!(EXPRESSION)) return false + ::google::protobuf::uint32 tag; + while ((tag = input->ReadTag()) != 0) { + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // required double x = 1; + case 1: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &x_))); + set_has_x(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(17)) goto parse_y; + break; + } + + // required double y = 2; + case 2: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { + parse_y: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &y_))); + set_has_y(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(25)) goto parse_z; + break; + } + + // optional double z = 3; + case 3: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { + parse_z: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &z_))); + set_has_z(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(33)) goto parse_roll; + break; + } + + // optional double roll = 4; + case 4: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { + parse_roll: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &roll_))); + set_has_roll(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(41)) goto parse_pitch; + break; + } + + // optional double pitch = 5; + case 5: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { + parse_pitch: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &pitch_))); + set_has_pitch(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectTag(49)) goto parse_yaw; + break; + } + + // optional double yaw = 6; + case 6: { + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { + parse_yaw: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &yaw_))); + set_has_yaw(); + } else { + goto handle_uninterpreted; + } + if (input->ExpectAtEnd()) return true; + break; + } + + default: { + handle_uninterpreted: + if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + return true; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, mutable_unknown_fields())); + break; + } + } + } + return true; +#undef DO_ +} + +void Waypoint::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // required double x = 1; + if (has_x()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->x(), output); + } + + // required double y = 2; + if (has_y()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->y(), output); + } + + // optional double z = 3; + if (has_z()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->z(), output); + } + + // optional double roll = 4; + if (has_roll()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->roll(), output); + } + + // optional double pitch = 5; + if (has_pitch()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->pitch(), output); + } + + // optional double yaw = 6; + if (has_yaw()) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->yaw(), output); + } + + if (!unknown_fields().empty()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + unknown_fields(), output); + } +} + +::google::protobuf::uint8* Waypoint::SerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // required double x = 1; + if (has_x()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->x(), target); + } + + // required double y = 2; + if (has_y()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->y(), target); + } + + // optional double z = 3; + if (has_z()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->z(), target); + } + + // optional double roll = 4; + if (has_roll()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->roll(), target); + } + + // optional double pitch = 5; + if (has_pitch()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->pitch(), target); + } + + // optional double yaw = 6; + if (has_yaw()) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->yaw(), target); + } + + if (!unknown_fields().empty()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + unknown_fields(), target); + } + return target; +} + +int Waypoint::ByteSize() const { + int total_size = 0; + + if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { + // required double x = 1; + if (has_x()) { + total_size += 1 + 8; + } + + // required double y = 2; + if (has_y()) { + total_size += 1 + 8; + } + + // optional double z = 3; + if (has_z()) { + total_size += 1 + 8; + } + + // optional double roll = 4; + if (has_roll()) { + total_size += 1 + 8; + } + + // optional double pitch = 5; + if (has_pitch()) { + total_size += 1 + 8; + } + + // optional double yaw = 6; + if (has_yaw()) { + total_size += 1 + 8; + } + + } + if (!unknown_fields().empty()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + unknown_fields()); + } + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = total_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void Waypoint::MergeFrom(const ::google::protobuf::Message& from) { + GOOGLE_CHECK_NE(&from, this); + const Waypoint* source = + ::google::protobuf::internal::dynamic_cast_if_available( + &from); + if (source == NULL) { + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + MergeFrom(*source); + } +} + +void Waypoint::MergeFrom(const Waypoint& from) { + GOOGLE_CHECK_NE(&from, this); + if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (from.has_x()) { + set_x(from.x()); + } + if (from.has_y()) { + set_y(from.y()); + } + if (from.has_z()) { + set_z(from.z()); + } + if (from.has_roll()) { + set_roll(from.roll()); + } + if (from.has_pitch()) { + set_pitch(from.pitch()); + } + if (from.has_yaw()) { + set_yaw(from.yaw()); + } + } + mutable_unknown_fields()->MergeFrom(from.unknown_fields()); +} + +void Waypoint::CopyFrom(const ::google::protobuf::Message& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Waypoint::CopyFrom(const Waypoint& from) { + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Waypoint::IsInitialized() const { + if ((_has_bits_[0] & 0x00000003) != 0x00000003) return false; + + return true; +} + +void Waypoint::Swap(Waypoint* other) { + if (other != this) { + std::swap(x_, other->x_); + std::swap(y_, other->y_); + std::swap(z_, other->z_); + std::swap(roll_, other->roll_); + std::swap(pitch_, other->pitch_); + std::swap(yaw_, other->yaw_); + std::swap(_has_bits_[0], other->_has_bits_[0]); + _unknown_fields_.Swap(&other->_unknown_fields_); + std::swap(_cached_size_, other->_cached_size_); + } +} + +::google::protobuf::Metadata Waypoint::GetMetadata() const { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::Metadata metadata; + metadata.descriptor = Waypoint_descriptor_; + metadata.reflection = Waypoint_reflection_; + return metadata; +} + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace px + +// @@protoc_insertion_point(global_scope) diff --git a/qgcunittest.pro b/qgcunittest.pro index f8c231362ff08abf42be4ccac4dc393ce46efc17..5a648a4647bb4583a89f2dc6a24404b864b308d2 100644 --- a/qgcunittest.pro +++ b/qgcunittest.pro @@ -1,76 +1,153 @@ -#------------------------------------------------- -# -# Project created by QtCreator 2011-01-11T08:54:37 -# -#------------------------------------------------- +# ------------------------------------------------- +# QGroundControl - Micro Air Vehicle Groundstation +# Please see our website at +# Maintainer: +# Lorenz Meier +# (c) 2009-2011 QGroundControl Developers +# This file is part of the open groundstation project +# QGroundControl is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# QGroundControl is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# You should have received a copy of the GNU General Public License +# along with QGroundControl. If not, see . +# ------------------------------------------------- + +# Qt configuration +CONFIG += qt \ + thread \ + console QT += network \ + opengl \ + svg \ + xml \ phonon \ + webkit \ + sql \ testlib \ - svg TEMPLATE = app - TARGET = qgcunittest - -BASEDIR = $$IN_PWD +BASEDIR = $${IN_PWD} TESTDIR = $$BASEDIR/qgcunittest -TARGETDIR = $$OUT_PWD -BUILDDIR = $$TARGETDIR/build +linux-g++|linux-g++-64{ + debug { + TARGETDIR = $${OUT_PWD}/debug + BUILDDIR = $${OUT_PWD}/build-debug + } + release { + TARGETDIR = $${OUT_PWD}/release + BUILDDIR = $${OUT_PWD}/build-release + } +} else { + TARGETDIR = $${OUT_PWD} + BUILDDIR = $${OUT_PWD}/build +} LANGUAGE = C++ +OBJECTS_DIR = $${BUILDDIR}/obj +MOC_DIR = $${BUILDDIR}/moc +UI_DIR = $${BUILDDIR}/ui +RCC_DIR = $${BUILDDIR}/rcc +MAVLINK_CONF = "" +MAVLINKPATH = $$BASEDIR/mavlink/include/v1.0 +DEFINES += MAVLINK_NO_DATA -CONFIG += console -CONFIG -= app_bundle +win32 { + QMAKE_INCDIR_QT = $$(QTDIR)/include + QMAKE_LIBDIR_QT = $$(QTDIR)/lib + QMAKE_UIC = "$$(QTDIR)/bin/uic.exe" + QMAKE_MOC = "$$(QTDIR)/bin/moc.exe" + QMAKE_RCC = "$$(QTDIR)/bin/rcc.exe" + QMAKE_QMAKE = "$$(QTDIR)/bin/qmake.exe" +} + + + +################################################################# +# EXTERNAL LIBRARY CONFIGURATION + +# Include NMEA parsing library (currently unused) +include(src/libs/nmea/nmea.pri) -OBJECTS_DIR = $$BUILDDIR/obj -MOC_DIR = $$BUILDDIR/moc -UI_HEADERS_DIR = src/ui/generated -MAVLINK_CONF = "" + +# EIGEN matrix library (header-only) +INCLUDEPATH += src/libs/eigen + +# OPMapControl library (from OpenPilot) +include(src/libs/utils/utils_external.pri) +include(src/libs/opmapcontrol/opmapcontrol_external.pri) +DEPENDPATH += \ + src/libs/utils \ + src/libs/utils/src \ + src/libs/opmapcontrol \ + src/libs/opmapcontrol/src \ + src/libs/opmapcontrol/src/mapwidget + +INCLUDEPATH += \ + src/libs/utils \ + src/libs \ + src/libs/opmapcontrol # If the user config file exists, it will be included. # if the variable MAVLINK_CONF contains the name of an # additional project, QGroundControl includes the support # of custom MAVLink messages of this project -exists(user_config.pri) { +exists(user_config.pri) { include(user_config.pri) message("----- USING CUSTOM USER QGROUNDCONTROL CONFIG FROM user_config.pri -----") message("Adding support for additional MAVLink messages for: " $$MAVLINK_CONF) message("------------------------------------------------------------------------") } -INCLUDEPATH += $$BASEDIR/../mavlink/include/common -contains(MAVLINK_CONF, pixhawk) { +INCLUDEPATH += $$MAVLINKPATH/common +INCLUDEPATH += $$MAVLINKPATH +contains(MAVLINK_CONF, pixhawk) { # Remove the default set - it is included anyway - INCLUDEPATH -= $$BASEDIR/../mavlink/include/common + INCLUDEPATH -= $$MAVLINKPATH/common # PIXHAWK SPECIAL MESSAGES - INCLUDEPATH += $$BASEDIR/../mavlink/include/pixhawk + INCLUDEPATH += $$MAVLINKPATH/pixhawk DEFINES += QGC_USE_PIXHAWK_MESSAGES } -contains(MAVLINK_CONF, slugs) { +contains(MAVLINK_CONF, slugs) { # Remove the default set - it is included anyway - INCLUDEPATH -= $$BASEDIR/../mavlink/include/common + INCLUDEPATH -= $$MAVLINKPATH/common # SLUGS SPECIAL MESSAGES - INCLUDEPATH += $$BASEDIR/../mavlink/include/slugs + INCLUDEPATH += $$MAVLINKPATH/slugs DEFINES += QGC_USE_SLUGS_MESSAGES + SOURCES += $$TESTDIR/SlugsMavUnitTest.cc + HEADERS += $$TESTDIR/SlugsMavUnitTest.h } -contains(MAVLINK_CONF, ualberta) { +contains(MAVLINK_CONF, ualberta) { # Remove the default set - it is included anyway - INCLUDEPATH -= $$BASEDIR/../mavlink/include/common + INCLUDEPATH -= $$MAVLINKPATH/common # UALBERTA SPECIAL MESSAGES - INCLUDEPATH += $$BASEDIR/../mavlink/include/ualberta + INCLUDEPATH += $$MAVLINKPATH/ualberta DEFINES += QGC_USE_UALBERTA_MESSAGES } -contains(MAVLINK_CONF, ardupilotmega) { +contains(MAVLINK_CONF, ardupilotmega) { # Remove the default set - it is included anyway - INCLUDEPATH -= $$BASEDIR/../mavlink/include/common + INCLUDEPATH -= $$MAVLINKPATH/common # UALBERTA SPECIAL MESSAGES - INCLUDEPATH += $$BASEDIR/../mavlink/include/ardupilotmega + INCLUDEPATH += $$MAVLINKPATH/ardupilotmega DEFINES += QGC_USE_ARDUPILOTMEGA_MESSAGES } +contains(MAVLINK_CONF, senseSoar) { + # Remove the default set - it is included anyway + INCLUDEPATH -= $$MAVLINKPATH/common + + # SENSESOAR SPECIAL MESSAGES + INCLUDEPATH += $$MAVLINKPATH/SenseSoar + DEFINES += QGC_USE_SENSESOAR_MESSAGES +} # Include general settings for QGroundControl # necessary as last include to override any non-acceptable settings @@ -79,66 +156,463 @@ include(qgroundcontrol.pri) # Reset QMAKE_POST_LINK to prevent file copy operations QMAKE_POST_LINK = "" -# QWT plot and QExtSerial depend on paths set by qgroundcontrol.pri -# Include serial port library -include(src/lib/qextserialport/qextserialport.pri) +# Include MAVLink generator +# has been deprecated +DEPENDPATH += \ + src/apps/mavlinkgen + +INCLUDEPATH += \ + src/apps/mavlinkgen \ + src/apps/mavlinkgen/ui \ + src/apps/mavlinkgen/generator + +include(src/apps/mavlinkgen/mavlinkgen.pri) + + # Include QWT plotting library include(src/lib/qwt/qwt.pri) DEPENDPATH += . \ - lib/QMapControl \ - lib/QMapControl/src \ - plugins + plugins \ + thirdParty/qserialport/include \ + thirdParty/qserialport/include/QtSerialPort \ + thirdParty/qserialport \ + src/libs/qextserialport + INCLUDEPATH += . \ - lib/QMapControl \ - $$BASEDIR/../mavlink/include \ - $$BASEDIR/src/uas \ - $$BASEDIR/src/comm \ - $$BASEDIR/src/ \ - $$BASEDIR/src/ui/RadioCalibration \ - $$BASEDIR/src/ui/ \ + thirdParty/qserialport/include \ + thirdParty/qserialport/include/QtSerialPort \ + thirdParty/qserialport/src \ + src/libs/qextserialport +# Include serial port library (QSerial) +include(qserialport.pri) -SOURCES += src/uas/UAS.cc \ - src/comm/MAVLinkProtocol.cc \ - src/uas/UASWaypointManager.cc \ - src/Waypoint.cc \ - src/ui/RadioCalibration/RadioCalibrationData.cc \ - src/uas/SlugsMAV.cc \ - src/uas/PxQuadMAV.cc \ - src/uas/ArduPilotMegaMAV.cc \ - src/GAudioOutput.cc \ - src/uas/UASManager.cc \ - src/comm/LinkManager.cc \ - src/QGC.cc \ - src/comm/SerialLink.cc \ - $$TESTDIR/SlugsMavUnitTest.cc \ - $$TESTDIR/testSuite.cc \ - $$TESTDIR/UASUnitTest.cc \ - src/uas/QGCMAVLinkUASFactory.cc +# Serial port detection (ripped-off from qextserialport library) +macx|macx-g++|macx-g++42::SOURCES += src/libs/qextserialport/qextserialenumerator_osx.cpp +linux-g++::SOURCES += src/libs/qextserialport/qextserialenumerator_unix.cpp +linux-g++-64::SOURCES += src/libs/qextserialport/qextserialenumerator_unix.cpp +win32::SOURCES += src/libs/qextserialport/qextserialenumerator_win.cpp +win32-msvc2008|win32-msvc2010::SOURCES += src/libs/qextserialport/qextserialenumerator_win.cpp + +# Input +FORMS += src/ui/MainWindow.ui \ + src/ui/CommSettings.ui \ + src/ui/SerialSettings.ui \ + src/ui/UASControl.ui \ + src/ui/UASList.ui \ + src/ui/UASInfo.ui \ + src/ui/Linechart.ui \ + src/ui/UASView.ui \ + src/ui/ParameterInterface.ui \ + src/ui/WaypointList.ui \ + src/ui/ObjectDetectionView.ui \ + src/ui/JoystickWidget.ui \ + src/ui/DebugConsole.ui \ + src/ui/HDDisplay.ui \ + src/ui/MAVLinkSettingsWidget.ui \ + src/ui/AudioOutputWidget.ui \ + src/ui/QGCSensorSettingsWidget.ui \ + src/ui/watchdog/WatchdogControl.ui \ + src/ui/watchdog/WatchdogProcessView.ui \ + src/ui/watchdog/WatchdogView.ui \ + src/ui/QGCFirmwareUpdate.ui \ + src/ui/QGCPxImuFirmwareUpdate.ui \ + src/ui/QGCDataPlot2D.ui \ + src/ui/QGCRemoteControlView.ui \ + src/ui/QMap3D.ui \ + src/ui/QGCWebView.ui \ + src/ui/map3D/QGCGoogleEarthView.ui \ + src/ui/SlugsDataSensorView.ui \ + src/ui/SlugsHilSim.ui \ + src/ui/SlugsPadCameraControl.ui \ + src/ui/uas/QGCUnconnectedInfoWidget.ui \ + src/ui/designer/QGCToolWidget.ui \ + src/ui/designer/QGCParamSlider.ui \ + src/ui/designer/QGCActionButton.ui \ + src/ui/designer/QGCCommandButton.ui \ + src/ui/QGCMAVLinkLogPlayer.ui \ + src/ui/QGCWaypointListMulti.ui \ + src/ui/mission/QGCCustomWaypointAction.ui \ + src/ui/QGCUDPLinkConfiguration.ui \ + src/ui/QGCSettingsWidget.ui \ + src/ui/UASControlParameters.ui \ + src/ui/mission/QGCMissionDoWidget.ui \ + src/ui/mission/QGCMissionConditionWidget.ui \ + src/ui/map/QGCMapTool.ui \ + src/ui/map/QGCMapToolBar.ui \ + src/ui/QGCMAVLinkInspector.ui \ + src/ui/WaypointViewOnlyView.ui \ + src/ui/WaypointEditableView.ui \ + src/ui/UnconnectedUASInfoWidget.ui \ + src/ui/mavlink/QGCMAVLinkMessageSender.ui \ + src/ui/firmwareupdate/QGCFirmwareUpdateWidget.ui \ + src/ui/QGCPluginHost.ui \ + src/ui/firmwareupdate/QGCPX4FirmwareUpdate.ui +INCLUDEPATH += src \ + src/ui \ + src/ui/linechart \ + src/ui/uas \ + src/ui/map \ + src/uas \ + src/comm \ + src/input \ + src/ui/mavlink \ + src/ui/watchdog \ + src/ui/map3D \ + src/ui/designer -HEADERS += src/uas/UASInterface.h \ +HEADERS += src/MG.h \ + src/QGCCore.h \ + src/uas/UASInterface.h \ src/uas/UAS.h \ - src/comm/MAVLinkProtocol.h \ - src/comm/ProtocolInterface.h \ - src/uas/UASWaypointManager.h \ - src/Waypoint.h \ - src/ui/RadioCalibration/RadioCalibrationData.h \ - src/uas/SlugsMAV.h \ - src/uas/PxQuadMAV.h \ - src/uas/ArduPilotMegaMAV.h \ - src/GAudioOutput.h \ src/uas/UASManager.h \ src/comm/LinkManager.h \ src/comm/LinkInterface.h \ - src/QGC.h \ src/comm/SerialLinkInterface.h \ src/comm/SerialLink.h \ - $$TESTDIR//SlugsMavUnitTest.h \ + src/comm/ProtocolInterface.h \ + src/comm/MAVLinkProtocol.h \ + src/comm/QGCFlightGearLink.h \ + src/ui/CommConfigurationWindow.h \ + src/ui/SerialConfigurationWindow.h \ + src/ui/MainWindow.h \ + src/ui/uas/UASControlWidget.h \ + src/ui/uas/UASListWidget.h \ + src/ui/uas/UASInfoWidget.h \ + src/ui/HUD.h \ + src/ui/linechart/LinechartWidget.h \ + src/ui/linechart/LinechartPlot.h \ + src/ui/linechart/Scrollbar.h \ + src/ui/linechart/ScrollZoomer.h \ + src/configuration.h \ + src/ui/uas/UASView.h \ + src/ui/CameraView.h \ + src/comm/MAVLinkSimulationLink.h \ + src/comm/UDPLink.h \ + src/ui/ParameterInterface.h \ + src/ui/WaypointList.h \ + src/Waypoint.h \ + src/ui/ObjectDetectionView.h \ + src/input/JoystickInput.h \ + src/ui/JoystickWidget.h \ + src/ui/DebugConsole.h \ + src/ui/HDDisplay.h \ + src/ui/MAVLinkSettingsWidget.h \ + src/ui/AudioOutputWidget.h \ + src/GAudioOutput.h \ + src/LogCompressor.h \ + src/ui/QGCParamWidget.h \ + src/ui/QGCSensorSettingsWidget.h \ + src/ui/linechart/Linecharts.h \ + src/uas/SlugsMAV.h \ + src/uas/PxQuadMAV.h \ + src/uas/ArduPilotMegaMAV.h \ + src/uas/senseSoarMAV.h \ + src/ui/watchdog/WatchdogControl.h \ + src/ui/watchdog/WatchdogProcessView.h \ + src/ui/watchdog/WatchdogView.h \ + src/uas/UASWaypointManager.h \ + src/ui/HSIDisplay.h \ + src/QGC.h \ + src/ui/QGCFirmwareUpdate.h \ + src/ui/QGCPxImuFirmwareUpdate.h \ + src/ui/QGCDataPlot2D.h \ + src/ui/linechart/IncrementalPlot.h \ + src/ui/QGCRemoteControlView.h \ + src/ui/RadioCalibration/RadioCalibrationData.h \ + src/ui/RadioCalibration/RadioCalibrationWindow.h \ + src/ui/RadioCalibration/AirfoilServoCalibrator.h \ + src/ui/RadioCalibration/SwitchCalibrator.h \ + src/ui/RadioCalibration/CurveCalibrator.h \ + src/ui/RadioCalibration/AbstractCalibrator.h \ + src/comm/QGCMAVLink.h \ + src/ui/QGCWebView.h \ + src/ui/map3D/QGCWebPage.h \ + src/ui/SlugsDataSensorView.h \ + src/ui/SlugsHilSim.h \ + src/ui/SlugsPadCameraControl.h \ + src/ui/QGCMainWindowAPConfigurator.h \ + src/comm/MAVLinkSwarmSimulationLink.h \ + src/ui/uas/QGCUnconnectedInfoWidget.h \ + src/ui/designer/QGCToolWidget.h \ + src/ui/designer/QGCParamSlider.h \ + src/ui/designer/QGCCommandButton.h \ + src/ui/designer/QGCToolWidgetItem.h \ + src/ui/QGCMAVLinkLogPlayer.h \ + src/comm/MAVLinkSimulationWaypointPlanner.h \ + src/comm/MAVLinkSimulationMAV.h \ + src/uas/QGCMAVLinkUASFactory.h \ + src/ui/QGCWaypointListMulti.h \ + src/ui/QGCUDPLinkConfiguration.h \ + src/ui/QGCSettingsWidget.h \ + src/ui/uas/UASControlParameters.h \ + src/ui/mission/QGCMissionDoWidget.h \ + src/ui/mission/QGCMissionConditionWidget.h \ + src/uas/QGCUASParamManager.h \ + src/ui/map/QGCMapWidget.h \ + src/ui/map/MAV2DIcon.h \ + src/ui/map/Waypoint2DIcon.h \ + src/ui/map/QGCMapTool.h \ + src/ui/map/QGCMapToolBar.h \ + src/libs/qextserialport/qextserialenumerator.h \ + src/QGCGeo.h \ + src/ui/QGCToolBar.h \ + src/ui/QGCMAVLinkInspector.h \ + src/ui/MAVLinkDecoder.h \ + src/ui/WaypointViewOnlyView.h \ + src/ui/WaypointViewOnlyView.h \ + src/ui/WaypointEditableView.h \ + src/ui/UnconnectedUASInfoWidget.h \ + src/ui/QGCRGBDView.h \ + src/ui/mavlink/QGCMAVLinkMessageSender.h \ + src/ui/firmwareupdate/QGCFirmwareUpdateWidget.h \ + src/ui/QGCPluginHost.h \ + src/ui/firmwareupdate/QGCPX4FirmwareUpdate.h \ $$TESTDIR/AutoTest.h \ $$TESTDIR/UASUnitTest.h \ - src/uas/QGCMAVLinkUASFactory.h +# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler +macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::HEADERS += src/ui/map3D/QGCGoogleEarthView.h -DEFINES += SRCDIR=\\\"$$PWD/\\\" +contains(DEPENDENCIES_PRESENT, osg) { + message("Including headers for OpenSceneGraph") + + # Enable only if OpenSceneGraph is available + HEADERS += src/ui/map3D/gpl.h \ + src/ui/map3D/CameraParams.h \ + src/ui/map3D/ViewParamWidget.h \ + src/ui/map3D/SystemContainer.h \ + src/ui/map3D/SystemViewParams.h \ + src/ui/map3D/GlobalViewParams.h \ + src/ui/map3D/SystemGroupNode.h \ + src/ui/map3D/Q3DWidget.h \ + src/ui/map3D/GCManipulator.h \ + src/ui/map3D/ImageWindowGeode.h \ + src/ui/map3D/PixhawkCheetahGeode.h \ + src/ui/map3D/Pixhawk3DWidget.h \ + src/ui/map3D/Q3DWidgetFactory.h \ + src/ui/map3D/WebImageCache.h \ + src/ui/map3D/WebImage.h \ + src/ui/map3D/TextureCache.h \ + src/ui/map3D/Texture.h \ + src/ui/map3D/Imagery.h \ + src/ui/map3D/HUDScaleGeode.h \ + src/ui/map3D/WaypointGroupNode.h \ + src/ui/map3D/TerrainParamDialog.h \ + src/ui/map3D/ImageryParamDialog.h +} +contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) { + message("Including headers for Protocol Buffers") + + # Enable only if protobuf is available + HEADERS += mavlink/include/v1.0/pixhawk/pixhawk.pb.h \ + src/ui/map3D/ObstacleGroupNode.h \ + src/ui/map3D/GLOverlayGeode.h +} +contains(DEPENDENCIES_PRESENT, libfreenect) { + message("Including headers for libfreenect") + + # Enable only if libfreenect is available + HEADERS += src/input/Freenect.h +} + +SOURCES += src/QGCCore.cc \ + src/uas/UASManager.cc \ + src/uas/UAS.cc \ + src/comm/LinkManager.cc \ + src/comm/LinkInterface.cpp \ + src/comm/SerialLink.cc \ + src/comm/MAVLinkProtocol.cc \ + src/comm/QGCFlightGearLink.cc \ + src/ui/CommConfigurationWindow.cc \ + src/ui/SerialConfigurationWindow.cc \ + src/ui/MainWindow.cc \ + src/ui/uas/UASControlWidget.cc \ + src/ui/uas/UASListWidget.cc \ + src/ui/uas/UASInfoWidget.cc \ + src/ui/HUD.cc \ + src/ui/linechart/LinechartWidget.cc \ + src/ui/linechart/LinechartPlot.cc \ + src/ui/linechart/Scrollbar.cc \ + src/ui/linechart/ScrollZoomer.cc \ + src/ui/uas/UASView.cc \ + src/ui/CameraView.cc \ + src/comm/MAVLinkSimulationLink.cc \ + src/comm/UDPLink.cc \ + src/ui/ParameterInterface.cc \ + src/ui/WaypointList.cc \ + src/Waypoint.cc \ + src/ui/ObjectDetectionView.cc \ + src/input/JoystickInput.cc \ + src/ui/JoystickWidget.cc \ + src/ui/DebugConsole.cc \ + src/ui/HDDisplay.cc \ + src/ui/MAVLinkSettingsWidget.cc \ + src/ui/AudioOutputWidget.cc \ + src/GAudioOutput.cc \ + src/LogCompressor.cc \ + src/ui/QGCParamWidget.cc \ + src/ui/QGCSensorSettingsWidget.cc \ + src/ui/linechart/Linecharts.cc \ + src/uas/SlugsMAV.cc \ + src/uas/PxQuadMAV.cc \ + src/uas/ArduPilotMegaMAV.cc \ + src/uas/senseSoarMAV.cpp \ + src/ui/watchdog/WatchdogControl.cc \ + src/ui/watchdog/WatchdogProcessView.cc \ + src/ui/watchdog/WatchdogView.cc \ + src/uas/UASWaypointManager.cc \ + src/ui/HSIDisplay.cc \ + src/QGC.cc \ + src/ui/QGCFirmwareUpdate.cc \ + src/ui/QGCPxImuFirmwareUpdate.cc \ + src/ui/QGCDataPlot2D.cc \ + src/ui/linechart/IncrementalPlot.cc \ + src/ui/QGCRemoteControlView.cc \ + src/ui/RadioCalibration/RadioCalibrationWindow.cc \ + src/ui/RadioCalibration/AirfoilServoCalibrator.cc \ + src/ui/RadioCalibration/SwitchCalibrator.cc \ + src/ui/RadioCalibration/CurveCalibrator.cc \ + src/ui/RadioCalibration/AbstractCalibrator.cc \ + src/ui/RadioCalibration/RadioCalibrationData.cc \ + src/ui/QGCWebView.cc \ + src/ui/map3D/QGCWebPage.cc \ + src/ui/SlugsDataSensorView.cc \ + src/ui/SlugsHilSim.cc \ + src/ui/SlugsPadCameraControl.cpp \ + src/ui/QGCMainWindowAPConfigurator.cc \ + src/comm/MAVLinkSwarmSimulationLink.cc \ + src/ui/uas/QGCUnconnectedInfoWidget.cc \ + src/ui/designer/QGCToolWidget.cc \ + src/ui/designer/QGCParamSlider.cc \ + src/ui/designer/QGCCommandButton.cc \ + src/ui/designer/QGCToolWidgetItem.cc \ + src/ui/QGCMAVLinkLogPlayer.cc \ + src/comm/MAVLinkSimulationWaypointPlanner.cc \ + src/comm/MAVLinkSimulationMAV.cc \ + src/uas/QGCMAVLinkUASFactory.cc \ + src/ui/QGCWaypointListMulti.cc \ + src/ui/QGCUDPLinkConfiguration.cc \ + src/ui/QGCSettingsWidget.cc \ + src/ui/uas/UASControlParameters.cpp \ + src/ui/mission/QGCMissionDoWidget.cc \ + src/ui/mission/QGCMissionConditionWidget.cc \ + src/uas/QGCUASParamManager.cc \ + src/ui/map/QGCMapWidget.cc \ + src/ui/map/MAV2DIcon.cc \ + src/ui/map/Waypoint2DIcon.cc \ + src/ui/map/QGCMapTool.cc \ + src/ui/map/QGCMapToolBar.cc \ + src/ui/QGCToolBar.cc \ + src/ui/QGCMAVLinkInspector.cc \ + src/ui/MAVLinkDecoder.cc \ + src/ui/WaypointViewOnlyView.cc \ + src/ui/WaypointEditableView.cc \ + src/ui/UnconnectedUASInfoWidget.cc \ + src/ui/QGCRGBDView.cc \ + src/ui/mavlink/QGCMAVLinkMessageSender.cc \ + src/ui/firmwareupdate/QGCFirmwareUpdateWidget.cc \ + src/ui/QGCPluginHost.cc \ + src/ui/firmwareupdate/QGCPX4FirmwareUpdate.cc \ + $$TESTDIR/testSuite.cc \ + $$TESTDIR/UASUnitTest.cc + +# Enable Google Earth only on Mac OS and Windows with Visual Studio compiler +macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc + +# Enable OSG only if it has been found +contains(DEPENDENCIES_PRESENT, osg) { + message("Including sources for OpenSceneGraph") + + # Enable only if OpenSceneGraph is available + SOURCES += src/ui/map3D/gpl.cc \ + src/ui/map3D/CameraParams.cc \ + src/ui/map3D/ViewParamWidget.cc \ + src/ui/map3D/SystemContainer.cc \ + src/ui/map3D/SystemViewParams.cc \ + src/ui/map3D/GlobalViewParams.cc \ + src/ui/map3D/SystemGroupNode.cc \ + src/ui/map3D/Q3DWidget.cc \ + src/ui/map3D/ImageWindowGeode.cc \ + src/ui/map3D/GCManipulator.cc \ + src/ui/map3D/PixhawkCheetahGeode.cc \ + src/ui/map3D/Pixhawk3DWidget.cc \ + src/ui/map3D/Q3DWidgetFactory.cc \ + src/ui/map3D/WebImageCache.cc \ + src/ui/map3D/WebImage.cc \ + src/ui/map3D/TextureCache.cc \ + src/ui/map3D/Texture.cc \ + src/ui/map3D/Imagery.cc \ + src/ui/map3D/HUDScaleGeode.cc \ + src/ui/map3D/WaypointGroupNode.cc \ + src/ui/map3D/TerrainParamDialog.cc \ + src/ui/map3D/ImageryParamDialog.cc + + contains(DEPENDENCIES_PRESENT, osgearth) { + message("Including sources for osgEarth") + + # Enable only if OpenSceneGraph is available + SOURCES += src/ui/map3D/QMap3D.cc + } +} +contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) { + message("Including sources for Protocol Buffers") + + # Enable only if protobuf is available + SOURCES += mavlink/src/v1.0/pixhawk/pixhawk.pb.cc \ + src/ui/map3D/ObstacleGroupNode.cc \ + src/ui/map3D/GLOverlayGeode.cc +} +contains(DEPENDENCIES_PRESENT, libfreenect) { + message("Including sources for libfreenect") + + # Enable only if libfreenect is available + SOURCES += src/input/Freenect.cc +} + +# Add icons and other resources +RESOURCES += qgroundcontrol.qrc + +# Include RT-LAB Library +win32:exists(src/lib/opalrt/OpalApi.h):exists(C:/OPAL-RT/RT-LAB7.2.4/Common/bin) { + message("Building support for Opal-RT") + LIBS += -LC:/OPAL-RT/RT-LAB7.2.4/Common/bin \ + -lOpalApi + INCLUDEPATH += src/lib/opalrt + HEADERS += src/comm/OpalRT.h \ + src/comm/OpalLink.h \ + src/comm/Parameter.h \ + src/comm/QGCParamID.h \ + src/comm/ParameterList.h \ + src/ui/OpalLinkConfigurationWindow.h + SOURCES += src/comm/OpalRT.cc \ + src/comm/OpalLink.cc \ + src/comm/Parameter.cc \ + src/comm/QGCParamID.cc \ + src/comm/ParameterList.cc \ + src/ui/OpalLinkConfigurationWindow.cc + FORMS += src/ui/OpalLinkSettings.ui + DEFINES += OPAL_RT +} +TRANSLATIONS += es-MX.ts \ + en-US.ts + +# xbee support +# libxbee only supported by linux and windows systems +win32-msvc2008|win32-msvc2010|linux { + HEADERS += src/comm/XbeeLinkInterface.h \ + src/comm/XbeeLink.h \ + src/comm/HexSpinBox.h \ + src/ui/XbeeConfigurationWindow.h \ + src/comm/CallConv.h + SOURCES += src/comm/XbeeLink.cpp \ + src/comm/HexSpinBox.cpp \ + src/ui/XbeeConfigurationWindow.cpp + DEFINES += XBEELINK + INCLUDEPATH += thirdParty/libxbee +# TO DO: build library when it does not exist already + LIBS += -LthirdParty/libxbee/lib \ + -llibxbee +} diff --git a/qgcunittest/SlugsMavUnitTest.cc b/qgcunittest/SlugsMavUnitTest.cc deleted file mode 100644 index 349903e074bd2647bd20bfa071b6d53ede50c3b6..0000000000000000000000000000000000000000 --- a/qgcunittest/SlugsMavUnitTest.cc +++ /dev/null @@ -1,34 +0,0 @@ -#include "SlugsMavUnitTest.h" - -SlugsMavUnitTest::SlugsMavUnitTest() -{ -} - -void SlugsMavUnitTest::initTestCase() -{ - mav = new MAVLinkProtocol(); - slugsMav = new SlugsMAV(mav, UASID); -} - -void SlugsMavUnitTest::cleanupTestCase() -{ - delete slugsMav; - delete mav; -} - -void SlugsMavUnitTest::first_test() -{ - QCOMPARE(1,1); -} - -void SlugsMavUnitTest::getPwmCommands_test() -{ - mavlink_pwm_commands_t* k = slugsMav->getPwmCommands(); - k->aux1=80; - - mavlink_pwm_commands_t* k2 = slugsMav->getPwmCommands(); - k2->aux1=81; - - QCOMPARE(k->aux1, k2->aux1); -} - diff --git a/qgcunittest/SlugsMavUnitTest.h b/qgcunittest/SlugsMavUnitTest.h deleted file mode 100644 index 51fb52959b64a36afbca8608e3a1f5e6464cb792..0000000000000000000000000000000000000000 --- a/qgcunittest/SlugsMavUnitTest.h +++ /dev/null @@ -1,35 +0,0 @@ -#ifndef SLUGSMAVUNITTEST_H -#define SLUGSMAVUNITTEST_H - -#include -#include -#include - -#include "UAS.h" -#include "MAVLinkProtocol.h" -#include "UASInterface.h" -#include "AutoTest.h" -#include "SlugsMAV.h" - -class SlugsMavUnitTest : public QObject -{ - Q_OBJECT -public: -#define UASID 5 - MAVLinkProtocol* mav; - SlugsMAV* slugsMav; - SlugsMavUnitTest(); -signals: - -private slots: - void initTestCase(); - void cleanupTestCase(); - void first_test(); - - void getPwmCommands_test(); - -}; - -DECLARE_TEST(SlugsMavUnitTest) - -#endif // SLUGSMAVUNITTEST_H diff --git a/qgcunittest/UASUnitTest.cc b/qgcunittest/UASUnitTest.cc index 5711347b065242a6c5337ae878304ef945a2353d..2fef763db399019c514b65c8e691f7f7bf98faac 100644 --- a/qgcunittest/UASUnitTest.cc +++ b/qgcunittest/UASUnitTest.cc @@ -6,9 +6,8 @@ UASUnitTest::UASUnitTest() void UASUnitTest::initTestCase() { - mav= new MAVLinkProtocol(); - link = new SerialLink(); - uas=new UAS(mav,UASID); + mav = new MAVLinkProtocol(); + uas = new UAS(mav,UASID); } void UASUnitTest::cleanupTestCase() @@ -27,7 +26,7 @@ void UASUnitTest::getUASID_test() // Test that the chosen ID was assigned at construction QCOMPARE(uas->getUASID(), UASID); - // Make sure that no other ID was sert + // Make sure that no other ID was set QEXPECT_FAIL("", "When you set an ID it does not use the default ID of 0", Continue); QCOMPARE(uas->getUASID(), 0); @@ -177,27 +176,27 @@ void UASUnitTest::getAirframe_test() void UASUnitTest::getWaypointList_test() { - QVector kk = uas->getWaypointManager()->getWaypointList(); + QVector kk = uas->getWaypointManager()->getWaypointEditableList(); QCOMPARE(kk.count(), 0); - Waypoint* wp = new Waypoint(0,0,0,0,0,false, false, 0,0, MAV_FRAME_GLOBAL, MAV_ACTION_NAVIGATE); - uas->getWaypointManager()->addWaypoint(wp, true); + Waypoint* wp = new Waypoint(0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,false, false, MAV_FRAME_GLOBAL, MAV_CMD_MISSION_START, "blah"); + uas->getWaypointManager()->addWaypointEditable(wp, true); - kk = uas->getWaypointManager()->getWaypointList(); + kk = uas->getWaypointManager()->getWaypointEditableList(); QCOMPARE(kk.count(), 1); wp = new Waypoint(); - uas->getWaypointManager()->addWaypoint(wp, false); + uas->getWaypointManager()->addWaypointEditable(wp, false); - kk = uas->getWaypointManager()->getWaypointList(); + kk = uas->getWaypointManager()->getWaypointEditableList(); QCOMPARE(kk.count(), 2); uas->getWaypointManager()->removeWaypoint(1); - kk = uas->getWaypointManager()->getWaypointList(); + kk = uas->getWaypointManager()->getWaypointEditableList(); QCOMPARE(kk.count(), 1); uas->getWaypointManager()->removeWaypoint(0); - kk = uas->getWaypointManager()->getWaypointList(); + kk = uas->getWaypointManager()->getWaypointEditableList(); QCOMPARE(kk.count(), 0); qDebug()<<"disconnect SIGNAL waypointListChanged"; @@ -205,17 +204,17 @@ void UASUnitTest::getWaypointList_test() void UASUnitTest::getWaypoint_test() { - Waypoint* wp = new Waypoint(0,5.6,0,0,0,false, false, 0,0, MAV_FRAME_GLOBAL, MAV_ACTION_NAVIGATE); + Waypoint* wp = new Waypoint(0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,false, false, MAV_FRAME_GLOBAL, MAV_CMD_MISSION_START, "blah"); - uas->getWaypointManager()->addWaypoint(wp, true); + uas->getWaypointManager()->addWaypointEditable(wp, true); - QVector wpList = uas->getWaypointManager()->getWaypointList(); + QVector wpList = uas->getWaypointManager()->getWaypointEditableList(); QCOMPARE(wpList.count(), 1); QCOMPARE(static_cast(0), static_cast(wpList.at(0))->getId()); wp = new Waypoint(0, 5.6, 2, 3); - uas->getWaypointManager()->addWaypoint(wp, true); + uas->getWaypointManager()->addWaypointEditable(wp, true); Waypoint* wp2 = static_cast(wpList.at(0)); QCOMPARE(wp->getX(), wp2->getX()); @@ -226,9 +225,9 @@ void UASUnitTest::getWaypoint_test() void UASUnitTest::signalWayPoint_test() { QSignalSpy spy(uas->getWaypointManager(), SIGNAL(waypointListChanged())); - - Waypoint* wp = new Waypoint(0,5.6,0,0,0,false, false, 0,0, MAV_FRAME_GLOBAL, MAV_ACTION_NAVIGATE); - uas->getWaypointManager()->addWaypoint(wp, true); + + Waypoint* wp = new Waypoint(0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,false, false, MAV_FRAME_GLOBAL, MAV_CMD_MISSION_START, "blah"); + uas->getWaypointManager()->addWaypointEditable(wp, true); QCOMPARE(spy.count(), 1); // 1 listChanged for add wayPoint uas->getWaypointManager()->removeWaypoint(0); @@ -245,11 +244,11 @@ void UASUnitTest::signalWayPoint_test() QSignalSpy spy2(uas->getWaypointManager(), SIGNAL(waypointListChanged())); QCOMPARE(spy2.count(), 0); - uas->getWaypointManager()->addWaypoint(wp, true); + uas->getWaypointManager()->addWaypointEditable(wp, true); QCOMPARE(spy2.count(), 1); uas->getWaypointManager()->clearWaypointList(); - QVector wpList = uas->getWaypointManager()->getWaypointList(); + QVector wpList = uas->getWaypointManager()->getWaypointEditableList(); QCOMPARE(wpList.count(), 1); } diff --git a/qgcunittest/UASUnitTest.h b/qgcunittest/UASUnitTest.h index 4fcb10a935be5fed6371f0d8e0173356c828f7c7..5ff6667419819fb6080fcd8ae155c6c75ef89d37 100644 --- a/qgcunittest/UASUnitTest.h +++ b/qgcunittest/UASUnitTest.h @@ -25,8 +25,6 @@ public: UAS* uas; UASUnitTest(); -signals: - private slots: void initTestCase(); void cleanupTestCase(); @@ -61,10 +59,6 @@ private slots: void signalWayPoint_test(); void signalUASLink_test(); void signalIdUASLink_test(); - -protected: - UAS *prueba; - }; DECLARE_TEST(UASUnitTest) diff --git a/qgcunittest/tst_uasunittest.cc b/qgcunittest/tst_uasunittest.cc deleted file mode 100644 index 83c901ab9a496aac2d854f87e3daa22b5493cd77..0000000000000000000000000000000000000000 --- a/qgcunittest/tst_uasunittest.cc +++ /dev/null @@ -1,201 +0,0 @@ -#include -#include -#include "UAS.h" -#include "MAVLinkProtocol.h" -#include "UASInterface.h" - -class UASUnitTest : public QObject -{ - Q_OBJECT - -public: - #define UASID 50 - MAVLinkProtocol* mav; - UAS* uas; - UASUnitTest(); - -private Q_SLOTS: - void initTestCase(); - void cleanupTestCase(); - void getUASID_test(); - void getUASName_test(); - void getUpTime_test(); - void getCommunicationStatus_test(); - void filterVoltage_test(); - void getAutopilotType_test(); - void setAutopilotType_test(); - void getStatusForCode_test(); - void getLocalX_test(); - void getLocalY_test(); - void getLocalZ_test(); - void getLatitude_test(); - void getLongitude_test(); - void getAltitude_test(); - void getRoll_test(); - void getPitch_test(); - void getYaw_test(); - -private: - -protected: - UAS *prueba; -}; - -UASUnitTest::UASUnitTest() -{ -} - -void UASUnitTest::initTestCase() -{ - mav= new MAVLinkProtocol(); - uas=new UAS(mav,UASID); -} - -void UASUnitTest::cleanupTestCase() -{ - delete uas; - delete mav; - -} - -void UASUnitTest::getUASID_test() -{ - // Test a default ID of zero is assigned - UAS* uas2 = new UAS(mav); - QCOMPARE(uas2->getUASID(), 0); - delete uas2; - - // Test that the chosen ID was assigned at construction - QCOMPARE(uas->getUASID(), UASID); - - // Make sure that no other ID was sert - QEXPECT_FAIL("", "When you set an ID it does not use the default ID of 0", Continue); - QCOMPARE(uas->getUASID(), 0); -} - -void UASUnitTest::getUASName_test() -{ - // Test that the name is build as MAV + ID - QCOMPARE(uas->getUASName(), "MAV 0" + QString::number(UASID)); - -} - -void UASUnitTest::getUpTime_test() -{ - UAS* uas2 = new UAS(mav); - // Test that the uptime starts at zero to a - // precision of seconds - QCOMPARE(floor(uas2->getUptime()/1000.0), 0.0); - - // Sleep for three seconds - QTest::qSleep(3000); - - // Test that the up time is computed correctly to a - // precision of seconds - QCOMPARE(floor(uas2->getUptime()/1000.0), 3.0); - - delete uas2; -} - -void UASUnitTest::getCommunicationStatus_test() -{ - // Verify that upon construction the Comm status is disconnected - QCOMPARE(uas->getCommunicationStatus(), static_cast(UASInterface::COMM_DISCONNECTED)); -} - -void UASUnitTest::filterVoltage_test() -{ - float verificar=uas->filterVoltage(0.4f); - // Verify that upon construction the Comm status is disconnected - QCOMPARE(verificar, 8.52f); -} -void UASUnitTest:: getAutopilotType_test() -{ - int verificar=uas->getAutopilotType(); - // Verify that upon construction the autopilot is set to -1 - QCOMPARE(verificar, -1); -} -void UASUnitTest::setAutopilotType_test() -{ - uas->setAutopilotType(2); - // Verify that the autopilot is set - QCOMPARE(uas->getAutopilotType(), 2); -} - -void UASUnitTest::getStatusForCode_test() -{ - QString state, desc; - state = ""; - desc = ""; - - uas->getStatusForCode(MAV_STATE_UNINIT, state, desc); - QVERIFY(state == "UNINIT"); - - uas->getStatusForCode(MAV_STATE_UNINIT, state, desc); - QVERIFY(state == "UNINIT"); - - uas->getStatusForCode(MAV_STATE_BOOT, state, desc); - QVERIFY(state == "BOOT"); - - uas->getStatusForCode(MAV_STATE_CALIBRATING, state, desc); - QVERIFY(state == "CALIBRATING"); - - uas->getStatusForCode(MAV_STATE_ACTIVE, state, desc); - QVERIFY(state == "ACTIVE"); - - uas->getStatusForCode(MAV_STATE_STANDBY, state, desc); - QVERIFY(state == "STANDBY"); - - uas->getStatusForCode(MAV_STATE_CRITICAL, state, desc); - QVERIFY(state == "CRITICAL"); - - uas->getStatusForCode(MAV_STATE_EMERGENCY, state, desc); - QVERIFY(state == "EMERGENCY"); - - uas->getStatusForCode(MAV_STATE_POWEROFF, state, desc); - QVERIFY(state == "SHUTDOWN"); - - uas->getStatusForCode(5325, state, desc); - QVERIFY(state == "UNKNOWN"); -} - - -void UASUnitTest::getLocalX_test() -{ - QCOMPARE(uas->getLocalX(), 0.0); -} -void UASUnitTest::getLocalY_test() -{ - QCOMPARE(uas->getLocalY(), 0.0); -} -void UASUnitTest::getLocalZ_test() -{ - QCOMPARE(uas->getLocalZ(), 0.0); -} -void UASUnitTest::getLatitude_test() -{ QCOMPARE(uas->getLatitude(), 0.0); -} -void UASUnitTest::getLongitude_test() -{ - QCOMPARE(uas->getLongitude(), 0.0); -} -void UASUnitTest::getAltitude_test() -{ - QCOMPARE(uas->getAltitude(), 0.0); -} -void UASUnitTest::getRoll_test() -{ - QCOMPARE(uas->getRoll(), 0.0); -} -void UASUnitTest::getPitch_test() -{ - QCOMPARE(uas->getPitch(), 0.0); -} -void UASUnitTest::getYaw_test() -{ - QCOMPARE(uas->getYaw(), 0.0); -} - -QTEST_APPLESS_MAIN(UASUnitTest); - -#include "tst_uasunittest.moc" diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index e14f0d20fbaf5e6b38a99af4239030f6f8d084f9..77fdaec15796b0a8fd2a81e2b2dca5bb04fe0af2 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -51,7 +51,7 @@ MOC_DIR = $${BUILDDIR}/moc UI_DIR = $${BUILDDIR}/ui RCC_DIR = $${BUILDDIR}/rcc MAVLINK_CONF = "" -MAVLINKPATH = $$BASEDIR/mavlink/include/v1.0 +MAVLINKPATH = $$BASEDIR/mavlink/include/mavlink/v1.0 DEFINES += MAVLINK_NO_DATA win32 { @@ -92,58 +92,24 @@ INCLUDEPATH += \ # If the user config file exists, it will be included. # if the variable MAVLINK_CONF contains the name of an # additional project, QGroundControl includes the support -# of custom MAVLink messages of this project +# of custom MAVLink messages of this project. It will also +# create a QGC_USE_{AUTOPILOT_NAME}_MESSAGES macro for use +# within the actual code. exists(user_config.pri) { include(user_config.pri) message("----- USING CUSTOM USER QGROUNDCONTROL CONFIG FROM user_config.pri -----") message("Adding support for additional MAVLink messages for: " $$MAVLINK_CONF) message("------------------------------------------------------------------------") } -INCLUDEPATH += $$MAVLINKPATH/common INCLUDEPATH += $$MAVLINKPATH -contains(MAVLINK_CONF, pixhawk) { - # Remove the default set - it is included anyway - INCLUDEPATH -= $$MAVLINKPATH/common - - # PIXHAWK SPECIAL MESSAGES - INCLUDEPATH += $$MAVLINKPATH/pixhawk - DEFINES += QGC_USE_PIXHAWK_MESSAGES -} -contains(MAVLINK_CONF, slugs) { - # Remove the default set - it is included anyway - INCLUDEPATH -= $$MAVLINKPATH/common - - # SLUGS SPECIAL MESSAGES - INCLUDEPATH += $$MAVLINKPATH/slugs - DEFINES += QGC_USE_SLUGS_MESSAGES -} -contains(MAVLINK_CONF, ualberta) { - # Remove the default set - it is included anyway - INCLUDEPATH -= $$MAVLINKPATH/common - - # UALBERTA SPECIAL MESSAGES - INCLUDEPATH += $$MAVLINKPATH/ualberta - DEFINES += QGC_USE_UALBERTA_MESSAGES -} -contains(MAVLINK_CONF, ardupilotmega) { - # Remove the default set - it is included anyway - INCLUDEPATH -= $$MAVLINKPATH/common - INCLUDEPATH -= $$BASEDIR/mavlink/include/v1.0/common - - # UALBERTA SPECIAL MESSAGES - INCLUDEPATH += $$MAVLINKPATH/ardupilotmega - DEFINES += QGC_USE_ARDUPILOTMEGA_MESSAGES -} -contains(MAVLINK_CONF, senseSoar) { - # Remove the default set - it is included anyway - INCLUDEPATH -= $$MAVLINKPATH/common - - # SENSESOAR SPECIAL MESSAGES - INCLUDEPATH += $$MAVLINKPATH/SenseSoar - DEFINES += QGC_USE_SENSESOAR_MESSAGES +isEmpty(MAVLINK_CONF) { + INCLUDEPATH += $$MAVLINKPATH/common +} else { + INCLUDEPATH += $$MAVLINKPATH/$$MAVLINK_CONF + DEFINES += 'MAVLINK_CONF="$${MAVLINK_CONF}.h"' + DEFINES += $$sprintf('QGC_USE_%1_MESSAGES', $$upper($$MAVLINK_CONF)) } - # Include general settings for QGroundControl # necessary as last include to override any non-acceptable settings # done by the plugins above @@ -550,7 +516,7 @@ contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) { message("Including sources for Protocol Buffers") # Enable only if protobuf is available - SOURCES += mavlink/src/v1.0/pixhawk/pixhawk.pb.cc \ + SOURCES += mavlink/share/mavlink/src/v1.0/pixhawk/pixhawk.pb.cc \ src/ui/map3D/ObstacleGroupNode.cc \ src/ui/map3D/GLOverlayGeode.cc } diff --git a/src/LogCompressor.cc b/src/LogCompressor.cc index 53afa4dfdf30b3babdb4c95da6bc146e0ce00162..5d41d08c8ed63b24373398d5c4f7d38449e0f48e 100644 --- a/src/LogCompressor.cc +++ b/src/LogCompressor.cc @@ -1,328 +1,177 @@ -/*=================================================================== -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief Implementation of class LogCompressor - * @author Lorenz Meier - * - */ - -#include -#include -#include -#include -#include -#include "LogCompressor.h" - -#include - -/** - * It will only get active upon calling startCompression() - */ -LogCompressor::LogCompressor(QString logFileName, QString outFileName, int uasid) : - logFileName(logFileName), - outFileName(outFileName), - running(true), - currentDataLine(0), - dataLines(1), - uasid(uasid), - holeFillingEnabled(true) -{ -} - -void LogCompressor::run() -{ - QString separator = "\t"; - QString fileName = logFileName; - QFile file(fileName); - QFile outfile(outFileName); - QStringList* keys = new QStringList(); - QList times;// = new QList(); - QList finalTimes; - - //qDebug() << "LOG COMPRESSOR: Starting" << fileName; - - if (!file.exists() || !file.open(QIODevice::ReadOnly | QIODevice::Text)) { - //qDebug() << "LOG COMPRESSOR: INPUT FILE DOES NOT EXIST"; - emit logProcessingStatusChanged(tr("Log Compressor: Cannot start/compress log file, since input file %1 is not readable").arg(QFileInfo(fileName).absoluteFilePath())); - return; - } - - // Check if file is writeable - if (outFileName == ""/* || !QFileInfo(outfile).isWritable()*/) { - //qDebug() << "LOG COMPRESSOR: OUTPUT FILE DOES NOT EXIST" << outFileName; - emit logProcessingStatusChanged(tr("Log Compressor: Cannot start/compress log file, since output file %1 is not writable").arg(QFileInfo(outFileName).absoluteFilePath())); - return; - } - - // Find all keys - QTextStream in(&file); - - // Search only a certain region, assuming that not more - // than N dimensions at H Hertz can be send - const unsigned int keySearchLimit = 15000; - // e.g. 500 Hz * 30 values or - // e.g. 100 Hz * 150 values - - unsigned int keyCounter = 0; - while (!in.atEnd() && keyCounter < keySearchLimit) { - QString line = in.readLine(); - // Accumulate map of keys - // Data field name is at position 2 - QString key = line.split(separator).at(2); - if (!keys->contains(key)) - { - keys->append(key); - } - keyCounter++; - } - keys->sort(); - - QString header = ""; - QString spacer = ""; - for (int i = 0; i < keys->length(); i++) { - header += keys->at(i) + separator; - spacer += separator; - } - - emit logProcessingStatusChanged(tr("Log compressor: Dataset contains dimension: ") + header); - - // Find all times - //in.reset(); - file.reset(); - in.reset(); - in.resetStatus(); - bool ok; - while (!in.atEnd()) { - QString line = in.readLine(); - // Accumulate map of keys - // Data field name is at position 2b - quint64 time = static_cast(line.split(separator).at(0)).toLongLong(&ok); - if (ok) { - times.append(time); - } - } - - qSort(times); - - qint64 lastTime = -1; - - // Create lines - QStringList* outLines = new QStringList(); - for (int i = 0; i < times.length(); i++) { - // Cast to signed on purpose, 64 bit timestamp still long enough - if (static_cast(times.at(i)) != lastTime) { - outLines->append(QString("%1").arg(times.at(i)) + separator + spacer); - lastTime = static_cast(times.at(i)); - finalTimes.append(times.at(i)); - //qDebug() << "ADDED:" << outLines->last(); - } - } - - dataLines = finalTimes.length(); - - emit logProcessingStatusChanged(tr("Log compressor: Now processing %1 log lines").arg(finalTimes.length())); - - // Fill in the values for all keys - file.reset(); - QTextStream data(&file); - int linecounter = 0; - quint64 lastTimeIndex = 0; - bool failed = false; - - while (!data.atEnd()) { - linecounter++; - currentDataLine = linecounter; - QString line = data.readLine(); - QStringList parts = line.split(separator); - // Get time - quint64 time = static_cast(parts.first()).toLongLong(&ok); - QString field = parts.at(2); - int fieldIndex = keys->indexOf(field); - QString value = parts.at(3); -// // Enforce NaN if no value is present -// if (value.length() == 0 || value == "" || value == " " || value == "\t" || value == "\n") { -// // Hole filling disabled, fill with NaN -// value = "NaN"; -// } - // Get matching output line - - // Constraining the search area might result in not finding a key, - // but it significantly reduces the time needed for the search - // setting a window of 100 entries means that a 1 Hz data point - // can still be located - quint64 offsetLimit = 100; - quint64 offset; - qint64 index = -1; - failed = false; - - // Search the index until it is valid (!= -1) - // or the start of the list has been reached (failed) - while (index == -1 && !failed) { - if (lastTimeIndex > offsetLimit) { - offset = lastTimeIndex - offsetLimit; - } else { - offset = 0; - } - - index = finalTimes.indexOf(time, offset); - if (index == -1) { - if (offset == 0) { - emit logProcessingStatusChanged(tr("Log compressor: Timestamp %1 not found in dataset, ignoring log line %2").arg(time).arg(linecounter)); - qDebug() << "Completely failed finding value"; - //continue; - failed = true; - } else { - emit logProcessingStatusChanged(tr("Log compressor: Timestamp %1 not found in dataset, restarting search.").arg(time)); - offsetLimit*=2; - } - } - } - - if (dataLines > 100) if (index % (dataLines/100) == 0) emit logProcessingStatusChanged(tr("Log compressor: Processed %1% of %2 lines").arg(index/(float)dataLines*100, 0, 'f', 2).arg(dataLines)); - - if (!failed) { - // When the algorithm reaches here the correct index was found - lastTimeIndex = index; - QString outLine = outLines->at(index); - QStringList outParts = outLine.split(separator); - // Replace measurement placeholder with current value - outParts.replace(fieldIndex+1, value); - outLine = outParts.join(separator); - outLines->replace(index, outLine); - } - } - - /////////////////////////// - // HOLE FILLING - - // If hole filling is enabled, run again through the whole file and replace holes - if (holeFillingEnabled) - { - // Build up the fill values - initialize to NaN - QStringList fillValues; - int fillCount = keys->count(); - for (int i = 0; i< fillCount; ++i) - { - fillValues.append("NaN"); - } - - // Run through all lines and replace with fill values - for (int index = 0; index < outLines->count(); ++index) - { - QString line = outLines->at(index); - //qDebug() << "LINE" << line; - QStringList fields = line.split(separator, QString::SkipEmptyParts); - // The fields line contains the timestamp - // index of the data fields therefore runs from 1 to n-1 - int fieldCount = fields.count(); - for (int i = 1; i < fillCount+1; ++i) - { - if (fieldCount <= i) fields.append(""); - - // Allow input data to be screwed up - if (fields.at(i) == "\t" || fields.at(i) == " " || fields.at(i) == "\n") - { - // Remove invalid data - if (fieldCount > fillCount+1) - { - // This field has a seperator value and is too much - //qDebug() << "REMOVED INVALID INPUT DATA"; - fields.removeAt(i); - } - // Continue on invalid data - continue; - } - - // Check if this is NaN - if (fields.at(i) == 0 || fields.at(i) == "") - { - // Value was empty, replace it - fields.replace(i, fillValues[i-1]); - //qDebug() << "FILL" << fillValues.at(i-1); - } - else - { - // Value was not NaN, use it as - // new fill value - fillValues.replace(i-1, fields[i]); - } - } - outLines->replace(index, fields.join(separator)); - } - } - - // Add header, write out file - file.close(); - - if (outFileName == logFileName) { - QFile::remove(file.fileName()); - outfile.setFileName(file.fileName()); - - } - if (!outfile.open(QIODevice::WriteOnly | QIODevice::Text)) - return; - outfile.write(QString(QString("timestamp_ms") + separator + header.replace(" ", "_") + QString("\n")).toLatin1()); - emit logProcessingStatusChanged(tr("Log Compressor: Writing output to file %1").arg(QFileInfo(outFileName).absoluteFilePath())); - - // File output - for (int i = 0; i < outLines->length(); i++) { - //qDebug() << outLines->at(i); - outfile.write(QString(outLines->at(i) + "\n").toLatin1()); - - } - - currentDataLine = 0; - dataLines = 1; - delete keys; - emit logProcessingStatusChanged(tr("Log compressor: Finished processing file: %1").arg(outfile.fileName())); - qDebug() << "Done with logfile processing"; - emit finishedFile(outfile.fileName()); - running = false; -} - -/** - * @param holeFilling If hole filling is enabled, the compressor tries to fill empty data fields with previous - * values from the same variable (or NaN, if no previous value existed) - */ -void LogCompressor::startCompression(bool holeFilling) -{ - // Set hole filling - holeFillingEnabled = holeFilling; - start(); -} - -bool LogCompressor::isFinished() -{ - return !running; -} - -int LogCompressor::getCurrentLine() -{ - return currentDataLine; -} - -int LogCompressor::getDataLines() -{ - return dataLines; -} +/*=================================================================== +QGroundControl Open Source Ground Control Station + +(c) 2009, 2010 QGROUNDCONTROL PROJECT + +This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + +======================================================================*/ + +/** + * @file + * @brief Implementation of class LogCompressor. This class reads in a file containing messages and translates it into a tab-delimited CSV file. + * @author Lorenz Meier + * + */ + +#include +#include +#include +#include +#include +#include +#include "LogCompressor.h" + +#include + +/** + * Initializes all the variables necessary for a compression run. This won't actually happen + * until startCompression(...) is called. + */ +LogCompressor::LogCompressor(QString logFileName, QString outFileName, QString delimiter) : + logFileName(logFileName), + outFileName(outFileName), + running(true), + currentDataLine(0), + holeFillingEnabled(true), + delimiter(delimiter) +{ +} + +void LogCompressor::run() +{ + // Verify that the input file is useable + QFile infile(logFileName); + if (!infile.exists() || !infile.open(QIODevice::ReadOnly | QIODevice::Text)) { + emit logProcessingStatusChanged(tr("Log Compressor: Cannot start/compress log file, since input file %1 is not readable").arg(QFileInfo(infile.fileName()).absoluteFilePath())); + return; + } + + // Verify that the output file is useable + QTemporaryFile outTmpFile; + if (!outTmpFile.open()) { + emit logProcessingStatusChanged(tr("Log Compressor: Cannot start/compress log file, since output file %1 is not writable").arg(QFileInfo(outTmpFile.fileName()).absoluteFilePath())); + return; + } + + + // First we search the input file through keySearchLimit number of lines + // looking for variables. This is neccessary before CSV files require + // the same number of fields for every line. + const unsigned int keySearchLimit = 15000; + unsigned int keyCounter = 0; + QTextStream in(&infile); + QMap messageMap; + while (!in.atEnd() && keyCounter < keySearchLimit) { + QString messageName = in.readLine().split(delimiter).at(2); + messageMap.insert(messageName, 0); + ++keyCounter; + } + + // Now update each key with its index in the output string. These are + // all offset by one to account for the first field: timestamp_ms. + QMap::iterator i = messageMap.begin(); + int j; + for (i = messageMap.begin(), j = 1; i != messageMap.end(); ++i, ++j) { + i.value() = j; + } + + // Open the output file and write the header line to it + QStringList headerList(messageMap.keys()); + QString headerLine = "timestamp_ms" + delimiter + headerList.join(delimiter) + "\n"; + outTmpFile.write(headerLine.toLocal8Bit()); + + emit logProcessingStatusChanged(tr("Log compressor: Dataset contains dimension: ") + headerLine); + + // Reset our position in the input file before we start the main processing loop. + infile.reset(); + in.reset(); + in.resetStatus(); + + // Template list stores a list for populating with data as it's parsed from messages. + QStringList templateList; + for (int i = 0; i < headerList.size() + 1; ++i) { + templateList << (holeFillingEnabled?"NaN":""); + } + QStringList filledList(templateList); + QStringList currentLine = in.readLine().split(delimiter); + currentDataLine = 1; + while (!in.atEnd()) { + // We only overwrite data from the last time set if we aren't doing a zero-order hold + if (!holeFillingEnabled) { + filledList = templateList; + } + // Populate this time set with the data from this first message + filledList.replace(0, currentLine.at(0)); + filledList.replace(messageMap.value(currentLine.at(2)), currentLine.at(3)); + + // Continue searching for messages in the same time set and adding that data + // to the current time set if appropriate. + while (!in.atEnd()) { + QStringList newLine = in.readLine().split(delimiter); + ++currentDataLine; + + if (newLine.at(0) == currentLine.at(0)) { + QString currentDataName = newLine.at(2); + QString currentDataValue = newLine.at(3); + filledList.replace(messageMap.value(currentDataName), currentDataValue); + } else { + currentLine = newLine; + break; + } + } + + // Write this current time set out to the file + QString output = filledList.join(delimiter) + "\n"; + outTmpFile.write(output.toLocal8Bit()); + } + + // We're now done with the source file + infile.close(); + + // Make sure we remove the source file before replacing it. + QFile::remove(outFileName); + outTmpFile.copy(outFileName); + outTmpFile.close(); + emit logProcessingStatusChanged(tr("Log Compressor: Writing output to file %1").arg(QFileInfo(outFileName).absoluteFilePath())); + + // Clean up and update the status before we return. + currentDataLine = 0; + emit logProcessingStatusChanged(tr("Log compressor: Finished processing file: %1").arg(outFileName)); + emit finishedFile(outFileName); + qDebug() << "Done with logfile processing"; + running = false; +} + +/** + * @param holeFilling If hole filling is enabled, the compressor tries to fill empty data fields with previous + * values from the same variable (or NaN, if no previous value existed) + */ +void LogCompressor::startCompression(bool holeFilling) +{ + holeFillingEnabled = holeFilling; + start(); +} + +bool LogCompressor::isFinished() +{ + return !running; +} + +int LogCompressor::getCurrentLine() +{ + return currentDataLine; +} diff --git a/src/LogCompressor.h b/src/LogCompressor.h index f9a0b855393be81a36acd7cb41b76923c43c5f3d..138c5a59c6698b947d5541a00b3eb36a873af102 100644 --- a/src/LogCompressor.h +++ b/src/LogCompressor.h @@ -8,29 +8,31 @@ class LogCompressor : public QThread Q_OBJECT public: /** @brief Create the log compressor. It will only get active upon calling startCompression() */ - LogCompressor(QString logFileName, QString outFileName="", int uasid = 0); + LogCompressor(QString logFileName, QString outFileName="", QString delimiter="\t"); /** @brief Start the compression of a raw, line-based logfile into a CSV file */ void startCompression(bool holeFilling=false); bool isFinished(); - int getDataLines(); int getCurrentLine(); protected: - void run(); - QString logFileName; - QString outFileName; - bool running; - int currentDataLine; - int dataLines; - int uasid; - bool holeFillingEnabled; ///< Enables the filling of holes in the dataset with the previous value (or NaN if none exists) + void run(); ///< This function actually performs the compression. It's an overloaded function from QThread + QString logFileName; ///< The input file name. + QString outFileName; ///< The output file name. If blank defaults to logFileName + bool running; ///< True when the startCompression() function is operating. + int currentDataLine; ///< The current line of data that is being processed. Only relevant when running==true + QString delimiter; ///< Delimiter between fields in the output file. Defaults to tab ('\t') + bool holeFillingEnabled; ///< Enables the filling of holes in the dataset with the previous value (or NaN if none exists) signals: + /** @brief This signal is emitted when there is a change in the status of the parsing algorithm. For instance if an error is encountered. + * @param status A status message + */ + void logProcessingStatusChanged(QString status); + /** @brief This signal is emitted once a logfile has been finished writing - * @param fileName The name out the output (CSV) file + * @param fileName The name of the output (CSV) file */ - void logProcessingStatusChanged(QString); void finishedFile(QString fileName); }; -#endif // LOGCOMPRESSOR_H +#endif // LOGCOMPRESSOR_H \ No newline at end of file diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index ec72b9f308b4431cee3b01ceb7f136eb45bdb343..fe631d074891652efacdeb4fe79b6f764d5e52c8 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -217,8 +217,18 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) // read extended header uint8_t* payload = reinterpret_cast(message.payload64); + memcpy(&extended_message.extended_payload_len, payload + 3, 4); + // Check if message is valid + if + (b.size() != MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_EXTENDED_HEADER_LEN+ extended_message.extended_payload_len) + { + //invalid message + qDebug() << "GOT INVALID EXTENDED MESSAGE, ABORTING"; + return; + } + const uint8_t* extended_payload = reinterpret_cast(b.constData()) + MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_EXTENDED_HEADER_LEN; // copy extended payload data diff --git a/src/comm/QGCMAVLink.h b/src/comm/QGCMAVLink.h index b03e72e2712505f84e9bd5354a5151252b936243..a73c4524ac64949e2023fdc291e1e6da1d330097 100644 --- a/src/comm/QGCMAVLink.h +++ b/src/comm/QGCMAVLink.h @@ -33,20 +33,8 @@ This file is part of the QGROUNDCONTROL project #include #include -#ifdef QGC_USE_PIXHAWK_MESSAGES -#include -#endif - -#ifdef QGC_USE_SLUGS_MESSAGES -#include -#endif - -#ifdef QGC_USE_UALBERTA_MESSAGES -#include -#endif - -#ifdef QGC_USE_ARDUPILOTMEGA_MESSAGES -#include +#ifdef MAVLINK_CONF +#include MAVLINK_CONF #endif diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index a0c75d8c6e706ecb6d55007c02364c81a6d6d483..92f969941d990fdee2e7517ce250f4afe5950c5a 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -2103,7 +2103,7 @@ void UAS::executeCommand(MAV_CMD command) { mavlink_message_t msg; mavlink_command_long_t cmd; - cmd.command = (uint8_t)command; + cmd.command = (uint16_t)command; cmd.confirmation = 0; cmd.param1 = 0.0f; cmd.param2 = 0.0f; @@ -2122,7 +2122,7 @@ void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float { mavlink_message_t msg; mavlink_command_long_t cmd; - cmd.command = (uint8_t)command; + cmd.command = (uint16_t)command; cmd.confirmation = confirmation; cmd.param1 = param1; cmd.param2 = param2; diff --git a/src/ui/Linechart.ui b/src/ui/Linechart.ui index beea2176bd08bc5afbf05623fbb1238c2ae8d6aa..58449dac50fdf8328e382939ce4a97f93da0f256 100644 --- a/src/ui/Linechart.ui +++ b/src/ui/Linechart.ui @@ -25,8 +25,11 @@ Form - - + + + + + @@ -46,13 +49,16 @@ 16777215 + + + Curve Selection Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - + 2 @@ -82,6 +88,9 @@ false + + + QFrame::NoFrame @@ -99,17 +108,103 @@ 0 0 - 219 - 475 + 368 + 488 + + + + 2 + + + + + + All MAVs + + + + + + + + 0 + + + + + 0 + + + + + Display only variable names in curve list + + + Short names + + + + + + + Display variable units in curve list + + + Display variable units in curve list + + + Show units + + + true + + + + + + + + + + + Rotate color scheme for all curves + + + Recolor + + + + + + + Qt::Vertical + + + QSizePolicy::Minimum + + + + 20 + 0 + + + + + + + + + + - + @@ -129,47 +224,14 @@ 300 + + + Diagram - - - - Short Names - - - - - - - Recolor - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - All MAVs - - - - diff --git a/src/ui/MAVLinkDecoder.cc b/src/ui/MAVLinkDecoder.cc index 091b2f4474eb16f2e8165a4e091efebf839775a3..f62fd8b680e318cf3bff1ac87614720c736e891b 100644 --- a/src/ui/MAVLinkDecoder.cc +++ b/src/ui/MAVLinkDecoder.cc @@ -12,10 +12,10 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) : componentID[i] = -1; componentMulti[i] = false; onboardTimeOffset[i] = 0; + onboardToGCSUnixTimeOffsetAndDelay[i] = 0; + firstOnboardTime[i] = 0; } - - // Fill filter messageFilter.insert(MAVLINK_MSG_ID_HEARTBEAT, false); messageFilter.insert(MAVLINK_MSG_ID_SYS_STATUS, false); diff --git a/src/ui/QGCDataPlot2D.cc b/src/ui/QGCDataPlot2D.cc index 4d44fa82499bdd6db70b3a10491e6a29b05342b7..9013ea3fdb05ad08ef92655f5b221c4c532e695c 100644 --- a/src/ui/QGCDataPlot2D.cc +++ b/src/ui/QGCDataPlot2D.cc @@ -246,21 +246,27 @@ void QGCDataPlot2D::exportSVG(QString fileName) */ void QGCDataPlot2D::selectFile() { - // Let user select the log file name - //QDate date(QDate::currentDate()); - // QString("./pixhawk-log-" + date.toString("yyyy-MM-dd") + "-" + QString::number(logindex) + ".log") - + // Open a file dialog prompting the user for the file to load. + // Note the special case for the Pixhawk. if (ui->inputFileType->currentText().contains("pxIMU") || ui->inputFileType->currentText().contains("RAW")) { fileName = QFileDialog::getOpenFileName(this, tr("Specify log file name"), QString(), "Logfile (*.imu *.raw)"); - } else { + } + else + { fileName = QFileDialog::getOpenFileName(this, tr("Specify log file name"), QString(), "Logfile (*.csv *.txt *.log)"); } - // Store reference to file + // Check if the user hit cancel, which results in a Null string. + // If this is the case, we just stop. + if (fileName.isNull()) + { + return; + } + // Now attempt to open the file QFileInfo fileInfo(fileName); - - if (!fileInfo.isReadable()) { + if (!fileInfo.isReadable()) + { QMessageBox msgBox; msgBox.setIcon(QMessageBox::Critical); msgBox.setText("Could not open file"); @@ -269,7 +275,9 @@ void QGCDataPlot2D::selectFile() msgBox.setDefaultButton(QMessageBox::Ok); msgBox.exec(); ui->filenameLabel->setText(tr("Could not open %1").arg(fileInfo.baseName()+"."+fileInfo.completeSuffix())); - } else { + } + else + { ui->filenameLabel->setText(tr("Opened %1").arg(fileInfo.completeBaseName()+"."+fileInfo.completeSuffix())); // Open and import the file loadFile(); @@ -552,8 +560,8 @@ void QGCDataPlot2D::loadCsvLog(QString file, QString xAxisName, QString yAxisFil bool QGCDataPlot2D::calculateRegression() { - // TODO Add support for quadratic / cubic curve fitting - return calculateRegression(ui->xRegressionComboBox->currentText(), ui->yRegressionComboBox->currentText(), "linear"); + // TODO: Add support for quadratic / cubic curve fitting + return calculateRegression(ui->xRegressionComboBox->currentText(), ui->yRegressionComboBox->currentText(), "linear"); } /** @@ -571,17 +579,22 @@ bool QGCDataPlot2D::calculateRegression(QString xName, QString yName, QString me ui->xRegressionComboBox->setCurrentIndex(curveNames.indexOf(xName)); ui->yRegressionComboBox->setCurrentIndex(curveNames.indexOf(yName)); } + + // Create a couple of arrays for us to use to temporarily store some of the data from the plot. + // These arrays are allocated on the heap as they are far too big to go in the stack and will + // cause an overflow. + // TODO: Look into if this would be better done by having a getter return const double pointers instead + // of using memcpy(). const int size = 100000; - double x[size]; - double y[size]; + double *x = new double[size]; + double *y = new double[size]; int copied = plot->data(yName, x, y, size); if (method == "linear") { double a; // Y-axis crossing double b; // Slope double r; // Regression coefficient - int lin = linearRegression(x, y, copied, &a, &b, &r); - if(lin == 1) { + if (linearRegression(x, y, copied, &a, &b, &r)) { function = tr("%1 = %2 * %3 + %4 | R-coefficient: %5").arg(yName, QString::number(b), xName, QString::number(a), QString::number(r)); // Plot curve @@ -591,19 +604,16 @@ bool QGCDataPlot2D::calculateRegression(QString xName, QString yName, QString me plot->setStyleText("lines"); // x-value of the current rightmost x position in the plot plot->appendData(tr("regression %1-%2").arg(xName, yName), plot->invTransform(QwtPlot::xBottom, plot->width() - plot->width()*0.08f), (a + b*plot->invTransform(QwtPlot::xBottom, plot->width() - plot->width() * 0.08f))); - result = true; + + result = true; } else { function = tr("Linear regression failed. (Limit: %1 data points. Try with less)").arg(size); - result = false; } - } else if (method == "quadratic") { - - } else if (method == "cubic") { - } else { function = tr("Regression method %1 not found").arg(method); - result = false; } + + delete x, y; } else { // xName == yName function = tr("Please select different X and Y dimensions, not %1 = %2").arg(xName, yName); @@ -627,7 +637,7 @@ bool QGCDataPlot2D::calculateRegression(QString xName, QString yName, QString me * the match of the regression. * @return 1 on success, 0 on failure (e.g. because of infinite slope) */ -int QGCDataPlot2D::linearRegression(double* x,double* y,int n,double* a,double* b,double* r) +bool QGCDataPlot2D::linearRegression(double *x, double *y, int n, double *a, double *b, double *r) { int i; double sumx=0,sumy=0,sumx2=0,sumy2=0,sumxy=0; @@ -637,7 +647,7 @@ int QGCDataPlot2D::linearRegression(double* x,double* y,int n,double* a,double* *b = 0; *r = 0; if (n < 2) - return(FALSE); + return true; /* Conpute some things we need */ for (i=0; iisPlayingLogFile()) { player->playPause(false); - if (enabled) + if (checked) { if (!player->selectLogFile()) return; } @@ -143,23 +142,35 @@ void QGCToolBar::playLogFile(bool enabled) { if (!player->selectLogFile()) return; } - player->playPause(enabled); + player->playPause(checked); } } -void QGCToolBar::logging(bool enabled) +void QGCToolBar::logging(bool checked) { // Stop logging in any case MainWindow::instance()->getMAVLink()->enableLogging(false); - if (enabled) + + // If the user is enabling logging + if (checked) { + // Prompt the user for a filename/location to save to QString fileName = QFileDialog::getSaveFileName(this, tr("Specify MAVLink log file to save to"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("MAVLink Logfile (*.mavlink *.log *.bin);;")); + // Check that they didn't cancel out + if (fileName.isNull()) + { + toggleLoggingAction->setChecked(false); + return; + } + + // Make sure the file's named properly if (!fileName.endsWith(".mavlink")) { fileName.append(".mavlink"); } + // Check that we can save the logfile QFileInfo file(fileName); if ((file.exists() && !file.isWritable())) { @@ -171,6 +182,7 @@ void QGCToolBar::logging(bool enabled) msgBox.setDefaultButton(QMessageBox::Ok); msgBox.exec(); } + // Otherwise we're off and logging else { MainWindow::instance()->getMAVLink()->setLogfileName(fileName); diff --git a/src/ui/QGCToolBar.h b/src/ui/QGCToolBar.h index e02eca683a0e2a0b903c8fdefed05f72d1bfdcf9..86f658df1d5198f6948d014cb6cd3fa395287ce9 100644 --- a/src/ui/QGCToolBar.h +++ b/src/ui/QGCToolBar.h @@ -55,9 +55,9 @@ public slots: /** @brief Received system text message */ void receiveTextMessage(int uasid, int componentid, int severity, QString text); /** @brief Start / stop logging */ - void logging(bool enabled); + void logging(bool checked); /** @brief Start playing logfile */ - void playLogFile(bool enabled); + void playLogFile(bool checked); /** @brief Set log playing component */ void setLogPlayer(QGCMAVLinkLogPlayer* player); /** @brief Update battery charge state */ diff --git a/src/ui/RadioCalibration/AbstractCalibrator.cc b/src/ui/RadioCalibration/AbstractCalibrator.cc index a07d0576fe9002c1c115518e67a943bf79cb7dfc..2ab73111b0c28c183ae18aa1e7d8bbd8ae458fa2 100644 --- a/src/ui/RadioCalibration/AbstractCalibrator.cc +++ b/src/ui/RadioCalibration/AbstractCalibrator.cc @@ -14,25 +14,42 @@ AbstractCalibrator::~AbstractCalibrator() uint16_t AbstractCalibrator::logAverage() { + // Short-circuit here if the log is empty otherwise we get a div-by-0 error. + if (log->empty()) + { + return 0; + } + uint16_t total = 0; for (int i=0; isize(); ++i) + { total += log->value(i); + } return total/log->size(); } uint16_t AbstractCalibrator::logExtrema() { uint16_t extrema = logAverage(); - if (logAverage() < 1500) { - for (int i=0; isize(); ++i) { + if (logAverage() < 1500) + { + for (int i=0; isize(); ++i) + { if (log->value(i) < extrema) - extrema = log->value(i); + { + extrema = log->value(i); + } } extrema -= 5; // add 5us to prevent integer overflow - } else { - for (int i=0; isize(); ++i) { + } + else + { + for (int i=0; isize(); ++i) + { if (log->value(i) > extrema) + { extrema = log->value(i); + } } extrema += 5; // subtact 5us to prevent integer overflow } @@ -44,6 +61,8 @@ void AbstractCalibrator::channelChanged(uint16_t raw) { pulseWidth->setText(QString::number(raw)); if (log->size() == 5) + { log->pop_front(); + } log->push_back(raw); } diff --git a/src/ui/WaypointList.cc b/src/ui/WaypointList.cc index 1c9bdb4453c744be8e080b031d56a66903514a68..f3eeb62c6e76b4267a408e4f904fdd4a5883d668 100644 --- a/src/ui/WaypointList.cc +++ b/src/ui/WaypointList.cc @@ -246,12 +246,22 @@ void WaypointList::addEditable() if (uas) { // Create first waypoint at current MAV position - addCurrentPositionWaypoint(); + if (uas->localPositionKnown() || uas->globalPositionKnown()) + { + addCurrentPositionWaypoint(); + } + else + { + // MAV connected, but position unknown, add default waypoint + updateStatusLabel(tr("WARNING: No position known. Adding default LOCAL (NED) waypoint")); + wp = new Waypoint(0, 0, 0, -0.50, 0, 0.20, 0, 0,true, true, MAV_FRAME_LOCAL_NED, MAV_CMD_NAV_WAYPOINT); + WPM->addWaypointEditable(wp); + } } else { //Since no UAV available, create first default waypoint. - updateStatusLabel(tr("No UAV. Added default LOCAL (NED) waypoint")); + updateStatusLabel(tr("No UAV connected. Adding default LOCAL (NED) waypoint")); wp = new Waypoint(0, 0, 0, -0.50, 0, 0.20, 0, 0,true, true, MAV_FRAME_LOCAL_NED, MAV_CMD_NAV_WAYPOINT); WPM->addWaypointEditable(wp); //create a popup notifying the user about the limitations of offline editing diff --git a/src/ui/linechart/LinechartWidget.cc b/src/ui/linechart/LinechartWidget.cc index 2de896e4a96270b96bfe329debd247b867420604..85834ce5ac1fe51032a4266f29f6f40a8225e178 100644 --- a/src/ui/linechart/LinechartWidget.cc +++ b/src/ui/linechart/LinechartWidget.cc @@ -135,8 +135,6 @@ LinechartWidget::LinechartWidget(int systemid, QWidget *parent) : QWidget(parent variance->setText("Variance"); curvesWidgetLayout->addWidget(variance, labelRow, 6); - // Add and customize plot elements (right side) - // Create the layout createLayout(); @@ -184,7 +182,7 @@ void LinechartWidget::writeSettings() QSettings settings; settings.beginGroup("LINECHART"); if (timeButton) settings.setValue("ENFORCE_GROUNDTIME", timeButton->isChecked()); - if (unitsCheckBox) settings.setValue("SHOW_UNITS", unitsCheckBox->isChecked()); + if (ui.showUnitsCheckBox) settings.setValue("SHOW_UNITS", ui.showUnitsCheckBox->isChecked()); if (ui.shortNameCheckBox) settings.setValue("SHORT_NAMES", ui.shortNameCheckBox->isChecked()); settings.endGroup(); settings.sync(); @@ -200,7 +198,7 @@ void LinechartWidget::readSettings() activePlot->enforceGroundTime(settings.value("ENFORCE_GROUNDTIME", timeButton->isChecked()).toBool()); timeButton->setChecked(settings.value("ENFORCE_GROUNDTIME", timeButton->isChecked()).toBool()); } - if (unitsCheckBox) unitsCheckBox->setChecked(settings.value("SHOW_UNITS", unitsCheckBox->isChecked()).toBool()); + if (ui.showUnitsCheckBox) ui.showUnitsCheckBox->setChecked(settings.value("SHOW_UNITS", ui.showUnitsCheckBox->isChecked()).toBool()); if (ui.shortNameCheckBox) ui.shortNameCheckBox->setChecked(settings.value("SHORT_NAMES", ui.shortNameCheckBox->isChecked()).toBool()); settings.endGroup(); } @@ -278,13 +276,9 @@ void LinechartWidget::createLayout() connect(timeButton, SIGNAL(clicked(bool)), activePlot, SLOT(enforceGroundTime(bool))); connect(timeButton, SIGNAL(clicked()), this, SLOT(writeSettings())); - unitsCheckBox = new QCheckBox(this); - unitsCheckBox->setText(tr("Show units")); - unitsCheckBox->setChecked(true); - unitsCheckBox->setToolTip(tr("Enable unit display in curve list")); - unitsCheckBox->setWhatsThis(tr("Enable unit display in curve list")); - layout->addWidget(unitsCheckBox, 1, 5); - connect(unitsCheckBox, SIGNAL(clicked()), this, SLOT(writeSettings())); + // Initialize the "Show units" checkbox. This is configured in the .ui file, so all + // we do here is attach the clicked() signal. + connect(ui.showUnitsCheckBox, SIGNAL(clicked()), this, SLOT(writeSettings())); ui.diagramGroupBox->setLayout(layout); @@ -671,8 +665,8 @@ void LinechartWidget::addCurve(const QString& curve, const QString& unit) unitLabel->setToolTip(tr("Unit of ") + curve); unitLabel->setWhatsThis(tr("Unit of ") + curve); curvesWidgetLayout->addWidget(unitLabel, labelRow, 4); - unitLabel->setVisible(unitsCheckBox->isChecked()); - connect(unitsCheckBox, SIGNAL(clicked(bool)), unitLabel, SLOT(setVisible(bool))); + unitLabel->setVisible(ui.showUnitsCheckBox->isChecked()); + connect(ui.showUnitsCheckBox, SIGNAL(clicked(bool)), unitLabel, SLOT(setVisible(bool))); // Mean mean = new QLabel(this); diff --git a/src/ui/linechart/LinechartWidget.h b/src/ui/linechart/LinechartWidget.h index 61e9ee884c1423200bd58fe1c8cbe391b020fa32..d111b2548f15a0234e711f5e33e980142dcc0722 100644 --- a/src/ui/linechart/LinechartWidget.h +++ b/src/ui/linechart/LinechartWidget.h @@ -163,7 +163,6 @@ protected: QToolButton* scalingLinearButton; QToolButton* scalingLogButton; QToolButton* logButton; - QPointer unitsCheckBox; QPointer timeButton; QFile* logFile; diff --git a/src/ui/linechart/Linecharts.cc b/src/ui/linechart/Linecharts.cc index bbfa282e37571ceedbae658ce5840d53c4e660ca..36d86d01e6a0757905b189629873aae74fd0b2d0 100644 --- a/src/ui/linechart/Linecharts.cc +++ b/src/ui/linechart/Linecharts.cc @@ -63,6 +63,7 @@ void Linecharts::hideEvent(QHideEvent* event) void Linecharts::selectSystem(int systemid) { + Q_UNUSED(systemid); // QWidget* prevWidget = currentWidget(); // if (prevWidget) // { diff --git a/src/ui/map3D/ObstacleGroupNode.cc b/src/ui/map3D/ObstacleGroupNode.cc index de01609228a26affed9174463f7195c165d036aa..aae78bfc4e48c647acc6d2a804833c3aa52d8ace 100644 --- a/src/ui/map3D/ObstacleGroupNode.cc +++ b/src/ui/map3D/ObstacleGroupNode.cc @@ -101,6 +101,7 @@ ObstacleGroupNode::update(double robotX, double robotY, double robotZ, sd->getOrCreateStateSet()->setMode(GL_BLEND, osg::StateAttribute::ON); sd->setColor(osg::Vec4(r, g, b, 1.0f)); + sd->setUseDisplayList(false); geode->addDrawable(sd); } diff --git a/thirdParty/fetchUpstream.sh b/thirdParty/fetchUpstream similarity index 71% rename from thirdParty/fetchUpstream.sh rename to thirdParty/fetchUpstream index 90d90ec32c4ab4d977c5a1d1abeeb05f59394ad6..73f92dab0894fa98cf53019eabe9bc494845efe4 100755 --- a/thirdParty/fetchUpstream.sh +++ b/thirdParty/fetchUpstream @@ -1,6 +1,6 @@ #!/bin/bash QSERIAL_TAG=004e3de552fe25fee593dfcb03e2ffa82cb0b152 -MAVLINK_VERSION=1.0.0 +MAVLINK_VERSION=1.0.6 libList="mavlink qserialport" @@ -30,13 +30,14 @@ function processLib fetch_git qserialport git://gitorious.org/inbiza-labs/qserialport.git master $QSERIAL_TAG ;; "mavlink") - rm -rf mavlink - mavlinkName=mavlink-$MAVLINK_VERSION-Linux - wget https://github.com/downloads/mavlink/mavlink/$mavlinkName.tar.gz - tar -xzvf $mavlinkName.tar.gz - mv $mavlinkName/usr/local/include/mavlink mavlink - rm -rf $mavlinkName - rm -rf $mavlinkName.tar.gz + cd $topDir/mavlink + rm -rf VERSION mavlink* include lib share *.zip + wget https://github.com/downloads/mavlink/mavlink/mavlink-${MAVLINK_VERSION}.zip + unzip mavlink-${MAVLINK_VERSION}.zip + mv mavlink-${MAVLINK_VERSION}/* . + rm -rf mavlink* + echo $MAVLINK_VERSION > VERSION + cd $topDir ;; "all") for lib in $libList @@ -52,6 +53,7 @@ function processLib echo unknown lib, possiblities are: $libList exit 1 esac + REPLY= } @@ -65,7 +67,7 @@ then do processLib $OPT done - + elif [ $# == 1 ] then lib=$1