diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index c2d8fcf4e1c8d2c6a28a561296e16365964b6e8a..c48292c4747a589051641bf377e348d8f97c983e 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -388,7 +388,7 @@ contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) { message("Including headers for Protocol Buffers") # Enable only if protobuf is available - HEADERS += ../mavlink/include/pixhawk/pixhawk.pb.h \ + HEADERS += thirdParty/mavlink/include/pixhawk/pixhawk.pb.h \ src/ui/map3D/ObstacleGroupNode.h } contains(DEPENDENCIES_PRESENT, libfreenect) { @@ -530,7 +530,7 @@ contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) { message("Including sources for Protocol Buffers") # Enable only if protobuf is available - SOURCES += ../mavlink/src/pixhawk/pixhawk.pb.cc \ + SOURCES += thirdParty/mavlink/src/pixhawk/pixhawk.pb.cc \ src/ui/map3D/ObstacleGroupNode.cc } contains(DEPENDENCIES_PRESENT, libfreenect) { diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index b12a82c7aebbb30c7e9d1112d11776a2174bb9f0..f7647499dbabff4602e4550c3d526c7da8642602 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -201,7 +201,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) // continue; // } //#endif -#ifdef QGC_PROTOBUF_ENABLED +#if defined(QGC_PROTOBUF_ENABLED) if (message.msgid == MAVLINK_MSG_ID_EXTENDED_MESSAGE) { @@ -218,6 +218,8 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) // copy extended payload data memcpy(extended_message.extended_payload, extended_payload, extended_message.extended_payload_len); +#if defined(QGC_USE_PIXHAWK_MESSAGES) + if (protobufManager.cacheFragment(extended_message)) { std::tr1::shared_ptr protobuf_msg; @@ -262,6 +264,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) } } } +#endif position += extended_message.extended_payload_len; diff --git a/src/comm/MAVLinkProtocol.h b/src/comm/MAVLinkProtocol.h index 32a3755217aed6f1054ac4421f51efca371b5f14..58910244f525e0548e628fc7d8eba4a1de3d9b14 100644 --- a/src/comm/MAVLinkProtocol.h +++ b/src/comm/MAVLinkProtocol.h @@ -42,9 +42,13 @@ This file is part of the QGROUNDCONTROL project #include "QGCMAVLink.h" #include "QGC.h" -#ifdef QGC_PROTOBUF_ENABLED +#if defined(QGC_PROTOBUF_ENABLED) +#include +#include +#if defined(QGC_USE_PIXHAWK_MESSAGES) #include #endif +#endif /** @@ -202,14 +206,14 @@ protected: int currLossCounter; bool versionMismatchIgnore; int systemId; -#ifdef QGC_PROTOBUF_ENABLED +#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) mavlink::ProtobufManager protobufManager; #endif signals: /** @brief Message received and directly copied via signal */ void messageReceived(LinkInterface* link, mavlink_message_t message); -#ifdef QGC_PROTOBUF_ENABLED +#if defined(QGC_PROTOBUF_ENABLED) /** @brief Message received via signal */ void extendedMessageReceived(LinkInterface *link, std::tr1::shared_ptr message); #endif diff --git a/src/uas/PxQuadMAV.cc b/src/uas/PxQuadMAV.cc index cc72fe32a1dce7c8029e68055f27e55c3ccdf5ed..0629924bb3792ae61e464cf4d317221c65a156af 100644 --- a/src/uas/PxQuadMAV.cc +++ b/src/uas/PxQuadMAV.cc @@ -206,7 +206,7 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) #endif } -#ifdef QGC_PROTOBUF_ENABLED +#if defined(QGC_PROTOBUF_ENABLED) void PxQuadMAV::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr message) { UAS::receiveExtendedMessage(link, message); diff --git a/src/uas/PxQuadMAV.h b/src/uas/PxQuadMAV.h index b52ea999ea02094523ff3e700c9490169f649716..212c8067f5806bea39da5b25b572644003e59c49 100644 --- a/src/uas/PxQuadMAV.h +++ b/src/uas/PxQuadMAV.h @@ -35,7 +35,7 @@ public: public slots: /** @brief Receive a MAVLink message from this MAV */ void receiveMessage(LinkInterface* link, mavlink_message_t message); -#ifdef QGC_PROTOBUF_ENABLED +#if defined(QGC_PROTOBUF_ENABLED) /** @brief Receive a Protobuf message from this MAV */ void receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr message); #endif diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 6d77db8baab28cf7c20f2939f90fa16d08571420..a1cc4989cb5437f843efe5f6544193d970f3d752 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -75,7 +75,7 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), pitch(0.0), yaw(0.0), statusTimeout(new QTimer(this)), -#ifdef QGC_PROTOBUF_ENABLED +#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) receivedPointCloudTimestamp(0.0), receivedRGBDImageTimestamp(0.0), receivedObstacleListTimestamp(0.0), @@ -1033,7 +1033,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) } } -#ifdef QGC_PROTOBUF_ENABLED +#if defined(QGC_PROTOBUF_ENABLED) void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr message) { if (!link) @@ -1080,6 +1080,7 @@ void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptrGetTypeName() == pointCloud.GetTypeName()) { receivedPointCloudTimestamp = QGC::groundTimeSeconds(); @@ -1112,6 +1113,7 @@ void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr +#ifdef QGC_USE_PIXHAWK_MESSAGES #include #endif +#endif /** * @brief Interface for all robots. @@ -94,7 +96,7 @@ public: virtual bool getSelected() const = 0; -#ifdef QGC_PROTOBUF_ENABLED +#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) virtual px::PointCloudXYZRGB getPointCloud() = 0; virtual px::PointCloudXYZRGB getPointCloud(qreal& receivedTimestamp) = 0; virtual px::RGBDImage getRGBDImage() = 0; diff --git a/src/ui/HSIDisplay.cc b/src/ui/HSIDisplay.cc index 20b8c09e7db0652c98e0cfb576a70172906eb313..9edb21991c45806d62e984967c92947c2ae64046 100644 --- a/src/ui/HSIDisplay.cc +++ b/src/ui/HSIDisplay.cc @@ -637,10 +637,39 @@ void HSIDisplay::keyPressEvent(QKeyEvent* event) statusClearTimer.start(); sendBodySetPointCoordinates(); } - else + else if ((event->key() == Qt::Key_Up)) { - HDDisplay::keyPressEvent(event); + setBodySetpointCoordinateXY(0.5, 0); } + else if ((event->key() == Qt::Key_Down)) + { + setBodySetpointCoordinateXY(-0.5, 0); + } + else if ((event->key() == Qt::Key_Left)) + { + setBodySetpointCoordinateXY(0, -0.5); + } + else if ((event->key() == Qt::Key_Right)) + { + setBodySetpointCoordinateXY(0, 0.5); + } + else if ((event->key() == Qt::Key_Plus)) + { + setBodySetpointCoordinateZ(-0.2); + } + else if ((event->key() == Qt::Key_Minus)) + { + setBodySetpointCoordinateZ(+0.2); + } + else if ((event->key() == Qt::Key_L)) + { + setBodySetpointCoordinateYaw(-0.1); + } + else if ((event->key() == Qt::Key_R)) + { + setBodySetpointCoordinateYaw(0.1); + } + HDDisplay::keyPressEvent(event); } void HSIDisplay::contextMenuEvent (QContextMenuEvent* event) diff --git a/src/ui/QGCRGBDView.cc b/src/ui/QGCRGBDView.cc index cfa24beac5d0e7d5cd1cf859771b8cf8db5487c0..36f8b5e042a5861090d87091562d28ff6a9527e5 100644 --- a/src/ui/QGCRGBDView.cc +++ b/src/ui/QGCRGBDView.cc @@ -220,7 +220,7 @@ float colormapJet[128][3] = { void QGCRGBDView::updateData(UASInterface *uas) { -#ifdef QGC_PROTOBUF_ENABLED +#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) px::RGBDImage rgbdImage = uas->getRGBDImage(); if (rgbdImage.rows() == 0 || rgbdImage.cols() == 0 || (!rgbEnabled && !depthEnabled)) diff --git a/src/ui/map3D/Pixhawk3DWidget.cc b/src/ui/map3D/Pixhawk3DWidget.cc index 22af254d8748d1c7b02ec1152a548fadec240d3c..ccc51e0f0d9af491c7c75318b743263ab3166d43 100644 --- a/src/ui/map3D/Pixhawk3DWidget.cc +++ b/src/ui/map3D/Pixhawk3DWidget.cc @@ -45,7 +45,7 @@ #include "QGC.h" #include "gpl.h" -#ifdef QGC_PROTOBUF_ENABLED +#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) #include #include #endif @@ -111,7 +111,7 @@ Pixhawk3DWidget::Pixhawk3DWidget(QWidget* parent) rgbd3DNode = createRGBD3D(); rollingMap->addChild(rgbd3DNode); -#ifdef QGC_PROTOBUF_ENABLED +#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) obstacleGroupNode = new ObstacleGroupNode; obstacleGroupNode->init(); rollingMap->addChild(obstacleGroupNode); @@ -861,7 +861,7 @@ Pixhawk3DWidget::display(void) rollingMap->setChildValue(mapNode, displayImagery); rollingMap->setChildValue(waypointGroupNode, displayWaypoints); rollingMap->setChildValue(targetNode, enableTarget); -#ifdef QGC_PROTOBUF_ENABLED +#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) rollingMap->setChildValue(obstacleGroupNode, displayObstacleList); rollingMap->setChildValue(pathNode, displayPath); #endif @@ -921,7 +921,7 @@ Pixhawk3DWidget::display(void) updateTarget(robotX, robotY, robotZ); } -#ifdef QGC_PROTOBUF_ENABLED +#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) if (displayRGBD2D || displayRGBD3D) { updateRGBD(robotX, robotY, robotZ); @@ -1647,7 +1647,7 @@ Pixhawk3DWidget::updateTarget(double robotX, double robotY, double robotZ) sd->setColor(osg::Vec4f(1.0f, 0.8f, 0.0f, 1.0f)); } -#ifdef QGC_PROTOBUF_ENABLED +#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) void Pixhawk3DWidget::updateRGBD(double robotX, double robotY, double robotZ) { diff --git a/src/ui/map3D/Pixhawk3DWidget.h b/src/ui/map3D/Pixhawk3DWidget.h index 60537da14cd1354cd6e8fcb57812530b3c5e43d8..97aac4e1389d56d70c4092046a2c67cf5fd8287f 100644 --- a/src/ui/map3D/Pixhawk3DWidget.h +++ b/src/ui/map3D/Pixhawk3DWidget.h @@ -38,7 +38,7 @@ #include "Imagery.h" #include "ImageWindowGeode.h" #include "WaypointGroupNode.h" -#ifdef QGC_PROTOBUF_ENABLED +#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) #include "ObstacleGroupNode.h" #endif @@ -127,7 +127,7 @@ private: const QString& zone); void updateWaypoints(void); void updateTarget(double robotX, double robotY, double robotZ); -#ifdef QGC_PROTOBUF_ENABLED +#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) void updateRGBD(double robotX, double robotY, double robotZ); void updateObstacles(double robotX, double robotY, double robotZ); void updatePath(double robotX, double robotY, double robotZ); @@ -182,7 +182,7 @@ private: osg::ref_ptr waypointGroupNode; osg::ref_ptr targetNode; osg::ref_ptr rgbd3DNode; -#ifdef QGC_PROTOBUF_ENABLED +#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) osg::ref_ptr obstacleGroupNode; osg::ref_ptr pathNode; #endif diff --git a/thirdParty/mavlink/README b/thirdParty/mavlink/README index 513d5c77f7116429ed650d349f1ec155cf16ddac..f91c58c0308ee10feef47e239cfd000a72cdbc74 100644 --- a/thirdParty/mavlink/README +++ b/thirdParty/mavlink/README @@ -25,5 +25,4 @@ For more information, please visit: http://qgroundcontrol.org/mavlink/ -(c) 2009-2011 Lorenz Meier - +(c) 2009-2012 Lorenz Meier \ No newline at end of file diff --git a/thirdParty/mavlink/generate.sh b/thirdParty/mavlink/generate.sh new file mode 100755 index 0000000000000000000000000000000000000000..092a7fc199cdd6397c2dda6824264f35ebc70ab5 --- /dev/null +++ b/thirdParty/mavlink/generate.sh @@ -0,0 +1,24 @@ +#!/bin/bash +# this script generates all the include files with pymavlink + +# settings +wireProtocol=1.0 +pymavlinkTag=51f3d6713e9a5b94c232ab9bf9d08095a0c97866 + +# download pymavlink +topDir=$PWD +rm -rf include +rm -rf pymavlink +git clone https://github.com/mavlink/pymavlink.git -b master pymavlink +cd pymavlink && git checkout $pymavlinkTag && rm -rf .git + +# generate includes using message definitions +cd $topDir +for file in $(find message_definitions -name "*.xml") +do + echo generating mavlink includes for definition: $file + ./pymavlink/generator/mavgen.py --lang=C --wire-protocol=$wireProtocol --output=include $file +done + +# cleanup +rm -rf pymavlink diff --git a/thirdParty/mavlink/include/ardupilotmega/version.h b/thirdParty/mavlink/include/ardupilotmega/version.h index d30cd335eca1c3ca6bbb6ab9d0fd72d2f3af0be4..a9d2465fa742533b5ab12c5a53fb070dc2730bba 100644 --- a/thirdParty/mavlink/include/ardupilotmega/version.h +++ b/thirdParty/mavlink/include/ardupilotmega/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Tue Jan 10 11:49:24 2012" +#define MAVLINK_BUILD_DATE "Thu Feb 9 16:35:34 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/thirdParty/mavlink/include/common/version.h b/thirdParty/mavlink/include/common/version.h index 22bd0615ef96ae6e42f59ff26524ac34db961ec5..62a33f085508517450415a95152505f3d47fe2d5 100644 --- a/thirdParty/mavlink/include/common/version.h +++ b/thirdParty/mavlink/include/common/version.h @@ -5,8 +5,8 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Wed Jan 11 14:50:35 2012" +#define MAVLINK_BUILD_DATE "Thu Feb 9 16:35:38 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" -#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 +#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 #endif // MAVLINK_VERSION_H diff --git a/thirdParty/mavlink/include/minimal/version.h b/thirdParty/mavlink/include/minimal/version.h index 42422df4e81f9e17d93ad3705fad543808143d3f..366fcc1eb69b90138e6d74246b8a7012f18b5711 100644 --- a/thirdParty/mavlink/include/minimal/version.h +++ b/thirdParty/mavlink/include/minimal/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Tue Jan 10 11:49:37 2012" +#define MAVLINK_BUILD_DATE "Thu Feb 9 16:35:36 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 9 diff --git a/thirdParty/mavlink/include/pixhawk/pixhawk.pb.h b/thirdParty/mavlink/include/pixhawk/pixhawk.pb.h index 9244a7318ac9dc5425addaec10105aceef8076f7..63279d3bb123b1e808b9a3636e662728c4b27555 100644 --- a/thirdParty/mavlink/include/pixhawk/pixhawk.pb.h +++ b/thirdParty/mavlink/include/pixhawk/pixhawk.pb.h @@ -32,6 +32,7 @@ void protobuf_AddDesc_pixhawk_2eproto(); void protobuf_AssignDesc_pixhawk_2eproto(); void protobuf_ShutdownFile_pixhawk_2eproto(); +class HeaderInfo; class PointCloudXYZI; class PointCloudXYZI_PointXYZI; class PointCloudXYZRGB; @@ -40,9 +41,113 @@ class RGBDImage; class Obstacle; class ObstacleList; class ObstacleMap; +class Waypoint; +class Path; // =================================================================== +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 PointCloudXYZI_PointXYZI : public ::google::protobuf::Message { public: PointCloudXYZI_PointXYZI(); @@ -211,10 +316,18 @@ class PointCloudXYZI : public ::google::protobuf::Message { // accessors ------------------------------------------------------- - // repeated .px.PointCloudXYZI.PointXYZI points = 1; + // 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 = 1; + 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(); @@ -225,13 +338,16 @@ class PointCloudXYZI : public ::google::protobuf::Message { // @@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_[(1 + 31) / 32]; + ::google::protobuf::uint32 _has_bits_[(2 + 31) / 32]; friend void protobuf_AddDesc_pixhawk_2eproto(); friend void protobuf_AssignDesc_pixhawk_2eproto(); @@ -410,10 +526,18 @@ class PointCloudXYZRGB : public ::google::protobuf::Message { // accessors ------------------------------------------------------- - // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 1; + // 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 = 1; + 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(); @@ -424,13 +548,16 @@ class PointCloudXYZRGB : public ::google::protobuf::Message { // @@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_[(1 + 31) / 32]; + ::google::protobuf::uint32 _has_bits_[(2 + 31) / 32]; friend void protobuf_AddDesc_pixhawk_2eproto(); friend void protobuf_AssignDesc_pixhawk_2eproto(); @@ -495,38 +622,46 @@ class RGBDImage : public ::google::protobuf::Message { // accessors ------------------------------------------------------- - // required uint32 cols = 1; + // 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 = 1; + static const int kColsFieldNumber = 2; inline ::google::protobuf::uint32 cols() const; inline void set_cols(::google::protobuf::uint32 value); - // required uint32 rows = 2; + // required uint32 rows = 3; inline bool has_rows() const; inline void clear_rows(); - static const int kRowsFieldNumber = 2; + static const int kRowsFieldNumber = 3; inline ::google::protobuf::uint32 rows() const; inline void set_rows(::google::protobuf::uint32 value); - // required uint32 step1 = 3; + // required uint32 step1 = 4; inline bool has_step1() const; inline void clear_step1(); - static const int kStep1FieldNumber = 3; + static const int kStep1FieldNumber = 4; inline ::google::protobuf::uint32 step1() const; inline void set_step1(::google::protobuf::uint32 value); - // required uint32 type1 = 4; + // required uint32 type1 = 5; inline bool has_type1() const; inline void clear_type1(); - static const int kType1FieldNumber = 4; + static const int kType1FieldNumber = 5; inline ::google::protobuf::uint32 type1() const; inline void set_type1(::google::protobuf::uint32 value); - // required bytes imageData1 = 5; + // required bytes imageData1 = 6; inline bool has_imagedata1() const; inline void clear_imagedata1(); - static const int kImageData1FieldNumber = 5; + 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); @@ -534,24 +669,24 @@ class RGBDImage : public ::google::protobuf::Message { inline ::std::string* mutable_imagedata1(); inline ::std::string* release_imagedata1(); - // required uint32 step2 = 6; + // required uint32 step2 = 7; inline bool has_step2() const; inline void clear_step2(); - static const int kStep2FieldNumber = 6; + static const int kStep2FieldNumber = 7; inline ::google::protobuf::uint32 step2() const; inline void set_step2(::google::protobuf::uint32 value); - // required uint32 type2 = 7; + // required uint32 type2 = 8; inline bool has_type2() const; inline void clear_type2(); - static const int kType2FieldNumber = 7; + static const int kType2FieldNumber = 8; inline ::google::protobuf::uint32 type2() const; inline void set_type2(::google::protobuf::uint32 value); - // required bytes imageData2 = 8; + // required bytes imageData2 = 9; inline bool has_imagedata2() const; inline void clear_imagedata2(); - static const int kImageData2FieldNumber = 8; + 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); @@ -559,27 +694,20 @@ class RGBDImage : public ::google::protobuf::Message { inline ::std::string* mutable_imagedata2(); inline ::std::string* release_imagedata2(); - // optional uint32 camera_config = 9; + // optional uint32 camera_config = 10; inline bool has_camera_config() const; inline void clear_camera_config(); - static const int kCameraConfigFieldNumber = 9; + 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 = 10; + // optional uint32 camera_type = 11; inline bool has_camera_type() const; inline void clear_camera_type(); - static const int kCameraTypeFieldNumber = 10; + static const int kCameraTypeFieldNumber = 11; inline ::google::protobuf::uint32 camera_type() const; inline void set_camera_type(::google::protobuf::uint32 value); - // optional uint64 timestamp = 11; - inline bool has_timestamp() const; - inline void clear_timestamp(); - static const int kTimestampFieldNumber = 11; - inline ::google::protobuf::uint64 timestamp() const; - inline void set_timestamp(::google::protobuf::uint64 value); - // optional float roll = 12; inline bool has_roll() const; inline void clear_roll(); @@ -657,6 +785,8 @@ class RGBDImage : public ::google::protobuf::Message { // @@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(); @@ -677,8 +807,6 @@ class RGBDImage : public ::google::protobuf::Message { inline void clear_has_camera_config(); inline void set_has_camera_type(); inline void clear_has_camera_type(); - inline void set_has_timestamp(); - inline void clear_has_timestamp(); inline void set_has_roll(); inline void clear_has_roll(); inline void set_has_pitch(); @@ -700,6 +828,7 @@ class RGBDImage : public ::google::protobuf::Message { ::google::protobuf::UnknownFieldSet _unknown_fields_; + ::px::HeaderInfo* header_; ::google::protobuf::uint32 cols_; ::google::protobuf::uint32 rows_; ::google::protobuf::uint32 step1_; @@ -710,7 +839,6 @@ class RGBDImage : public ::google::protobuf::Message { ::std::string* imagedata2_; ::google::protobuf::uint32 camera_config_; ::google::protobuf::uint32 camera_type_; - ::google::protobuf::uint64 timestamp_; float roll_; float pitch_; float yaw_; @@ -920,12 +1048,13 @@ class ObstacleList : public ::google::protobuf::Message { // accessors ------------------------------------------------------- - // optional uint64 utime = 1; - inline bool has_utime() const; - inline void clear_utime(); - static const int kUtimeFieldNumber = 1; - inline ::google::protobuf::uint64 utime() const; - inline void set_utime(::google::protobuf::uint64 value); + // 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; @@ -941,12 +1070,12 @@ class ObstacleList : public ::google::protobuf::Message { // @@protoc_insertion_point(class_scope:px.ObstacleList) private: - inline void set_has_utime(); - inline void clear_has_utime(); + inline void set_has_header(); + inline void clear_has_header(); ::google::protobuf::UnknownFieldSet _unknown_fields_; - ::google::protobuf::uint64 utime_; + ::px::HeaderInfo* header_; ::google::protobuf::RepeatedPtrField< ::px::Obstacle > obstacles_; mutable int _cached_size_; @@ -1015,12 +1144,13 @@ class ObstacleMap : public ::google::protobuf::Message { // accessors ------------------------------------------------------- - // required uint64 utime = 1; - inline bool has_utime() const; - inline void clear_utime(); - static const int kUtimeFieldNumber = 1; - inline ::google::protobuf::uint64 utime() const; - inline void set_utime(::google::protobuf::uint64 value); + // 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; @@ -1091,8 +1221,8 @@ class ObstacleMap : public ::google::protobuf::Message { // @@protoc_insertion_point(class_scope:px.ObstacleMap) private: - inline void set_has_utime(); - inline void clear_has_utime(); + 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(); @@ -1114,7 +1244,7 @@ class ObstacleMap : public ::google::protobuf::Message { ::google::protobuf::UnknownFieldSet _unknown_fields_; - ::google::protobuf::uint64 utime_; + ::px::HeaderInfo* header_; ::google::protobuf::int32 type_; float resolution_; ::google::protobuf::int32 rows_; @@ -1135,11 +1265,309 @@ class ObstacleMap : public ::google::protobuf::Message { void InitAsDefaultInstance(); static ObstacleMap* 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_; +}; +// ------------------------------------------------------------------- + +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_; +}; // =================================================================== // =================================================================== +// 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; +} + +// ------------------------------------------------------------------- + // PointCloudXYZI_PointXYZI // required float x = 1; @@ -1234,7 +1662,36 @@ inline void PointCloudXYZI_PointXYZI::set_intensity(float value) { // PointCloudXYZI -// repeated .px.PointCloudXYZI.PointXYZI points = 1; +// 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(); } @@ -1355,7 +1812,36 @@ inline void PointCloudXYZRGB_PointXYZRGB::set_rgb(float value) { // PointCloudXYZRGB -// repeated .px.PointCloudXYZRGB.PointXYZRGB points = 1; +// 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(); } @@ -1384,16 +1870,45 @@ PointCloudXYZRGB::mutable_points() { // RGBDImage -// required uint32 cols = 1; -inline bool RGBDImage::has_cols() const { +// required .px.HeaderInfo header = 1; +inline bool RGBDImage::has_header() const { return (_has_bits_[0] & 0x00000001u) != 0; } -inline void RGBDImage::set_has_cols() { +inline void RGBDImage::set_has_header() { _has_bits_[0] |= 0x00000001u; } -inline void RGBDImage::clear_has_cols() { +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(); @@ -1406,15 +1921,15 @@ inline void RGBDImage::set_cols(::google::protobuf::uint32 value) { cols_ = value; } -// required uint32 rows = 2; +// required uint32 rows = 3; inline bool RGBDImage::has_rows() const { - return (_has_bits_[0] & 0x00000002u) != 0; + return (_has_bits_[0] & 0x00000004u) != 0; } inline void RGBDImage::set_has_rows() { - _has_bits_[0] |= 0x00000002u; + _has_bits_[0] |= 0x00000004u; } inline void RGBDImage::clear_has_rows() { - _has_bits_[0] &= ~0x00000002u; + _has_bits_[0] &= ~0x00000004u; } inline void RGBDImage::clear_rows() { rows_ = 0u; @@ -1428,15 +1943,15 @@ inline void RGBDImage::set_rows(::google::protobuf::uint32 value) { rows_ = value; } -// required uint32 step1 = 3; +// required uint32 step1 = 4; inline bool RGBDImage::has_step1() const { - return (_has_bits_[0] & 0x00000004u) != 0; + return (_has_bits_[0] & 0x00000008u) != 0; } inline void RGBDImage::set_has_step1() { - _has_bits_[0] |= 0x00000004u; + _has_bits_[0] |= 0x00000008u; } inline void RGBDImage::clear_has_step1() { - _has_bits_[0] &= ~0x00000004u; + _has_bits_[0] &= ~0x00000008u; } inline void RGBDImage::clear_step1() { step1_ = 0u; @@ -1450,15 +1965,15 @@ inline void RGBDImage::set_step1(::google::protobuf::uint32 value) { step1_ = value; } -// required uint32 type1 = 4; +// required uint32 type1 = 5; inline bool RGBDImage::has_type1() const { - return (_has_bits_[0] & 0x00000008u) != 0; + return (_has_bits_[0] & 0x00000010u) != 0; } inline void RGBDImage::set_has_type1() { - _has_bits_[0] |= 0x00000008u; + _has_bits_[0] |= 0x00000010u; } inline void RGBDImage::clear_has_type1() { - _has_bits_[0] &= ~0x00000008u; + _has_bits_[0] &= ~0x00000010u; } inline void RGBDImage::clear_type1() { type1_ = 0u; @@ -1472,15 +1987,15 @@ inline void RGBDImage::set_type1(::google::protobuf::uint32 value) { type1_ = value; } -// required bytes imageData1 = 5; +// required bytes imageData1 = 6; inline bool RGBDImage::has_imagedata1() const { - return (_has_bits_[0] & 0x00000010u) != 0; + return (_has_bits_[0] & 0x00000020u) != 0; } inline void RGBDImage::set_has_imagedata1() { - _has_bits_[0] |= 0x00000010u; + _has_bits_[0] |= 0x00000020u; } inline void RGBDImage::clear_has_imagedata1() { - _has_bits_[0] &= ~0x00000010u; + _has_bits_[0] &= ~0x00000020u; } inline void RGBDImage::clear_imagedata1() { if (imagedata1_ != &::google::protobuf::internal::kEmptyString) { @@ -1530,15 +2045,15 @@ inline ::std::string* RGBDImage::release_imagedata1() { } } -// required uint32 step2 = 6; +// required uint32 step2 = 7; inline bool RGBDImage::has_step2() const { - return (_has_bits_[0] & 0x00000020u) != 0; + return (_has_bits_[0] & 0x00000040u) != 0; } inline void RGBDImage::set_has_step2() { - _has_bits_[0] |= 0x00000020u; + _has_bits_[0] |= 0x00000040u; } inline void RGBDImage::clear_has_step2() { - _has_bits_[0] &= ~0x00000020u; + _has_bits_[0] &= ~0x00000040u; } inline void RGBDImage::clear_step2() { step2_ = 0u; @@ -1552,15 +2067,15 @@ inline void RGBDImage::set_step2(::google::protobuf::uint32 value) { step2_ = value; } -// required uint32 type2 = 7; +// required uint32 type2 = 8; inline bool RGBDImage::has_type2() const { - return (_has_bits_[0] & 0x00000040u) != 0; + return (_has_bits_[0] & 0x00000080u) != 0; } inline void RGBDImage::set_has_type2() { - _has_bits_[0] |= 0x00000040u; + _has_bits_[0] |= 0x00000080u; } inline void RGBDImage::clear_has_type2() { - _has_bits_[0] &= ~0x00000040u; + _has_bits_[0] &= ~0x00000080u; } inline void RGBDImage::clear_type2() { type2_ = 0u; @@ -1574,15 +2089,15 @@ inline void RGBDImage::set_type2(::google::protobuf::uint32 value) { type2_ = value; } -// required bytes imageData2 = 8; +// required bytes imageData2 = 9; inline bool RGBDImage::has_imagedata2() const { - return (_has_bits_[0] & 0x00000080u) != 0; + return (_has_bits_[0] & 0x00000100u) != 0; } inline void RGBDImage::set_has_imagedata2() { - _has_bits_[0] |= 0x00000080u; + _has_bits_[0] |= 0x00000100u; } inline void RGBDImage::clear_has_imagedata2() { - _has_bits_[0] &= ~0x00000080u; + _has_bits_[0] &= ~0x00000100u; } inline void RGBDImage::clear_imagedata2() { if (imagedata2_ != &::google::protobuf::internal::kEmptyString) { @@ -1632,15 +2147,15 @@ inline ::std::string* RGBDImage::release_imagedata2() { } } -// optional uint32 camera_config = 9; +// optional uint32 camera_config = 10; inline bool RGBDImage::has_camera_config() const { - return (_has_bits_[0] & 0x00000100u) != 0; + return (_has_bits_[0] & 0x00000200u) != 0; } inline void RGBDImage::set_has_camera_config() { - _has_bits_[0] |= 0x00000100u; + _has_bits_[0] |= 0x00000200u; } inline void RGBDImage::clear_has_camera_config() { - _has_bits_[0] &= ~0x00000100u; + _has_bits_[0] &= ~0x00000200u; } inline void RGBDImage::clear_camera_config() { camera_config_ = 0u; @@ -1654,15 +2169,15 @@ inline void RGBDImage::set_camera_config(::google::protobuf::uint32 value) { camera_config_ = value; } -// optional uint32 camera_type = 10; +// optional uint32 camera_type = 11; inline bool RGBDImage::has_camera_type() const { - return (_has_bits_[0] & 0x00000200u) != 0; + return (_has_bits_[0] & 0x00000400u) != 0; } inline void RGBDImage::set_has_camera_type() { - _has_bits_[0] |= 0x00000200u; + _has_bits_[0] |= 0x00000400u; } inline void RGBDImage::clear_has_camera_type() { - _has_bits_[0] &= ~0x00000200u; + _has_bits_[0] &= ~0x00000400u; } inline void RGBDImage::clear_camera_type() { camera_type_ = 0u; @@ -1676,28 +2191,6 @@ inline void RGBDImage::set_camera_type(::google::protobuf::uint32 value) { camera_type_ = value; } -// optional uint64 timestamp = 11; -inline bool RGBDImage::has_timestamp() const { - return (_has_bits_[0] & 0x00000400u) != 0; -} -inline void RGBDImage::set_has_timestamp() { - _has_bits_[0] |= 0x00000400u; -} -inline void RGBDImage::clear_has_timestamp() { - _has_bits_[0] &= ~0x00000400u; -} -inline void RGBDImage::clear_timestamp() { - timestamp_ = GOOGLE_ULONGLONG(0); - clear_has_timestamp(); -} -inline ::google::protobuf::uint64 RGBDImage::timestamp() const { - return timestamp_; -} -inline void RGBDImage::set_timestamp(::google::protobuf::uint64 value) { - set_has_timestamp(); - timestamp_ = value; -} - // optional float roll = 12; inline bool RGBDImage::has_roll() const { return (_has_bits_[0] & 0x00000800u) != 0; @@ -2061,26 +2554,33 @@ inline void Obstacle::set_height(float value) { // ObstacleList -// optional uint64 utime = 1; -inline bool ObstacleList::has_utime() const { +// required .px.HeaderInfo header = 1; +inline bool ObstacleList::has_header() const { return (_has_bits_[0] & 0x00000001u) != 0; } -inline void ObstacleList::set_has_utime() { +inline void ObstacleList::set_has_header() { _has_bits_[0] |= 0x00000001u; } -inline void ObstacleList::clear_has_utime() { +inline void ObstacleList::clear_has_header() { _has_bits_[0] &= ~0x00000001u; } -inline void ObstacleList::clear_utime() { - utime_ = GOOGLE_ULONGLONG(0); - clear_has_utime(); +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 ::google::protobuf::uint64 ObstacleList::utime() const { - return utime_; +inline ::px::HeaderInfo* ObstacleList::mutable_header() { + set_has_header(); + if (header_ == NULL) header_ = new ::px::HeaderInfo; + return header_; } -inline void ObstacleList::set_utime(::google::protobuf::uint64 value) { - set_has_utime(); - utime_ = value; +inline ::px::HeaderInfo* ObstacleList::release_header() { + clear_has_header(); + ::px::HeaderInfo* temp = header_; + header_ = NULL; + return temp; } // repeated .px.Obstacle obstacles = 2; @@ -2112,26 +2612,33 @@ ObstacleList::mutable_obstacles() { // ObstacleMap -// required uint64 utime = 1; -inline bool ObstacleMap::has_utime() const { +// required .px.HeaderInfo header = 1; +inline bool ObstacleMap::has_header() const { return (_has_bits_[0] & 0x00000001u) != 0; } -inline void ObstacleMap::set_has_utime() { +inline void ObstacleMap::set_has_header() { _has_bits_[0] |= 0x00000001u; } -inline void ObstacleMap::clear_has_utime() { +inline void ObstacleMap::clear_has_header() { _has_bits_[0] &= ~0x00000001u; } -inline void ObstacleMap::clear_utime() { - utime_ = GOOGLE_ULONGLONG(0); - clear_has_utime(); +inline void ObstacleMap::clear_header() { + if (header_ != NULL) header_->::px::HeaderInfo::Clear(); + clear_has_header(); } -inline ::google::protobuf::uint64 ObstacleMap::utime() const { - return utime_; +inline const ::px::HeaderInfo& ObstacleMap::header() const { + return header_ != NULL ? *header_ : *default_instance_->header_; } -inline void ObstacleMap::set_utime(::google::protobuf::uint64 value) { - set_has_utime(); - utime_ = value; +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; @@ -2368,6 +2875,200 @@ inline ::std::string* ObstacleMap::release_data() { } } +// ------------------------------------------------------------------- + +// 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; +} + +// ------------------------------------------------------------------- + +// 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_; +} + // @@protoc_insertion_point(namespace_scope) diff --git a/thirdParty/mavlink/include/pixhawk/version.h b/thirdParty/mavlink/include/pixhawk/version.h index bdbc30dd097be650dd6814e724d491b9e8cb392b..cb28e96c47767b8ef4fb56daccccfdfb5f837989 100644 --- a/thirdParty/mavlink/include/pixhawk/version.h +++ b/thirdParty/mavlink/include/pixhawk/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Tue Jan 10 12:52:11 2012" +#define MAVLINK_BUILD_DATE "Thu Feb 9 16:35:38 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 diff --git a/thirdParty/mavlink/include/sensesoar/mavlink.h b/thirdParty/mavlink/include/sensesoar/mavlink.h new file mode 100644 index 0000000000000000000000000000000000000000..c0a0a8967355ee30c7a39f82ae3f9f0250aaaa30 --- /dev/null +++ b/thirdParty/mavlink/include/sensesoar/mavlink.h @@ -0,0 +1,27 @@ +/** @file + * @brief MAVLink comm protocol built from sensesoar.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 "sensesoar.h" + +#endif // MAVLINK_H diff --git a/thirdParty/mavlink/include/sensesoar/mavlink_msg_cmd_airspeed_ack.h b/thirdParty/mavlink/include/sensesoar/mavlink_msg_cmd_airspeed_ack.h new file mode 100644 index 0000000000000000000000000000000000000000..6dcab9fa822edaa7cc888cf0e53ab7783340e72e --- /dev/null +++ b/thirdParty/mavlink/include/sensesoar/mavlink_msg_cmd_airspeed_ack.h @@ -0,0 +1,166 @@ +// MESSAGE CMD_AIRSPEED_ACK PACKING + +#define MAVLINK_MSG_ID_CMD_AIRSPEED_ACK 194 + +typedef struct __mavlink_cmd_airspeed_ack_t +{ + float spCmd; ///< commanded airspeed + uint8_t ack; ///< 0:ack, 1:nack +} mavlink_cmd_airspeed_ack_t; + +#define MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN 5 +#define MAVLINK_MSG_ID_194_LEN 5 + + + +#define MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_ACK { \ + "CMD_AIRSPEED_ACK", \ + 2, \ + { { "spCmd", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_cmd_airspeed_ack_t, spCmd) }, \ + { "ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_cmd_airspeed_ack_t, ack) }, \ + } \ +} + + +/** + * @brief Pack a cmd_airspeed_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 spCmd commanded airspeed + * @param ack 0:ack, 1:nack + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_cmd_airspeed_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float spCmd, uint8_t ack) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[5]; + _mav_put_float(buf, 0, spCmd); + _mav_put_uint8_t(buf, 4, ack); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5); +#else + mavlink_cmd_airspeed_ack_t packet; + packet.spCmd = spCmd; + packet.ack = ack; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5); +#endif + + msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_ACK; + return mavlink_finalize_message(msg, system_id, component_id, 5, 243); +} + +/** + * @brief Pack a cmd_airspeed_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 spCmd commanded airspeed + * @param ack 0:ack, 1:nack + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_cmd_airspeed_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float spCmd,uint8_t ack) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[5]; + _mav_put_float(buf, 0, spCmd); + _mav_put_uint8_t(buf, 4, ack); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5); +#else + mavlink_cmd_airspeed_ack_t packet; + packet.spCmd = spCmd; + packet.ack = ack; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5); +#endif + + msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_ACK; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 5, 243); +} + +/** + * @brief Encode a cmd_airspeed_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 cmd_airspeed_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_cmd_airspeed_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cmd_airspeed_ack_t* cmd_airspeed_ack) +{ + return mavlink_msg_cmd_airspeed_ack_pack(system_id, component_id, msg, cmd_airspeed_ack->spCmd, cmd_airspeed_ack->ack); +} + +/** + * @brief Send a cmd_airspeed_ack message + * @param chan MAVLink channel to send the message + * + * @param spCmd commanded airspeed + * @param ack 0:ack, 1:nack + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_cmd_airspeed_ack_send(mavlink_channel_t chan, float spCmd, uint8_t ack) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[5]; + _mav_put_float(buf, 0, spCmd); + _mav_put_uint8_t(buf, 4, ack); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, buf, 5, 243); +#else + mavlink_cmd_airspeed_ack_t packet; + packet.spCmd = spCmd; + packet.ack = ack; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, (const char *)&packet, 5, 243); +#endif +} + +#endif + +// MESSAGE CMD_AIRSPEED_ACK UNPACKING + + +/** + * @brief Get field spCmd from cmd_airspeed_ack message + * + * @return commanded airspeed + */ +static inline float mavlink_msg_cmd_airspeed_ack_get_spCmd(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field ack from cmd_airspeed_ack message + * + * @return 0:ack, 1:nack + */ +static inline uint8_t mavlink_msg_cmd_airspeed_ack_get_ack(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Decode a cmd_airspeed_ack message into a struct + * + * @param msg The message to decode + * @param cmd_airspeed_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_cmd_airspeed_ack_decode(const mavlink_message_t* msg, mavlink_cmd_airspeed_ack_t* cmd_airspeed_ack) +{ +#if MAVLINK_NEED_BYTE_SWAP + cmd_airspeed_ack->spCmd = mavlink_msg_cmd_airspeed_ack_get_spCmd(msg); + cmd_airspeed_ack->ack = mavlink_msg_cmd_airspeed_ack_get_ack(msg); +#else + memcpy(cmd_airspeed_ack, _MAV_PAYLOAD(msg), 5); +#endif +} diff --git a/thirdParty/mavlink/include/sensesoar/mavlink_msg_cmd_airspeed_chng.h b/thirdParty/mavlink/include/sensesoar/mavlink_msg_cmd_airspeed_chng.h new file mode 100644 index 0000000000000000000000000000000000000000..d5b21b8d79b69be6622885d1f13f0339e33dfab2 --- /dev/null +++ b/thirdParty/mavlink/include/sensesoar/mavlink_msg_cmd_airspeed_chng.h @@ -0,0 +1,166 @@ +// MESSAGE CMD_AIRSPEED_CHNG PACKING + +#define MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG 192 + +typedef struct __mavlink_cmd_airspeed_chng_t +{ + float spCmd; ///< commanded airspeed + uint8_t target; ///< Target ID +} mavlink_cmd_airspeed_chng_t; + +#define MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN 5 +#define MAVLINK_MSG_ID_192_LEN 5 + + + +#define MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_CHNG { \ + "CMD_AIRSPEED_CHNG", \ + 2, \ + { { "spCmd", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_cmd_airspeed_chng_t, spCmd) }, \ + { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_cmd_airspeed_chng_t, target) }, \ + } \ +} + + +/** + * @brief Pack a cmd_airspeed_chng 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 Target ID + * @param spCmd commanded airspeed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target, float spCmd) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[5]; + _mav_put_float(buf, 0, spCmd); + _mav_put_uint8_t(buf, 4, target); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5); +#else + mavlink_cmd_airspeed_chng_t packet; + packet.spCmd = spCmd; + packet.target = target; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5); +#endif + + msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG; + return mavlink_finalize_message(msg, system_id, component_id, 5, 209); +} + +/** + * @brief Pack a cmd_airspeed_chng 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 Target ID + * @param spCmd commanded airspeed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target,float spCmd) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[5]; + _mav_put_float(buf, 0, spCmd); + _mav_put_uint8_t(buf, 4, target); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5); +#else + mavlink_cmd_airspeed_chng_t packet; + packet.spCmd = spCmd; + packet.target = target; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5); +#endif + + msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 5, 209); +} + +/** + * @brief Encode a cmd_airspeed_chng 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 cmd_airspeed_chng C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_cmd_airspeed_chng_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cmd_airspeed_chng_t* cmd_airspeed_chng) +{ + return mavlink_msg_cmd_airspeed_chng_pack(system_id, component_id, msg, cmd_airspeed_chng->target, cmd_airspeed_chng->spCmd); +} + +/** + * @brief Send a cmd_airspeed_chng message + * @param chan MAVLink channel to send the message + * + * @param target Target ID + * @param spCmd commanded airspeed + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_cmd_airspeed_chng_send(mavlink_channel_t chan, uint8_t target, float spCmd) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[5]; + _mav_put_float(buf, 0, spCmd); + _mav_put_uint8_t(buf, 4, target); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, buf, 5, 209); +#else + mavlink_cmd_airspeed_chng_t packet; + packet.spCmd = spCmd; + packet.target = target; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, (const char *)&packet, 5, 209); +#endif +} + +#endif + +// MESSAGE CMD_AIRSPEED_CHNG UNPACKING + + +/** + * @brief Get field target from cmd_airspeed_chng message + * + * @return Target ID + */ +static inline uint8_t mavlink_msg_cmd_airspeed_chng_get_target(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field spCmd from cmd_airspeed_chng message + * + * @return commanded airspeed + */ +static inline float mavlink_msg_cmd_airspeed_chng_get_spCmd(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Decode a cmd_airspeed_chng message into a struct + * + * @param msg The message to decode + * @param cmd_airspeed_chng C-struct to decode the message contents into + */ +static inline void mavlink_msg_cmd_airspeed_chng_decode(const mavlink_message_t* msg, mavlink_cmd_airspeed_chng_t* cmd_airspeed_chng) +{ +#if MAVLINK_NEED_BYTE_SWAP + cmd_airspeed_chng->spCmd = mavlink_msg_cmd_airspeed_chng_get_spCmd(msg); + cmd_airspeed_chng->target = mavlink_msg_cmd_airspeed_chng_get_target(msg); +#else + memcpy(cmd_airspeed_chng, _MAV_PAYLOAD(msg), 5); +#endif +} diff --git a/thirdParty/mavlink/include/sensesoar/mavlink_msg_filt_rot_vel.h b/thirdParty/mavlink/include/sensesoar/mavlink_msg_filt_rot_vel.h new file mode 100644 index 0000000000000000000000000000000000000000..f5fef06f0438cfe04423ee101aa7b5920f440211 --- /dev/null +++ b/thirdParty/mavlink/include/sensesoar/mavlink_msg_filt_rot_vel.h @@ -0,0 +1,144 @@ +// MESSAGE FILT_ROT_VEL PACKING + +#define MAVLINK_MSG_ID_FILT_ROT_VEL 184 + +typedef struct __mavlink_filt_rot_vel_t +{ + float rotVel[3]; ///< rotational velocity +} mavlink_filt_rot_vel_t; + +#define MAVLINK_MSG_ID_FILT_ROT_VEL_LEN 12 +#define MAVLINK_MSG_ID_184_LEN 12 + +#define MAVLINK_MSG_FILT_ROT_VEL_FIELD_ROTVEL_LEN 3 + +#define MAVLINK_MESSAGE_INFO_FILT_ROT_VEL { \ + "FILT_ROT_VEL", \ + 1, \ + { { "rotVel", NULL, MAVLINK_TYPE_FLOAT, 3, 0, offsetof(mavlink_filt_rot_vel_t, rotVel) }, \ + } \ +} + + +/** + * @brief Pack a filt_rot_vel 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 rotVel rotational velocity + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_filt_rot_vel_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const float *rotVel) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + + _mav_put_float_array(buf, 0, rotVel, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_filt_rot_vel_t packet; + + mav_array_memcpy(packet.rotVel, rotVel, sizeof(float)*3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_FILT_ROT_VEL; + return mavlink_finalize_message(msg, system_id, component_id, 12, 79); +} + +/** + * @brief Pack a filt_rot_vel 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 rotVel rotational velocity + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_filt_rot_vel_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const float *rotVel) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + + _mav_put_float_array(buf, 0, rotVel, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_filt_rot_vel_t packet; + + mav_array_memcpy(packet.rotVel, rotVel, sizeof(float)*3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_FILT_ROT_VEL; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 79); +} + +/** + * @brief Encode a filt_rot_vel 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 filt_rot_vel C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_filt_rot_vel_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_filt_rot_vel_t* filt_rot_vel) +{ + return mavlink_msg_filt_rot_vel_pack(system_id, component_id, msg, filt_rot_vel->rotVel); +} + +/** + * @brief Send a filt_rot_vel message + * @param chan MAVLink channel to send the message + * + * @param rotVel rotational velocity + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_filt_rot_vel_send(mavlink_channel_t chan, const float *rotVel) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + + _mav_put_float_array(buf, 0, rotVel, 3); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, buf, 12, 79); +#else + mavlink_filt_rot_vel_t packet; + + mav_array_memcpy(packet.rotVel, rotVel, sizeof(float)*3); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, (const char *)&packet, 12, 79); +#endif +} + +#endif + +// MESSAGE FILT_ROT_VEL UNPACKING + + +/** + * @brief Get field rotVel from filt_rot_vel message + * + * @return rotational velocity + */ +static inline uint16_t mavlink_msg_filt_rot_vel_get_rotVel(const mavlink_message_t* msg, float *rotVel) +{ + return _MAV_RETURN_float_array(msg, rotVel, 3, 0); +} + +/** + * @brief Decode a filt_rot_vel message into a struct + * + * @param msg The message to decode + * @param filt_rot_vel C-struct to decode the message contents into + */ +static inline void mavlink_msg_filt_rot_vel_decode(const mavlink_message_t* msg, mavlink_filt_rot_vel_t* filt_rot_vel) +{ +#if MAVLINK_NEED_BYTE_SWAP + mavlink_msg_filt_rot_vel_get_rotVel(msg, filt_rot_vel->rotVel); +#else + memcpy(filt_rot_vel, _MAV_PAYLOAD(msg), 12); +#endif +} diff --git a/thirdParty/mavlink/include/sensesoar/mavlink_msg_llc_out.h b/thirdParty/mavlink/include/sensesoar/mavlink_msg_llc_out.h new file mode 100644 index 0000000000000000000000000000000000000000..5ee3d5a19f2a92da8fcbfbefbf65fcdcbeb3c01c --- /dev/null +++ b/thirdParty/mavlink/include/sensesoar/mavlink_msg_llc_out.h @@ -0,0 +1,167 @@ +// MESSAGE LLC_OUT PACKING + +#define MAVLINK_MSG_ID_LLC_OUT 186 + +typedef struct __mavlink_llc_out_t +{ + int16_t servoOut[4]; ///< Servo signal + int16_t MotorOut[2]; ///< motor signal +} mavlink_llc_out_t; + +#define MAVLINK_MSG_ID_LLC_OUT_LEN 12 +#define MAVLINK_MSG_ID_186_LEN 12 + +#define MAVLINK_MSG_LLC_OUT_FIELD_SERVOOUT_LEN 4 +#define MAVLINK_MSG_LLC_OUT_FIELD_MOTOROUT_LEN 2 + +#define MAVLINK_MESSAGE_INFO_LLC_OUT { \ + "LLC_OUT", \ + 2, \ + { { "servoOut", NULL, MAVLINK_TYPE_INT16_T, 4, 0, offsetof(mavlink_llc_out_t, servoOut) }, \ + { "MotorOut", NULL, MAVLINK_TYPE_INT16_T, 2, 8, offsetof(mavlink_llc_out_t, MotorOut) }, \ + } \ +} + + +/** + * @brief Pack a llc_out 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 servoOut Servo signal + * @param MotorOut motor signal + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_llc_out_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const int16_t *servoOut, const int16_t *MotorOut) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + + _mav_put_int16_t_array(buf, 0, servoOut, 4); + _mav_put_int16_t_array(buf, 8, MotorOut, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_llc_out_t packet; + + mav_array_memcpy(packet.servoOut, servoOut, sizeof(int16_t)*4); + mav_array_memcpy(packet.MotorOut, MotorOut, sizeof(int16_t)*2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_LLC_OUT; + return mavlink_finalize_message(msg, system_id, component_id, 12, 5); +} + +/** + * @brief Pack a llc_out 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 servoOut Servo signal + * @param MotorOut motor signal + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_llc_out_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const int16_t *servoOut,const int16_t *MotorOut) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + + _mav_put_int16_t_array(buf, 0, servoOut, 4); + _mav_put_int16_t_array(buf, 8, MotorOut, 2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_llc_out_t packet; + + mav_array_memcpy(packet.servoOut, servoOut, sizeof(int16_t)*4); + mav_array_memcpy(packet.MotorOut, MotorOut, sizeof(int16_t)*2); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_LLC_OUT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 5); +} + +/** + * @brief Encode a llc_out 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 llc_out C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_llc_out_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_llc_out_t* llc_out) +{ + return mavlink_msg_llc_out_pack(system_id, component_id, msg, llc_out->servoOut, llc_out->MotorOut); +} + +/** + * @brief Send a llc_out message + * @param chan MAVLink channel to send the message + * + * @param servoOut Servo signal + * @param MotorOut motor signal + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_llc_out_send(mavlink_channel_t chan, const int16_t *servoOut, const int16_t *MotorOut) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + + _mav_put_int16_t_array(buf, 0, servoOut, 4); + _mav_put_int16_t_array(buf, 8, MotorOut, 2); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, buf, 12, 5); +#else + mavlink_llc_out_t packet; + + mav_array_memcpy(packet.servoOut, servoOut, sizeof(int16_t)*4); + mav_array_memcpy(packet.MotorOut, MotorOut, sizeof(int16_t)*2); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, (const char *)&packet, 12, 5); +#endif +} + +#endif + +// MESSAGE LLC_OUT UNPACKING + + +/** + * @brief Get field servoOut from llc_out message + * + * @return Servo signal + */ +static inline uint16_t mavlink_msg_llc_out_get_servoOut(const mavlink_message_t* msg, int16_t *servoOut) +{ + return _MAV_RETURN_int16_t_array(msg, servoOut, 4, 0); +} + +/** + * @brief Get field MotorOut from llc_out message + * + * @return motor signal + */ +static inline uint16_t mavlink_msg_llc_out_get_MotorOut(const mavlink_message_t* msg, int16_t *MotorOut) +{ + return _MAV_RETURN_int16_t_array(msg, MotorOut, 2, 8); +} + +/** + * @brief Decode a llc_out message into a struct + * + * @param msg The message to decode + * @param llc_out C-struct to decode the message contents into + */ +static inline void mavlink_msg_llc_out_decode(const mavlink_message_t* msg, mavlink_llc_out_t* llc_out) +{ +#if MAVLINK_NEED_BYTE_SWAP + mavlink_msg_llc_out_get_servoOut(msg, llc_out->servoOut); + mavlink_msg_llc_out_get_MotorOut(msg, llc_out->MotorOut); +#else + memcpy(llc_out, _MAV_PAYLOAD(msg), 12); +#endif +} diff --git a/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_air_temp.h b/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_air_temp.h new file mode 100644 index 0000000000000000000000000000000000000000..60cf01845470911949dc7f48c0c895221dbcbdeb --- /dev/null +++ b/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_air_temp.h @@ -0,0 +1,144 @@ +// MESSAGE OBS_AIR_TEMP PACKING + +#define MAVLINK_MSG_ID_OBS_AIR_TEMP 183 + +typedef struct __mavlink_obs_air_temp_t +{ + float airT; ///< Air Temperatur +} mavlink_obs_air_temp_t; + +#define MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN 4 +#define MAVLINK_MSG_ID_183_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_OBS_AIR_TEMP { \ + "OBS_AIR_TEMP", \ + 1, \ + { { "airT", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_obs_air_temp_t, airT) }, \ + } \ +} + + +/** + * @brief Pack a obs_air_temp 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 airT Air Temperatur + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_obs_air_temp_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float airT) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_float(buf, 0, airT); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); +#else + mavlink_obs_air_temp_t packet; + packet.airT = airT; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_OBS_AIR_TEMP; + return mavlink_finalize_message(msg, system_id, component_id, 4, 248); +} + +/** + * @brief Pack a obs_air_temp 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 airT Air Temperatur + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_obs_air_temp_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float airT) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_float(buf, 0, airT); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); +#else + mavlink_obs_air_temp_t packet; + packet.airT = airT; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_OBS_AIR_TEMP; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 248); +} + +/** + * @brief Encode a obs_air_temp 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 obs_air_temp C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_obs_air_temp_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_air_temp_t* obs_air_temp) +{ + return mavlink_msg_obs_air_temp_pack(system_id, component_id, msg, obs_air_temp->airT); +} + +/** + * @brief Send a obs_air_temp message + * @param chan MAVLink channel to send the message + * + * @param airT Air Temperatur + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_obs_air_temp_send(mavlink_channel_t chan, float airT) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_float(buf, 0, airT); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, buf, 4, 248); +#else + mavlink_obs_air_temp_t packet; + packet.airT = airT; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, (const char *)&packet, 4, 248); +#endif +} + +#endif + +// MESSAGE OBS_AIR_TEMP UNPACKING + + +/** + * @brief Get field airT from obs_air_temp message + * + * @return Air Temperatur + */ +static inline float mavlink_msg_obs_air_temp_get_airT(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Decode a obs_air_temp message into a struct + * + * @param msg The message to decode + * @param obs_air_temp C-struct to decode the message contents into + */ +static inline void mavlink_msg_obs_air_temp_decode(const mavlink_message_t* msg, mavlink_obs_air_temp_t* obs_air_temp) +{ +#if MAVLINK_NEED_BYTE_SWAP + obs_air_temp->airT = mavlink_msg_obs_air_temp_get_airT(msg); +#else + memcpy(obs_air_temp, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_air_velocity.h b/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_air_velocity.h new file mode 100644 index 0000000000000000000000000000000000000000..ef56c5c61780e00ac1fa32d3e57aadf0f4de4516 --- /dev/null +++ b/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_air_velocity.h @@ -0,0 +1,188 @@ +// MESSAGE OBS_AIR_VELOCITY PACKING + +#define MAVLINK_MSG_ID_OBS_AIR_VELOCITY 178 + +typedef struct __mavlink_obs_air_velocity_t +{ + float magnitude; ///< Air speed + float aoa; ///< angle of attack + float slip; ///< slip angle +} mavlink_obs_air_velocity_t; + +#define MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN 12 +#define MAVLINK_MSG_ID_178_LEN 12 + + + +#define MAVLINK_MESSAGE_INFO_OBS_AIR_VELOCITY { \ + "OBS_AIR_VELOCITY", \ + 3, \ + { { "magnitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_obs_air_velocity_t, magnitude) }, \ + { "aoa", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_obs_air_velocity_t, aoa) }, \ + { "slip", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_obs_air_velocity_t, slip) }, \ + } \ +} + + +/** + * @brief Pack a obs_air_velocity 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 magnitude Air speed + * @param aoa angle of attack + * @param slip slip angle + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_obs_air_velocity_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float magnitude, float aoa, float slip) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_float(buf, 0, magnitude); + _mav_put_float(buf, 4, aoa); + _mav_put_float(buf, 8, slip); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_obs_air_velocity_t packet; + packet.magnitude = magnitude; + packet.aoa = aoa; + packet.slip = slip; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_OBS_AIR_VELOCITY; + return mavlink_finalize_message(msg, system_id, component_id, 12, 32); +} + +/** + * @brief Pack a obs_air_velocity 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 magnitude Air speed + * @param aoa angle of attack + * @param slip slip angle + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_obs_air_velocity_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float magnitude,float aoa,float slip) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_float(buf, 0, magnitude); + _mav_put_float(buf, 4, aoa); + _mav_put_float(buf, 8, slip); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_obs_air_velocity_t packet; + packet.magnitude = magnitude; + packet.aoa = aoa; + packet.slip = slip; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_OBS_AIR_VELOCITY; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 32); +} + +/** + * @brief Encode a obs_air_velocity 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 obs_air_velocity C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_obs_air_velocity_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_air_velocity_t* obs_air_velocity) +{ + return mavlink_msg_obs_air_velocity_pack(system_id, component_id, msg, obs_air_velocity->magnitude, obs_air_velocity->aoa, obs_air_velocity->slip); +} + +/** + * @brief Send a obs_air_velocity message + * @param chan MAVLink channel to send the message + * + * @param magnitude Air speed + * @param aoa angle of attack + * @param slip slip angle + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_obs_air_velocity_send(mavlink_channel_t chan, float magnitude, float aoa, float slip) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_float(buf, 0, magnitude); + _mav_put_float(buf, 4, aoa); + _mav_put_float(buf, 8, slip); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, buf, 12, 32); +#else + mavlink_obs_air_velocity_t packet; + packet.magnitude = magnitude; + packet.aoa = aoa; + packet.slip = slip; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, (const char *)&packet, 12, 32); +#endif +} + +#endif + +// MESSAGE OBS_AIR_VELOCITY UNPACKING + + +/** + * @brief Get field magnitude from obs_air_velocity message + * + * @return Air speed + */ +static inline float mavlink_msg_obs_air_velocity_get_magnitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field aoa from obs_air_velocity message + * + * @return angle of attack + */ +static inline float mavlink_msg_obs_air_velocity_get_aoa(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field slip from obs_air_velocity message + * + * @return slip angle + */ +static inline float mavlink_msg_obs_air_velocity_get_slip(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Decode a obs_air_velocity message into a struct + * + * @param msg The message to decode + * @param obs_air_velocity C-struct to decode the message contents into + */ +static inline void mavlink_msg_obs_air_velocity_decode(const mavlink_message_t* msg, mavlink_obs_air_velocity_t* obs_air_velocity) +{ +#if MAVLINK_NEED_BYTE_SWAP + obs_air_velocity->magnitude = mavlink_msg_obs_air_velocity_get_magnitude(msg); + obs_air_velocity->aoa = mavlink_msg_obs_air_velocity_get_aoa(msg); + obs_air_velocity->slip = mavlink_msg_obs_air_velocity_get_slip(msg); +#else + memcpy(obs_air_velocity, _MAV_PAYLOAD(msg), 12); +#endif +} diff --git a/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_attitude.h b/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_attitude.h new file mode 100644 index 0000000000000000000000000000000000000000..7a3e6d0ba48b16270acfe67d6091738bdcb078d8 --- /dev/null +++ b/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_attitude.h @@ -0,0 +1,144 @@ +// MESSAGE OBS_ATTITUDE PACKING + +#define MAVLINK_MSG_ID_OBS_ATTITUDE 174 + +typedef struct __mavlink_obs_attitude_t +{ + double quat[4]; ///< Quaternion re;im +} mavlink_obs_attitude_t; + +#define MAVLINK_MSG_ID_OBS_ATTITUDE_LEN 32 +#define MAVLINK_MSG_ID_174_LEN 32 + +#define MAVLINK_MSG_OBS_ATTITUDE_FIELD_QUAT_LEN 4 + +#define MAVLINK_MESSAGE_INFO_OBS_ATTITUDE { \ + "OBS_ATTITUDE", \ + 1, \ + { { "quat", NULL, MAVLINK_TYPE_DOUBLE, 4, 0, offsetof(mavlink_obs_attitude_t, quat) }, \ + } \ +} + + +/** + * @brief Pack a obs_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 quat Quaternion re;im + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_obs_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const double *quat) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + + _mav_put_double_array(buf, 0, quat, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); +#else + mavlink_obs_attitude_t packet; + + mav_array_memcpy(packet.quat, quat, sizeof(double)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_OBS_ATTITUDE; + return mavlink_finalize_message(msg, system_id, component_id, 32, 146); +} + +/** + * @brief Pack a obs_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 quat Quaternion re;im + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_obs_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const double *quat) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + + _mav_put_double_array(buf, 0, quat, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); +#else + mavlink_obs_attitude_t packet; + + mav_array_memcpy(packet.quat, quat, sizeof(double)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_OBS_ATTITUDE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 146); +} + +/** + * @brief Encode a obs_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 obs_attitude C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_obs_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_attitude_t* obs_attitude) +{ + return mavlink_msg_obs_attitude_pack(system_id, component_id, msg, obs_attitude->quat); +} + +/** + * @brief Send a obs_attitude message + * @param chan MAVLink channel to send the message + * + * @param quat Quaternion re;im + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_obs_attitude_send(mavlink_channel_t chan, const double *quat) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + + _mav_put_double_array(buf, 0, quat, 4); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, buf, 32, 146); +#else + mavlink_obs_attitude_t packet; + + mav_array_memcpy(packet.quat, quat, sizeof(double)*4); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, (const char *)&packet, 32, 146); +#endif +} + +#endif + +// MESSAGE OBS_ATTITUDE UNPACKING + + +/** + * @brief Get field quat from obs_attitude message + * + * @return Quaternion re;im + */ +static inline uint16_t mavlink_msg_obs_attitude_get_quat(const mavlink_message_t* msg, double *quat) +{ + return _MAV_RETURN_double_array(msg, quat, 4, 0); +} + +/** + * @brief Decode a obs_attitude message into a struct + * + * @param msg The message to decode + * @param obs_attitude C-struct to decode the message contents into + */ +static inline void mavlink_msg_obs_attitude_decode(const mavlink_message_t* msg, mavlink_obs_attitude_t* obs_attitude) +{ +#if MAVLINK_NEED_BYTE_SWAP + mavlink_msg_obs_attitude_get_quat(msg, obs_attitude->quat); +#else + memcpy(obs_attitude, _MAV_PAYLOAD(msg), 32); +#endif +} diff --git a/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_bias.h b/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_bias.h new file mode 100644 index 0000000000000000000000000000000000000000..565ab0cd8647906a7c74d2928fc72fa0509d9ea3 --- /dev/null +++ b/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_bias.h @@ -0,0 +1,167 @@ +// MESSAGE OBS_BIAS PACKING + +#define MAVLINK_MSG_ID_OBS_BIAS 180 + +typedef struct __mavlink_obs_bias_t +{ + float accBias[3]; ///< accelerometer bias + float gyroBias[3]; ///< gyroscope bias +} mavlink_obs_bias_t; + +#define MAVLINK_MSG_ID_OBS_BIAS_LEN 24 +#define MAVLINK_MSG_ID_180_LEN 24 + +#define MAVLINK_MSG_OBS_BIAS_FIELD_ACCBIAS_LEN 3 +#define MAVLINK_MSG_OBS_BIAS_FIELD_GYROBIAS_LEN 3 + +#define MAVLINK_MESSAGE_INFO_OBS_BIAS { \ + "OBS_BIAS", \ + 2, \ + { { "accBias", NULL, MAVLINK_TYPE_FLOAT, 3, 0, offsetof(mavlink_obs_bias_t, accBias) }, \ + { "gyroBias", NULL, MAVLINK_TYPE_FLOAT, 3, 12, offsetof(mavlink_obs_bias_t, gyroBias) }, \ + } \ +} + + +/** + * @brief Pack a obs_bias 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 accBias accelerometer bias + * @param gyroBias gyroscope bias + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_obs_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const float *accBias, const float *gyroBias) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[24]; + + _mav_put_float_array(buf, 0, accBias, 3); + _mav_put_float_array(buf, 12, gyroBias, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24); +#else + mavlink_obs_bias_t packet; + + mav_array_memcpy(packet.accBias, accBias, sizeof(float)*3); + mav_array_memcpy(packet.gyroBias, gyroBias, sizeof(float)*3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24); +#endif + + msg->msgid = MAVLINK_MSG_ID_OBS_BIAS; + return mavlink_finalize_message(msg, system_id, component_id, 24, 159); +} + +/** + * @brief Pack a obs_bias 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 accBias accelerometer bias + * @param gyroBias gyroscope bias + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_obs_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const float *accBias,const float *gyroBias) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[24]; + + _mav_put_float_array(buf, 0, accBias, 3); + _mav_put_float_array(buf, 12, gyroBias, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24); +#else + mavlink_obs_bias_t packet; + + mav_array_memcpy(packet.accBias, accBias, sizeof(float)*3); + mav_array_memcpy(packet.gyroBias, gyroBias, sizeof(float)*3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24); +#endif + + msg->msgid = MAVLINK_MSG_ID_OBS_BIAS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 24, 159); +} + +/** + * @brief Encode a obs_bias 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 obs_bias C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_obs_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_bias_t* obs_bias) +{ + return mavlink_msg_obs_bias_pack(system_id, component_id, msg, obs_bias->accBias, obs_bias->gyroBias); +} + +/** + * @brief Send a obs_bias message + * @param chan MAVLink channel to send the message + * + * @param accBias accelerometer bias + * @param gyroBias gyroscope bias + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_obs_bias_send(mavlink_channel_t chan, const float *accBias, const float *gyroBias) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[24]; + + _mav_put_float_array(buf, 0, accBias, 3); + _mav_put_float_array(buf, 12, gyroBias, 3); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, buf, 24, 159); +#else + mavlink_obs_bias_t packet; + + mav_array_memcpy(packet.accBias, accBias, sizeof(float)*3); + mav_array_memcpy(packet.gyroBias, gyroBias, sizeof(float)*3); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, (const char *)&packet, 24, 159); +#endif +} + +#endif + +// MESSAGE OBS_BIAS UNPACKING + + +/** + * @brief Get field accBias from obs_bias message + * + * @return accelerometer bias + */ +static inline uint16_t mavlink_msg_obs_bias_get_accBias(const mavlink_message_t* msg, float *accBias) +{ + return _MAV_RETURN_float_array(msg, accBias, 3, 0); +} + +/** + * @brief Get field gyroBias from obs_bias message + * + * @return gyroscope bias + */ +static inline uint16_t mavlink_msg_obs_bias_get_gyroBias(const mavlink_message_t* msg, float *gyroBias) +{ + return _MAV_RETURN_float_array(msg, gyroBias, 3, 12); +} + +/** + * @brief Decode a obs_bias message into a struct + * + * @param msg The message to decode + * @param obs_bias C-struct to decode the message contents into + */ +static inline void mavlink_msg_obs_bias_decode(const mavlink_message_t* msg, mavlink_obs_bias_t* obs_bias) +{ +#if MAVLINK_NEED_BYTE_SWAP + mavlink_msg_obs_bias_get_accBias(msg, obs_bias->accBias); + mavlink_msg_obs_bias_get_gyroBias(msg, obs_bias->gyroBias); +#else + memcpy(obs_bias, _MAV_PAYLOAD(msg), 24); +#endif +} diff --git a/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_position.h b/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_position.h new file mode 100644 index 0000000000000000000000000000000000000000..e886c8c24fc95467923a6634e01aea2598d685f3 --- /dev/null +++ b/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_position.h @@ -0,0 +1,188 @@ +// MESSAGE OBS_POSITION PACKING + +#define MAVLINK_MSG_ID_OBS_POSITION 170 + +typedef struct __mavlink_obs_position_t +{ + int32_t lon; ///< Longitude expressed in 1E7 + int32_t lat; ///< Latitude expressed in 1E7 + int32_t alt; ///< Altitude expressed in milimeters +} mavlink_obs_position_t; + +#define MAVLINK_MSG_ID_OBS_POSITION_LEN 12 +#define MAVLINK_MSG_ID_170_LEN 12 + + + +#define MAVLINK_MESSAGE_INFO_OBS_POSITION { \ + "OBS_POSITION", \ + 3, \ + { { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_obs_position_t, lon) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_obs_position_t, lat) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_obs_position_t, alt) }, \ + } \ +} + + +/** + * @brief Pack a obs_position 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 lon Longitude expressed in 1E7 + * @param lat Latitude expressed in 1E7 + * @param alt Altitude expressed in milimeters + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_obs_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int32_t lon, int32_t lat, int32_t alt) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_int32_t(buf, 0, lon); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, alt); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_obs_position_t packet; + packet.lon = lon; + packet.lat = lat; + packet.alt = alt; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_OBS_POSITION; + return mavlink_finalize_message(msg, system_id, component_id, 12, 15); +} + +/** + * @brief Pack a obs_position 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 lon Longitude expressed in 1E7 + * @param lat Latitude expressed in 1E7 + * @param alt Altitude expressed in milimeters + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_obs_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int32_t lon,int32_t lat,int32_t alt) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_int32_t(buf, 0, lon); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, alt); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_obs_position_t packet; + packet.lon = lon; + packet.lat = lat; + packet.alt = alt; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_OBS_POSITION; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 15); +} + +/** + * @brief Encode a obs_position 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 obs_position C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_obs_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_position_t* obs_position) +{ + return mavlink_msg_obs_position_pack(system_id, component_id, msg, obs_position->lon, obs_position->lat, obs_position->alt); +} + +/** + * @brief Send a obs_position message + * @param chan MAVLink channel to send the message + * + * @param lon Longitude expressed in 1E7 + * @param lat Latitude expressed in 1E7 + * @param alt Altitude expressed in milimeters + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_obs_position_send(mavlink_channel_t chan, int32_t lon, int32_t lat, int32_t alt) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_int32_t(buf, 0, lon); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, alt); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, buf, 12, 15); +#else + mavlink_obs_position_t packet; + packet.lon = lon; + packet.lat = lat; + packet.alt = alt; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, (const char *)&packet, 12, 15); +#endif +} + +#endif + +// MESSAGE OBS_POSITION UNPACKING + + +/** + * @brief Get field lon from obs_position message + * + * @return Longitude expressed in 1E7 + */ +static inline int32_t mavlink_msg_obs_position_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field lat from obs_position message + * + * @return Latitude expressed in 1E7 + */ +static inline int32_t mavlink_msg_obs_position_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field alt from obs_position message + * + * @return Altitude expressed in milimeters + */ +static inline int32_t mavlink_msg_obs_position_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Decode a obs_position message into a struct + * + * @param msg The message to decode + * @param obs_position C-struct to decode the message contents into + */ +static inline void mavlink_msg_obs_position_decode(const mavlink_message_t* msg, mavlink_obs_position_t* obs_position) +{ +#if MAVLINK_NEED_BYTE_SWAP + obs_position->lon = mavlink_msg_obs_position_get_lon(msg); + obs_position->lat = mavlink_msg_obs_position_get_lat(msg); + obs_position->alt = mavlink_msg_obs_position_get_alt(msg); +#else + memcpy(obs_position, _MAV_PAYLOAD(msg), 12); +#endif +} diff --git a/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_qff.h b/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_qff.h new file mode 100644 index 0000000000000000000000000000000000000000..4ab10ca07cecb9577cb58597e9385486935bfb9a --- /dev/null +++ b/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_qff.h @@ -0,0 +1,144 @@ +// MESSAGE OBS_QFF PACKING + +#define MAVLINK_MSG_ID_OBS_QFF 182 + +typedef struct __mavlink_obs_qff_t +{ + float qff; ///< Wind +} mavlink_obs_qff_t; + +#define MAVLINK_MSG_ID_OBS_QFF_LEN 4 +#define MAVLINK_MSG_ID_182_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_OBS_QFF { \ + "OBS_QFF", \ + 1, \ + { { "qff", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_obs_qff_t, qff) }, \ + } \ +} + + +/** + * @brief Pack a obs_qff 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 qff Wind + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_obs_qff_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float qff) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_float(buf, 0, qff); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); +#else + mavlink_obs_qff_t packet; + packet.qff = qff; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_OBS_QFF; + return mavlink_finalize_message(msg, system_id, component_id, 4, 24); +} + +/** + * @brief Pack a obs_qff 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 qff Wind + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_obs_qff_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float qff) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_float(buf, 0, qff); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); +#else + mavlink_obs_qff_t packet; + packet.qff = qff; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_OBS_QFF; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 24); +} + +/** + * @brief Encode a obs_qff 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 obs_qff C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_obs_qff_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_qff_t* obs_qff) +{ + return mavlink_msg_obs_qff_pack(system_id, component_id, msg, obs_qff->qff); +} + +/** + * @brief Send a obs_qff message + * @param chan MAVLink channel to send the message + * + * @param qff Wind + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_obs_qff_send(mavlink_channel_t chan, float qff) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_float(buf, 0, qff); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, buf, 4, 24); +#else + mavlink_obs_qff_t packet; + packet.qff = qff; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, (const char *)&packet, 4, 24); +#endif +} + +#endif + +// MESSAGE OBS_QFF UNPACKING + + +/** + * @brief Get field qff from obs_qff message + * + * @return Wind + */ +static inline float mavlink_msg_obs_qff_get_qff(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Decode a obs_qff message into a struct + * + * @param msg The message to decode + * @param obs_qff C-struct to decode the message contents into + */ +static inline void mavlink_msg_obs_qff_decode(const mavlink_message_t* msg, mavlink_obs_qff_t* obs_qff) +{ +#if MAVLINK_NEED_BYTE_SWAP + obs_qff->qff = mavlink_msg_obs_qff_get_qff(msg); +#else + memcpy(obs_qff, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_velocity.h b/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_velocity.h new file mode 100644 index 0000000000000000000000000000000000000000..e5ace9f85e2e85614ecbfb0c6e2422d3b1d99185 --- /dev/null +++ b/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_velocity.h @@ -0,0 +1,144 @@ +// MESSAGE OBS_VELOCITY PACKING + +#define MAVLINK_MSG_ID_OBS_VELOCITY 172 + +typedef struct __mavlink_obs_velocity_t +{ + float vel[3]; ///< Velocity +} mavlink_obs_velocity_t; + +#define MAVLINK_MSG_ID_OBS_VELOCITY_LEN 12 +#define MAVLINK_MSG_ID_172_LEN 12 + +#define MAVLINK_MSG_OBS_VELOCITY_FIELD_VEL_LEN 3 + +#define MAVLINK_MESSAGE_INFO_OBS_VELOCITY { \ + "OBS_VELOCITY", \ + 1, \ + { { "vel", NULL, MAVLINK_TYPE_FLOAT, 3, 0, offsetof(mavlink_obs_velocity_t, vel) }, \ + } \ +} + + +/** + * @brief Pack a obs_velocity 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 vel Velocity + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_obs_velocity_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const float *vel) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + + _mav_put_float_array(buf, 0, vel, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_obs_velocity_t packet; + + mav_array_memcpy(packet.vel, vel, sizeof(float)*3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_OBS_VELOCITY; + return mavlink_finalize_message(msg, system_id, component_id, 12, 108); +} + +/** + * @brief Pack a obs_velocity 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 vel Velocity + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_obs_velocity_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const float *vel) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + + _mav_put_float_array(buf, 0, vel, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_obs_velocity_t packet; + + mav_array_memcpy(packet.vel, vel, sizeof(float)*3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_OBS_VELOCITY; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 108); +} + +/** + * @brief Encode a obs_velocity 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 obs_velocity C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_obs_velocity_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_velocity_t* obs_velocity) +{ + return mavlink_msg_obs_velocity_pack(system_id, component_id, msg, obs_velocity->vel); +} + +/** + * @brief Send a obs_velocity message + * @param chan MAVLink channel to send the message + * + * @param vel Velocity + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_obs_velocity_send(mavlink_channel_t chan, const float *vel) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + + _mav_put_float_array(buf, 0, vel, 3); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, buf, 12, 108); +#else + mavlink_obs_velocity_t packet; + + mav_array_memcpy(packet.vel, vel, sizeof(float)*3); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, (const char *)&packet, 12, 108); +#endif +} + +#endif + +// MESSAGE OBS_VELOCITY UNPACKING + + +/** + * @brief Get field vel from obs_velocity message + * + * @return Velocity + */ +static inline uint16_t mavlink_msg_obs_velocity_get_vel(const mavlink_message_t* msg, float *vel) +{ + return _MAV_RETURN_float_array(msg, vel, 3, 0); +} + +/** + * @brief Decode a obs_velocity message into a struct + * + * @param msg The message to decode + * @param obs_velocity C-struct to decode the message contents into + */ +static inline void mavlink_msg_obs_velocity_decode(const mavlink_message_t* msg, mavlink_obs_velocity_t* obs_velocity) +{ +#if MAVLINK_NEED_BYTE_SWAP + mavlink_msg_obs_velocity_get_vel(msg, obs_velocity->vel); +#else + memcpy(obs_velocity, _MAV_PAYLOAD(msg), 12); +#endif +} diff --git a/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_wind.h b/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_wind.h new file mode 100644 index 0000000000000000000000000000000000000000..6011a1caadd0c8f05fe5cf744ebf527ef3c62a51 --- /dev/null +++ b/thirdParty/mavlink/include/sensesoar/mavlink_msg_obs_wind.h @@ -0,0 +1,144 @@ +// MESSAGE OBS_WIND PACKING + +#define MAVLINK_MSG_ID_OBS_WIND 176 + +typedef struct __mavlink_obs_wind_t +{ + float wind[3]; ///< Wind +} mavlink_obs_wind_t; + +#define MAVLINK_MSG_ID_OBS_WIND_LEN 12 +#define MAVLINK_MSG_ID_176_LEN 12 + +#define MAVLINK_MSG_OBS_WIND_FIELD_WIND_LEN 3 + +#define MAVLINK_MESSAGE_INFO_OBS_WIND { \ + "OBS_WIND", \ + 1, \ + { { "wind", NULL, MAVLINK_TYPE_FLOAT, 3, 0, offsetof(mavlink_obs_wind_t, wind) }, \ + } \ +} + + +/** + * @brief Pack a obs_wind 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 wind Wind + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_obs_wind_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const float *wind) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + + _mav_put_float_array(buf, 0, wind, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_obs_wind_t packet; + + mav_array_memcpy(packet.wind, wind, sizeof(float)*3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_OBS_WIND; + return mavlink_finalize_message(msg, system_id, component_id, 12, 16); +} + +/** + * @brief Pack a obs_wind 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 wind Wind + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_obs_wind_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const float *wind) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + + _mav_put_float_array(buf, 0, wind, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12); +#else + mavlink_obs_wind_t packet; + + mav_array_memcpy(packet.wind, wind, sizeof(float)*3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_OBS_WIND; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 16); +} + +/** + * @brief Encode a obs_wind 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 obs_wind C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_obs_wind_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_wind_t* obs_wind) +{ + return mavlink_msg_obs_wind_pack(system_id, component_id, msg, obs_wind->wind); +} + +/** + * @brief Send a obs_wind message + * @param chan MAVLink channel to send the message + * + * @param wind Wind + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_obs_wind_send(mavlink_channel_t chan, const float *wind) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + + _mav_put_float_array(buf, 0, wind, 3); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, buf, 12, 16); +#else + mavlink_obs_wind_t packet; + + mav_array_memcpy(packet.wind, wind, sizeof(float)*3); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, (const char *)&packet, 12, 16); +#endif +} + +#endif + +// MESSAGE OBS_WIND UNPACKING + + +/** + * @brief Get field wind from obs_wind message + * + * @return Wind + */ +static inline uint16_t mavlink_msg_obs_wind_get_wind(const mavlink_message_t* msg, float *wind) +{ + return _MAV_RETURN_float_array(msg, wind, 3, 0); +} + +/** + * @brief Decode a obs_wind message into a struct + * + * @param msg The message to decode + * @param obs_wind C-struct to decode the message contents into + */ +static inline void mavlink_msg_obs_wind_decode(const mavlink_message_t* msg, mavlink_obs_wind_t* obs_wind) +{ +#if MAVLINK_NEED_BYTE_SWAP + mavlink_msg_obs_wind_get_wind(msg, obs_wind->wind); +#else + memcpy(obs_wind, _MAV_PAYLOAD(msg), 12); +#endif +} diff --git a/thirdParty/mavlink/include/sensesoar/mavlink_msg_pm_elec.h b/thirdParty/mavlink/include/sensesoar/mavlink_msg_pm_elec.h new file mode 100644 index 0000000000000000000000000000000000000000..d194dae9bc4b31f1b32fd857c5c67533de1a8d77 --- /dev/null +++ b/thirdParty/mavlink/include/sensesoar/mavlink_msg_pm_elec.h @@ -0,0 +1,182 @@ +// MESSAGE PM_ELEC PACKING + +#define MAVLINK_MSG_ID_PM_ELEC 188 + +typedef struct __mavlink_pm_elec_t +{ + float PwCons; ///< current power consumption + float BatStat; ///< battery status + float PwGen[3]; ///< Power generation from each module +} mavlink_pm_elec_t; + +#define MAVLINK_MSG_ID_PM_ELEC_LEN 20 +#define MAVLINK_MSG_ID_188_LEN 20 + +#define MAVLINK_MSG_PM_ELEC_FIELD_PWGEN_LEN 3 + +#define MAVLINK_MESSAGE_INFO_PM_ELEC { \ + "PM_ELEC", \ + 3, \ + { { "PwCons", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_pm_elec_t, PwCons) }, \ + { "BatStat", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_pm_elec_t, BatStat) }, \ + { "PwGen", NULL, MAVLINK_TYPE_FLOAT, 3, 8, offsetof(mavlink_pm_elec_t, PwGen) }, \ + } \ +} + + +/** + * @brief Pack a pm_elec 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 PwCons current power consumption + * @param BatStat battery status + * @param PwGen Power generation from each module + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_pm_elec_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float PwCons, float BatStat, const float *PwGen) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_float(buf, 0, PwCons); + _mav_put_float(buf, 4, BatStat); + _mav_put_float_array(buf, 8, PwGen, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); +#else + mavlink_pm_elec_t packet; + packet.PwCons = PwCons; + packet.BatStat = BatStat; + mav_array_memcpy(packet.PwGen, PwGen, sizeof(float)*3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_PM_ELEC; + return mavlink_finalize_message(msg, system_id, component_id, 20, 170); +} + +/** + * @brief Pack a pm_elec 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 PwCons current power consumption + * @param BatStat battery status + * @param PwGen Power generation from each module + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_pm_elec_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float PwCons,float BatStat,const float *PwGen) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_float(buf, 0, PwCons); + _mav_put_float(buf, 4, BatStat); + _mav_put_float_array(buf, 8, PwGen, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); +#else + mavlink_pm_elec_t packet; + packet.PwCons = PwCons; + packet.BatStat = BatStat; + mav_array_memcpy(packet.PwGen, PwGen, sizeof(float)*3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_PM_ELEC; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 170); +} + +/** + * @brief Encode a pm_elec 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 pm_elec C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_pm_elec_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pm_elec_t* pm_elec) +{ + return mavlink_msg_pm_elec_pack(system_id, component_id, msg, pm_elec->PwCons, pm_elec->BatStat, pm_elec->PwGen); +} + +/** + * @brief Send a pm_elec message + * @param chan MAVLink channel to send the message + * + * @param PwCons current power consumption + * @param BatStat battery status + * @param PwGen Power generation from each module + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_pm_elec_send(mavlink_channel_t chan, float PwCons, float BatStat, const float *PwGen) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_float(buf, 0, PwCons); + _mav_put_float(buf, 4, BatStat); + _mav_put_float_array(buf, 8, PwGen, 3); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, buf, 20, 170); +#else + mavlink_pm_elec_t packet; + packet.PwCons = PwCons; + packet.BatStat = BatStat; + mav_array_memcpy(packet.PwGen, PwGen, sizeof(float)*3); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, (const char *)&packet, 20, 170); +#endif +} + +#endif + +// MESSAGE PM_ELEC UNPACKING + + +/** + * @brief Get field PwCons from pm_elec message + * + * @return current power consumption + */ +static inline float mavlink_msg_pm_elec_get_PwCons(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field BatStat from pm_elec message + * + * @return battery status + */ +static inline float mavlink_msg_pm_elec_get_BatStat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field PwGen from pm_elec message + * + * @return Power generation from each module + */ +static inline uint16_t mavlink_msg_pm_elec_get_PwGen(const mavlink_message_t* msg, float *PwGen) +{ + return _MAV_RETURN_float_array(msg, PwGen, 3, 8); +} + +/** + * @brief Decode a pm_elec message into a struct + * + * @param msg The message to decode + * @param pm_elec C-struct to decode the message contents into + */ +static inline void mavlink_msg_pm_elec_decode(const mavlink_message_t* msg, mavlink_pm_elec_t* pm_elec) +{ +#if MAVLINK_NEED_BYTE_SWAP + pm_elec->PwCons = mavlink_msg_pm_elec_get_PwCons(msg); + pm_elec->BatStat = mavlink_msg_pm_elec_get_BatStat(msg); + mavlink_msg_pm_elec_get_PwGen(msg, pm_elec->PwGen); +#else + memcpy(pm_elec, _MAV_PAYLOAD(msg), 20); +#endif +} diff --git a/thirdParty/mavlink/include/sensesoar/mavlink_msg_sys_stat.h b/thirdParty/mavlink/include/sensesoar/mavlink_msg_sys_stat.h new file mode 100644 index 0000000000000000000000000000000000000000..597fdf911f47ee9ca3eeed15cc543f4bbb37bbf4 --- /dev/null +++ b/thirdParty/mavlink/include/sensesoar/mavlink_msg_sys_stat.h @@ -0,0 +1,210 @@ +// MESSAGE SYS_Stat PACKING + +#define MAVLINK_MSG_ID_SYS_Stat 190 + +typedef struct __mavlink_sys_stat_t +{ + uint8_t gps; ///< gps status + uint8_t act; ///< actuator status + uint8_t mod; ///< module status + uint8_t commRssi; ///< module status +} mavlink_sys_stat_t; + +#define MAVLINK_MSG_ID_SYS_Stat_LEN 4 +#define MAVLINK_MSG_ID_190_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_SYS_Stat { \ + "SYS_Stat", \ + 4, \ + { { "gps", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_sys_stat_t, gps) }, \ + { "act", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_sys_stat_t, act) }, \ + { "mod", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_sys_stat_t, mod) }, \ + { "commRssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_sys_stat_t, commRssi) }, \ + } \ +} + + +/** + * @brief Pack a sys_stat 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 gps status + * @param act actuator status + * @param mod module status + * @param commRssi module status + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sys_stat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t gps, uint8_t act, uint8_t mod, uint8_t commRssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint8_t(buf, 0, gps); + _mav_put_uint8_t(buf, 1, act); + _mav_put_uint8_t(buf, 2, mod); + _mav_put_uint8_t(buf, 3, commRssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); +#else + mavlink_sys_stat_t packet; + packet.gps = gps; + packet.act = act; + packet.mod = mod; + packet.commRssi = commRssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYS_Stat; + return mavlink_finalize_message(msg, system_id, component_id, 4, 157); +} + +/** + * @brief Pack a sys_stat 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 gps gps status + * @param act actuator status + * @param mod module status + * @param commRssi module status + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sys_stat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t gps,uint8_t act,uint8_t mod,uint8_t commRssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint8_t(buf, 0, gps); + _mav_put_uint8_t(buf, 1, act); + _mav_put_uint8_t(buf, 2, mod); + _mav_put_uint8_t(buf, 3, commRssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4); +#else + mavlink_sys_stat_t packet; + packet.gps = gps; + packet.act = act; + packet.mod = mod; + packet.commRssi = commRssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYS_Stat; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 157); +} + +/** + * @brief Encode a sys_stat 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_stat C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_sys_stat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_stat_t* sys_stat) +{ + return mavlink_msg_sys_stat_pack(system_id, component_id, msg, sys_stat->gps, sys_stat->act, sys_stat->mod, sys_stat->commRssi); +} + +/** + * @brief Send a sys_stat message + * @param chan MAVLink channel to send the message + * + * @param gps gps status + * @param act actuator status + * @param mod module status + * @param commRssi module status + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_sys_stat_send(mavlink_channel_t chan, uint8_t gps, uint8_t act, uint8_t mod, uint8_t commRssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint8_t(buf, 0, gps); + _mav_put_uint8_t(buf, 1, act); + _mav_put_uint8_t(buf, 2, mod); + _mav_put_uint8_t(buf, 3, commRssi); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, buf, 4, 157); +#else + mavlink_sys_stat_t packet; + packet.gps = gps; + packet.act = act; + packet.mod = mod; + packet.commRssi = commRssi; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, (const char *)&packet, 4, 157); +#endif +} + +#endif + +// MESSAGE SYS_Stat UNPACKING + + +/** + * @brief Get field gps from sys_stat message + * + * @return gps status + */ +static inline uint8_t mavlink_msg_sys_stat_get_gps(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field act from sys_stat message + * + * @return actuator status + */ +static inline uint8_t mavlink_msg_sys_stat_get_act(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field mod from sys_stat message + * + * @return module status + */ +static inline uint8_t mavlink_msg_sys_stat_get_mod(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field commRssi from sys_stat message + * + * @return module status + */ +static inline uint8_t mavlink_msg_sys_stat_get_commRssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Decode a sys_stat message into a struct + * + * @param msg The message to decode + * @param sys_stat C-struct to decode the message contents into + */ +static inline void mavlink_msg_sys_stat_decode(const mavlink_message_t* msg, mavlink_sys_stat_t* sys_stat) +{ +#if MAVLINK_NEED_BYTE_SWAP + sys_stat->gps = mavlink_msg_sys_stat_get_gps(msg); + sys_stat->act = mavlink_msg_sys_stat_get_act(msg); + sys_stat->mod = mavlink_msg_sys_stat_get_mod(msg); + sys_stat->commRssi = mavlink_msg_sys_stat_get_commRssi(msg); +#else + memcpy(sys_stat, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/thirdParty/mavlink/include/sensesoar/sensesoar.h b/thirdParty/mavlink/include/sensesoar/sensesoar.h new file mode 100644 index 0000000000000000000000000000000000000000..0e71525281be2cd16696606833fd725095b161fc --- /dev/null +++ b/thirdParty/mavlink/include/sensesoar/sensesoar.h @@ -0,0 +1,77 @@ +/** @file + * @brief MAVLink comm protocol generated from sensesoar.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef SENSESOAR_H +#define SENSESOAR_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, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 0, 12, 0, 32, 0, 12, 0, 12, 0, 24, 0, 4, 4, 12, 0, 12, 0, 20, 0, 4, 0, 5, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 15, 0, 108, 0, 146, 0, 16, 0, 32, 0, 159, 0, 24, 248, 79, 0, 5, 0, 170, 0, 157, 0, 209, 0, 243, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, 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}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_OBS_POSITION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_ATTITUDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_WIND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_AIR_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_BIAS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_QFF, MAVLINK_MESSAGE_INFO_OBS_AIR_TEMP, MAVLINK_MESSAGE_INFO_FILT_ROT_VEL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LLC_OUT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PM_ELEC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_Stat, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_CHNG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_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}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_SENSESOAR + +#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 Different flight modes */ +#ifndef HAVE_ENUM_SENSESOAR_MODE +#define HAVE_ENUM_SENSESOAR_MODE +enum SENSESOAR_MODE +{ + SENSESOAR_MODE_GLIDING=1, /* | */ + SENSESOAR_MODE_AUTONOMOUS=2, /* | */ + SENSESOAR_MODE_MANUAL=3, /* | */ + SENSESOAR_MODE_ENUM_END=4, /* | */ +}; +#endif + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_obs_position.h" +#include "./mavlink_msg_obs_velocity.h" +#include "./mavlink_msg_obs_attitude.h" +#include "./mavlink_msg_obs_wind.h" +#include "./mavlink_msg_obs_air_velocity.h" +#include "./mavlink_msg_obs_bias.h" +#include "./mavlink_msg_obs_qff.h" +#include "./mavlink_msg_obs_air_temp.h" +#include "./mavlink_msg_filt_rot_vel.h" +#include "./mavlink_msg_llc_out.h" +#include "./mavlink_msg_pm_elec.h" +#include "./mavlink_msg_sys_stat.h" +#include "./mavlink_msg_cmd_airspeed_chng.h" +#include "./mavlink_msg_cmd_airspeed_ack.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // SENSESOAR_H diff --git a/thirdParty/mavlink/include/sensesoar/version.h b/thirdParty/mavlink/include/sensesoar/version.h index 941b10628bbc3b14cf930a74f5330638fad5ed51..e3b4b8bc2d17be67109139fb4f5325a12da1c32e 100644 --- a/thirdParty/mavlink/include/sensesoar/version.h +++ b/thirdParty/mavlink/include/sensesoar/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Wed Jan 11 14:50:35 2012" +#define MAVLINK_BUILD_DATE "Thu Feb 9 16:35:36 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/thirdParty/mavlink/include/slugs/slugs.h b/thirdParty/mavlink/include/slugs/slugs.h index d0fda8c1d09e5558ec17287ac4309b373e6ea0a6..0c90cb9fcb69de701be031a5f766527ebd7722ad 100644 --- a/thirdParty/mavlink/include/slugs/slugs.h +++ b/thirdParty/mavlink/include/slugs/slugs.h @@ -12,15 +12,15 @@ 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, 0, 0, 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, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 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, 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, 36, 30, 18, 18, 51, 9, 3} +#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, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 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, 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, 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, 0, 0, 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, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 75, 232, 168, 2, 0, 0, 120, 167, 0, 16, 146, 104, 0, 65, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 247} +#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, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 75, 232, 168, 2, 0, 0, 120, 167, 0, 16, 146, 104, 0, 65, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, 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}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, 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}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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}}}, 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, MAVLINK_MESSAGE_INFO_EXTENDED_MESSAGE} +#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}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, 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}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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}}}, 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" diff --git a/thirdParty/mavlink/include/slugs/version.h b/thirdParty/mavlink/include/slugs/version.h index 58a4bfb5412cc6fbbabb2c87b8ae2952932d5281..81427e789c6b6203e9ed1206b0cfb0d521788d76 100644 --- a/thirdParty/mavlink/include/slugs/version.h +++ b/thirdParty/mavlink/include/slugs/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Sun Nov 6 11:54:29 2011" +#define MAVLINK_BUILD_DATE "Thu Feb 9 16:35:35 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/thirdParty/mavlink/include/test/version.h b/thirdParty/mavlink/include/test/version.h index cfc73238c7162a0e0fc013d1a283c8d8754b2dd3..605c945cd87c55c1fd93d5705704f58c47b28902 100644 --- a/thirdParty/mavlink/include/test/version.h +++ b/thirdParty/mavlink/include/test/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Tue Jan 10 11:49:45 2012" +#define MAVLINK_BUILD_DATE "Thu Feb 9 16:35:37 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 179 diff --git a/thirdParty/mavlink/include/ualberta/ualberta.h b/thirdParty/mavlink/include/ualberta/ualberta.h index e962d87bdad76454fcdcfe080c684065bf7df141..476df38891c67e9fac0e33401033ea746ee96d11 100644 --- a/thirdParty/mavlink/include/ualberta/ualberta.h +++ b/thirdParty/mavlink/include/ualberta/ualberta.h @@ -12,15 +12,15 @@ 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, 0, 0, 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, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 36, 30, 18, 18, 51, 9, 3} +#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, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 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, 0, 0, 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, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 204, 49, 170, 44, 83, 46, 247} +#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, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, 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}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, 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}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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}}}, 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, MAVLINK_MESSAGE_INFO_EXTENDED_MESSAGE} +#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}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, 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}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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}}}, 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" diff --git a/thirdParty/mavlink/include/ualberta/version.h b/thirdParty/mavlink/include/ualberta/version.h index 18a92c9b3aeeea40c43c65dd331fd1e241c5eaa3..2c8e97da22222646557f2313bede58dbb39ccbf2 100644 --- a/thirdParty/mavlink/include/ualberta/version.h +++ b/thirdParty/mavlink/include/ualberta/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Sun Nov 6 11:54:54 2011" +#define MAVLINK_BUILD_DATE "Thu Feb 9 16:35:36 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/thirdParty/mavlink/message_definitions/pixhawk.proto b/thirdParty/mavlink/message_definitions/pixhawk.proto index 6bd0a82b366ba8f79ede45a27f81da3e3080651b..e658cf575c1175c60a0020099d9bb85e652d717d 100644 --- a/thirdParty/mavlink/message_definitions/pixhawk.proto +++ b/thirdParty/mavlink/message_definitions/pixhawk.proto @@ -1,5 +1,11 @@ package px; +message HeaderInfo { + required int32 source_sysid = 1; + required int32 source_compid = 2; + required double timestamp = 3; // in seconds +} + message PointCloudXYZI { message PointXYZI { required float x = 1; @@ -8,7 +14,8 @@ message PointCloudXYZI { required float intensity = 4; } - repeated PointXYZI points = 1; + required HeaderInfo header = 1; + repeated PointXYZI points = 2; } message PointCloudXYZRGB { @@ -19,22 +26,24 @@ message PointCloudXYZRGB { required float rgb = 4; } - repeated PointXYZRGB points = 1; + required HeaderInfo header = 1; + repeated PointXYZRGB points = 2; } message RGBDImage { - required uint32 cols = 1; ///< Number of columns in image(s) - required uint32 rows = 2; ///< Number of rows in image(s) - required uint32 step1 = 3; ///< Step (stride) of image 1 - required uint32 type1 = 4; ///< Type of image 1 - required bytes imageData1 = 5; - required uint32 step2 = 6; ///< Step (stride) of image 2 - required uint32 type2 = 7; ///< Type of image 2 - required bytes imageData2 = 8; - optional uint32 camera_config = 9; ///< PxSHM::Camera enumeration - optional uint32 camera_type = 10; ///< PxSHM::CameraType enumeration - optional uint64 timestamp = 11; + required HeaderInfo header = 1; + + required uint32 cols = 2; ///< Number of columns in image(s) + required uint32 rows = 3; ///< Number of rows in image(s) + required uint32 step1 = 4; ///< Step (stride) of image 1 + required uint32 type1 = 5; ///< Type of image 1 + required bytes imageData1 = 6; + required uint32 step2 = 7; ///< Step (stride) of image 2 + required uint32 type2 = 8; ///< Type of image 2 + required bytes imageData2 = 9; + optional uint32 camera_config = 10; ///< PxSHM::Camera enumeration + optional uint32 camera_type = 11; ///< PxSHM::CameraType enumeration optional float roll = 12; optional float pitch = 13; optional float yaw = 14; @@ -47,3 +56,53 @@ message RGBDImage repeated float camera_matrix = 21; } +message Obstacle +{ + optional float x = 1; + optional float y = 2; + optional float z = 3; + optional float length = 4; + optional float width = 5; + optional float height = 6; +} + +message ObstacleList +{ + required HeaderInfo header = 1; + + repeated Obstacle obstacles = 2; +} + +message ObstacleMap +{ + required HeaderInfo header = 1; + + required int32 type = 2; + + optional float resolution = 3; + optional int32 rows = 4; + optional int32 cols = 5; + optional int32 mapR0 = 6; + optional int32 mapC0 = 7; + optional int32 arrayR0 = 8; + optional int32 arrayC0 = 9; + + optional bytes data = 10; +} + +message Waypoint +{ + required double x = 1; + required double y = 2; + optional double z = 3; + optional double roll = 4; + optional double pitch = 5; + optional double yaw = 6; +} + +message Path +{ + required HeaderInfo header = 1; + + repeated Waypoint waypoints = 2; +} diff --git a/thirdParty/mavlink/message_definitions/sensesoar.xml b/thirdParty/mavlink/message_definitions/sensesoar.xml new file mode 100644 index 0000000000000000000000000000000000000000..4c7140f93d690128b2e0feaf51f8ec9292875110 --- /dev/null +++ b/thirdParty/mavlink/message_definitions/sensesoar.xml @@ -0,0 +1,83 @@ + + + common.xml + + + Different flight modes + Gliding mode with motors off + Autonomous flight + RC controlled + + + + + Position estimate of the observer in global frame + Longitude expressed in 1E7 + Latitude expressed in 1E7 + Altitude expressed in milimeters + + + velocity estimate of the observer in NED inertial frame + Velocity + + + attitude estimate of the observer + Quaternion re;im + + + Wind estimate in NED inertial frame + Wind + + + Estimate of the air velocity + Air speed + angle of attack + slip angle + + + IMU biases + accelerometer bias + gyroscope bias + + + estimate of the pressure at sea level + Wind + + + ambient air temperature + Air Temperatur + + + filtered rotational velocity + rotational velocity + + + low level control output + Servo signal + motor signal + + + Power managment + current power consumption + battery status + Power generation from each module + + + system status + gps status + actuator status + module status + module status + + + change commanded air speed + Target ID + commanded airspeed + + + accept change of airspeed + commanded airspeed + 0:ack, 1:nack + + + diff --git a/thirdParty/mavlink/src/pixhawk/pixhawk.pb.cc b/thirdParty/mavlink/src/pixhawk/pixhawk.pb.cc index 16bc3b1eea34eb1d3688567de9322b7838ecd059..2e2058224a421351b8c5cff77601cc322272d30c 100644 --- a/thirdParty/mavlink/src/pixhawk/pixhawk.pb.cc +++ b/thirdParty/mavlink/src/pixhawk/pixhawk.pb.cc @@ -17,6 +17,9 @@ namespace px { namespace { +const ::google::protobuf::Descriptor* HeaderInfo_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + HeaderInfo_reflection_ = NULL; const ::google::protobuf::Descriptor* PointCloudXYZI_descriptor_ = NULL; const ::google::protobuf::internal::GeneratedMessageReflection* PointCloudXYZI_reflection_ = NULL; @@ -32,6 +35,21 @@ const ::google::protobuf::internal::GeneratedMessageReflection* const ::google::protobuf::Descriptor* RGBDImage_descriptor_ = NULL; const ::google::protobuf::internal::GeneratedMessageReflection* RGBDImage_reflection_ = 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* Waypoint_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + Waypoint_reflection_ = NULL; +const ::google::protobuf::Descriptor* Path_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + Path_reflection_ = NULL; } // namespace @@ -42,8 +60,26 @@ void protobuf_AssignDesc_pixhawk_2eproto() { ::google::protobuf::DescriptorPool::generated_pool()->FindFileByName( "pixhawk.proto"); GOOGLE_CHECK(file != NULL); - PointCloudXYZI_descriptor_ = file->message_type(0); - static const int PointCloudXYZI_offsets_[1] = { + 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)); + PointCloudXYZI_descriptor_ = file->message_type(1); + static const int PointCloudXYZI_offsets_[2] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, header_), GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, points_), }; PointCloudXYZI_reflection_ = @@ -75,8 +111,9 @@ void protobuf_AssignDesc_pixhawk_2eproto() { ::google::protobuf::DescriptorPool::generated_pool(), ::google::protobuf::MessageFactory::generated_factory(), sizeof(PointCloudXYZI_PointXYZI)); - PointCloudXYZRGB_descriptor_ = file->message_type(1); - static const int PointCloudXYZRGB_offsets_[1] = { + PointCloudXYZRGB_descriptor_ = file->message_type(2); + static const int PointCloudXYZRGB_offsets_[2] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, header_), GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, points_), }; PointCloudXYZRGB_reflection_ = @@ -108,8 +145,9 @@ void protobuf_AssignDesc_pixhawk_2eproto() { ::google::protobuf::DescriptorPool::generated_pool(), ::google::protobuf::MessageFactory::generated_factory(), sizeof(PointCloudXYZRGB_PointXYZRGB)); - RGBDImage_descriptor_ = file->message_type(2); + RGBDImage_descriptor_ = file->message_type(3); 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_), @@ -120,7 +158,6 @@ void protobuf_AssignDesc_pixhawk_2eproto() { 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, timestamp_), GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, roll_), GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, pitch_), GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, yaw_), @@ -143,6 +180,102 @@ void protobuf_AssignDesc_pixhawk_2eproto() { ::google::protobuf::DescriptorPool::generated_pool(), ::google::protobuf::MessageFactory::generated_factory(), sizeof(RGBDImage)); + Obstacle_descriptor_ = file->message_type(4); + 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(5); + 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(6); + 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)); + Waypoint_descriptor_ = file->message_type(7); + 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)); + Path_descriptor_ = file->message_type(8); + 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)); } namespace { @@ -155,6 +288,8 @@ inline void protobuf_AssignDescriptorsOnce() { void protobuf_RegisterTypes(const ::std::string&) { protobuf_AssignDescriptorsOnce(); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + HeaderInfo_descriptor_, &HeaderInfo::default_instance()); ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( PointCloudXYZI_descriptor_, &PointCloudXYZI::default_instance()); ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( @@ -165,11 +300,23 @@ void protobuf_RegisterTypes(const ::std::string&) { PointCloudXYZRGB_PointXYZRGB_descriptor_, &PointCloudXYZRGB_PointXYZRGB::default_instance()); ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( RGBDImage_descriptor_, &RGBDImage::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( + Waypoint_descriptor_, &Waypoint::default_instance()); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + Path_descriptor_, &Path::default_instance()); } } // namespace void protobuf_ShutdownFile_pixhawk_2eproto() { + delete HeaderInfo::default_instance_; + delete HeaderInfo_reflection_; delete PointCloudXYZI::default_instance_; delete PointCloudXYZI_reflection_; delete PointCloudXYZI_PointXYZI::default_instance_; @@ -180,6 +327,16 @@ void protobuf_ShutdownFile_pixhawk_2eproto() { delete PointCloudXYZRGB_PointXYZRGB_reflection_; delete RGBDImage::default_instance_; delete RGBDImage_reflection_; + delete Obstacle::default_instance_; + delete Obstacle_reflection_; + delete ObstacleList::default_instance_; + delete ObstacleList_reflection_; + delete ObstacleMap::default_instance_; + delete ObstacleMap_reflection_; + delete Waypoint::default_instance_; + delete Waypoint_reflection_; + delete Path::default_instance_; + delete Path_reflection_; } void protobuf_AddDesc_pixhawk_2eproto() { @@ -189,35 +346,63 @@ void protobuf_AddDesc_pixhawk_2eproto() { GOOGLE_PROTOBUF_VERIFY_VERSION; ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( - "\n\rpixhawk.proto\022\002px\"\177\n\016PointCloudXYZI\022,\n" - "\006points\030\001 \003(\0132\034.px.PointCloudXYZI.PointX" - "YZI\032\?\n\tPointXYZI\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\tintensity\030\004 \002(\002\"\201\001\n\020PointCl" - "oudXYZRGB\0220\n\006points\030\001 \003(\0132 .px.PointClou" - "dXYZRGB.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" - "\"\350\002\n\tRGBDImage\022\014\n\004cols\030\001 \002(\r\022\014\n\004rows\030\002 \002" - "(\r\022\r\n\005step1\030\003 \002(\r\022\r\n\005type1\030\004 \002(\r\022\022\n\nimag" - "eData1\030\005 \002(\014\022\r\n\005step2\030\006 \002(\r\022\r\n\005type2\030\007 \002" - "(\r\022\022\n\nimageData2\030\010 \002(\014\022\025\n\rcamera_config\030" - "\t \001(\r\022\023\n\013camera_type\030\n \001(\r\022\021\n\ttimestamp\030" - "\013 \001(\004\022\014\n\004roll\030\014 \001(\002\022\r\n\005pitch\030\r \001(\002\022\013\n\003ya" - "w\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\010ground_z\030\024 \001(\002\022\025\n\rcamera_matrix\030\025 " - "\003(\002", 643); + "\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\"\237\001\n\016PointCloudXYZI\022\036\n\006" + "header\030\001 \002(\0132\016.px.HeaderInfo\022,\n\006points\030\002" + " \003(\0132\034.px.PointCloudXYZI.PointXYZI\032\?\n\tPo" + "intXYZI\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\tintensity\030\004 \002(\002\"\241\001\n\020PointCloudXYZRGB" + "\022\036\n\006header\030\001 \002(\0132\016.px.HeaderInfo\0220\n\006poin" + "ts\030\002 \003(\0132 .px.PointCloudXYZRGB.PointXYZR" + "GB\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" + "\006header\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\005type" + "1\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" + "\rcamera_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\010ground_z\030\024 \001(\002\022\025\n\rcamera_matrix\030\025 \003(\002\"" + "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\006h" + "eight\030\006 \001(\002\"O\n\014ObstacleList\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\013ObstacleMap\022\036\n\006header\030\001" + " \002(\0132\016.px.HeaderInfo\022\014\n\004type\030\002 \002(\005\022\022\n\nre" + "solution\030\003 \001(\002\022\014\n\004rows\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\007arra" + "yR0\030\010 \001(\005\022\017\n\007arrayC0\030\t \001(\005\022\014\n\004data\030\n \001(\014" + "\"U\n\010Waypoint\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\003ya" + "w\030\006 \001(\001\"G\n\004Path\022\036\n\006header\030\001 \002(\0132\016.px.Hea" + "derInfo\022\037\n\twaypoints\030\002 \003(\0132\014.px.Waypoint", 1320); ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( "pixhawk.proto", &protobuf_RegisterTypes); + HeaderInfo::default_instance_ = new HeaderInfo(); 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(); + Obstacle::default_instance_ = new Obstacle(); + ObstacleList::default_instance_ = new ObstacleList(); + ObstacleMap::default_instance_ = new ObstacleMap(); + Waypoint::default_instance_ = new Waypoint(); + Path::default_instance_ = new Path(); + HeaderInfo::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(); + Obstacle::default_instance_->InitAsDefaultInstance(); + ObstacleList::default_instance_->InitAsDefaultInstance(); + ObstacleMap::default_instance_->InitAsDefaultInstance(); + Waypoint::default_instance_->InitAsDefaultInstance(); + Path::default_instance_->InitAsDefaultInstance(); ::google::protobuf::internal::OnShutdown(&protobuf_ShutdownFile_pixhawk_2eproto); } @@ -229,6 +414,292 @@ struct StaticDescriptorInitializer_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; +} + + // =================================================================== #ifndef _MSC_VER @@ -552,6 +1023,7 @@ void PointCloudXYZI_PointXYZI::Swap(PointCloudXYZI_PointXYZI* other) { // ------------------------------------------------------------------- #ifndef _MSC_VER +const int PointCloudXYZI::kHeaderFieldNumber; const int PointCloudXYZI::kPointsFieldNumber; #endif // !_MSC_VER @@ -561,6 +1033,7 @@ PointCloudXYZI::PointCloudXYZI() } void PointCloudXYZI::InitAsDefaultInstance() { + header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); } PointCloudXYZI::PointCloudXYZI(const PointCloudXYZI& from) @@ -571,6 +1044,7 @@ PointCloudXYZI::PointCloudXYZI(const PointCloudXYZI& from) void PointCloudXYZI::SharedCtor() { _cached_size_ = 0; + header_ = NULL; ::memset(_has_bits_, 0, sizeof(_has_bits_)); } @@ -580,6 +1054,7 @@ PointCloudXYZI::~PointCloudXYZI() { void PointCloudXYZI::SharedDtor() { if (this != default_instance_) { + delete header_; } } @@ -604,6 +1079,11 @@ PointCloudXYZI* PointCloudXYZI::New() const { } 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(); @@ -615,8 +1095,21 @@ bool PointCloudXYZI::MergePartialFromCodedStream( ::google::protobuf::uint32 tag; while ((tag = input->ReadTag()) != 0) { switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // repeated .px.PointCloudXYZI.PointXYZI points = 1; + // 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: @@ -625,7 +1118,7 @@ bool PointCloudXYZI::MergePartialFromCodedStream( } else { goto handle_uninterpreted; } - if (input->ExpectTag(10)) goto parse_points; + if (input->ExpectTag(18)) goto parse_points; if (input->ExpectAtEnd()) return true; break; } @@ -648,10 +1141,16 @@ bool PointCloudXYZI::MergePartialFromCodedStream( void PointCloudXYZI::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // repeated .px.PointCloudXYZI.PointXYZI points = 1; + // 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( - 1, this->points(i), output); + 2, this->points(i), output); } if (!unknown_fields().empty()) { @@ -662,11 +1161,18 @@ void PointCloudXYZI::SerializeWithCachedSizes( ::google::protobuf::uint8* PointCloudXYZI::SerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // repeated .px.PointCloudXYZI.PointXYZI points = 1; + // 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( - 1, this->points(i), target); + 2, this->points(i), target); } if (!unknown_fields().empty()) { @@ -679,7 +1185,16 @@ void PointCloudXYZI::SerializeWithCachedSizes( int PointCloudXYZI::ByteSize() const { int total_size = 0; - // repeated .px.PointCloudXYZI.PointXYZI points = 1; + 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 += @@ -713,6 +1228,11 @@ void PointCloudXYZI::MergeFrom(const ::google::protobuf::Message& from) { 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()); } @@ -729,7 +1249,11 @@ void PointCloudXYZI::CopyFrom(const PointCloudXYZI& 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; } @@ -738,6 +1262,7 @@ bool PointCloudXYZI::IsInitialized() const { 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_); @@ -1077,6 +1602,7 @@ void PointCloudXYZRGB_PointXYZRGB::Swap(PointCloudXYZRGB_PointXYZRGB* other) { // ------------------------------------------------------------------- #ifndef _MSC_VER +const int PointCloudXYZRGB::kHeaderFieldNumber; const int PointCloudXYZRGB::kPointsFieldNumber; #endif // !_MSC_VER @@ -1086,6 +1612,7 @@ PointCloudXYZRGB::PointCloudXYZRGB() } void PointCloudXYZRGB::InitAsDefaultInstance() { + header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); } PointCloudXYZRGB::PointCloudXYZRGB(const PointCloudXYZRGB& from) @@ -1096,6 +1623,7 @@ PointCloudXYZRGB::PointCloudXYZRGB(const PointCloudXYZRGB& from) void PointCloudXYZRGB::SharedCtor() { _cached_size_ = 0; + header_ = NULL; ::memset(_has_bits_, 0, sizeof(_has_bits_)); } @@ -1105,6 +1633,7 @@ PointCloudXYZRGB::~PointCloudXYZRGB() { void PointCloudXYZRGB::SharedDtor() { if (this != default_instance_) { + delete header_; } } @@ -1129,6 +1658,11 @@ PointCloudXYZRGB* PointCloudXYZRGB::New() const { } 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(); @@ -1140,8 +1674,21 @@ bool PointCloudXYZRGB::MergePartialFromCodedStream( ::google::protobuf::uint32 tag; while ((tag = input->ReadTag()) != 0) { switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 1; + // 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: @@ -1150,7 +1697,7 @@ bool PointCloudXYZRGB::MergePartialFromCodedStream( } else { goto handle_uninterpreted; } - if (input->ExpectTag(10)) goto parse_points; + if (input->ExpectTag(18)) goto parse_points; if (input->ExpectAtEnd()) return true; break; } @@ -1173,10 +1720,16 @@ bool PointCloudXYZRGB::MergePartialFromCodedStream( void PointCloudXYZRGB::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 1; + // 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( - 1, this->points(i), output); + 2, this->points(i), output); } if (!unknown_fields().empty()) { @@ -1187,11 +1740,18 @@ void PointCloudXYZRGB::SerializeWithCachedSizes( ::google::protobuf::uint8* PointCloudXYZRGB::SerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 1; + // 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( - 1, this->points(i), target); + 2, this->points(i), target); } if (!unknown_fields().empty()) { @@ -1204,7 +1764,16 @@ void PointCloudXYZRGB::SerializeWithCachedSizes( int PointCloudXYZRGB::ByteSize() const { int total_size = 0; - // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 1; + 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 += @@ -1238,6 +1807,11 @@ void PointCloudXYZRGB::MergeFrom(const ::google::protobuf::Message& from) { 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()); } @@ -1254,7 +1828,11 @@ void PointCloudXYZRGB::CopyFrom(const PointCloudXYZRGB& 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; } @@ -1263,6 +1841,7 @@ bool PointCloudXYZRGB::IsInitialized() const { 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_); @@ -1282,6 +1861,7 @@ void PointCloudXYZRGB::Swap(PointCloudXYZRGB* other) { // =================================================================== #ifndef _MSC_VER +const int RGBDImage::kHeaderFieldNumber; const int RGBDImage::kColsFieldNumber; const int RGBDImage::kRowsFieldNumber; const int RGBDImage::kStep1FieldNumber; @@ -1292,7 +1872,6 @@ const int RGBDImage::kType2FieldNumber; const int RGBDImage::kImageData2FieldNumber; const int RGBDImage::kCameraConfigFieldNumber; const int RGBDImage::kCameraTypeFieldNumber; -const int RGBDImage::kTimestampFieldNumber; const int RGBDImage::kRollFieldNumber; const int RGBDImage::kPitchFieldNumber; const int RGBDImage::kYawFieldNumber; @@ -1311,6 +1890,7 @@ RGBDImage::RGBDImage() } void RGBDImage::InitAsDefaultInstance() { + header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); } RGBDImage::RGBDImage(const RGBDImage& from) @@ -1321,6 +1901,7 @@ RGBDImage::RGBDImage(const RGBDImage& from) void RGBDImage::SharedCtor() { _cached_size_ = 0; + header_ = NULL; cols_ = 0u; rows_ = 0u; step1_ = 0u; @@ -1331,7 +1912,6 @@ void RGBDImage::SharedCtor() { imagedata2_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); camera_config_ = 0u; camera_type_ = 0u; - timestamp_ = GOOGLE_ULONGLONG(0); roll_ = 0; pitch_ = 0; yaw_ = 0; @@ -1356,6 +1936,7 @@ void RGBDImage::SharedDtor() { delete imagedata2_; } if (this != default_instance_) { + delete header_; } } @@ -1381,6 +1962,9 @@ RGBDImage* RGBDImage::New() const { 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; @@ -1392,16 +1976,15 @@ void RGBDImage::Clear() { } step2_ = 0u; type2_ = 0u; + } + if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) { if (has_imagedata2()) { if (imagedata2_ != &::google::protobuf::internal::kEmptyString) { imagedata2_->clear(); } } - } - if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) { camera_config_ = 0u; camera_type_ = 0u; - timestamp_ = GOOGLE_ULONGLONG(0); roll_ = 0; pitch_ = 0; yaw_ = 0; @@ -1425,10 +2008,24 @@ bool RGBDImage::MergePartialFromCodedStream( ::google::protobuf::uint32 tag; while ((tag = input->ReadTag()) != 0) { switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required uint32 cols = 1; + // 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_))); @@ -1436,12 +2033,12 @@ bool RGBDImage::MergePartialFromCodedStream( } else { goto handle_uninterpreted; } - if (input->ExpectTag(16)) goto parse_rows; + if (input->ExpectTag(24)) goto parse_rows; break; } - // required uint32 rows = 2; - case 2: { + // required uint32 rows = 3; + case 3: { if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { parse_rows: @@ -1452,12 +2049,12 @@ bool RGBDImage::MergePartialFromCodedStream( } else { goto handle_uninterpreted; } - if (input->ExpectTag(24)) goto parse_step1; + if (input->ExpectTag(32)) goto parse_step1; break; } - // required uint32 step1 = 3; - case 3: { + // required uint32 step1 = 4; + case 4: { if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { parse_step1: @@ -1468,12 +2065,12 @@ bool RGBDImage::MergePartialFromCodedStream( } else { goto handle_uninterpreted; } - if (input->ExpectTag(32)) goto parse_type1; + if (input->ExpectTag(40)) goto parse_type1; break; } - // required uint32 type1 = 4; - case 4: { + // required uint32 type1 = 5; + case 5: { if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { parse_type1: @@ -1484,12 +2081,12 @@ bool RGBDImage::MergePartialFromCodedStream( } else { goto handle_uninterpreted; } - if (input->ExpectTag(42)) goto parse_imageData1; + if (input->ExpectTag(50)) goto parse_imageData1; break; } - // required bytes imageData1 = 5; - case 5: { + // required bytes imageData1 = 6; + case 6: { if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { parse_imageData1: @@ -1498,12 +2095,12 @@ bool RGBDImage::MergePartialFromCodedStream( } else { goto handle_uninterpreted; } - if (input->ExpectTag(48)) goto parse_step2; + if (input->ExpectTag(56)) goto parse_step2; break; } - // required uint32 step2 = 6; - case 6: { + // required uint32 step2 = 7; + case 7: { if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { parse_step2: @@ -1514,12 +2111,12 @@ bool RGBDImage::MergePartialFromCodedStream( } else { goto handle_uninterpreted; } - if (input->ExpectTag(56)) goto parse_type2; + if (input->ExpectTag(64)) goto parse_type2; break; } - // required uint32 type2 = 7; - case 7: { + // required uint32 type2 = 8; + case 8: { if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { parse_type2: @@ -1530,12 +2127,12 @@ bool RGBDImage::MergePartialFromCodedStream( } else { goto handle_uninterpreted; } - if (input->ExpectTag(66)) goto parse_imageData2; + if (input->ExpectTag(74)) goto parse_imageData2; break; } - // required bytes imageData2 = 8; - case 8: { + // required bytes imageData2 = 9; + case 9: { if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { parse_imageData2: @@ -1544,12 +2141,12 @@ bool RGBDImage::MergePartialFromCodedStream( } else { goto handle_uninterpreted; } - if (input->ExpectTag(72)) goto parse_camera_config; + if (input->ExpectTag(80)) goto parse_camera_config; break; } - // optional uint32 camera_config = 9; - case 9: { + // optional uint32 camera_config = 10; + case 10: { if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { parse_camera_config: @@ -1560,12 +2157,12 @@ bool RGBDImage::MergePartialFromCodedStream( } else { goto handle_uninterpreted; } - if (input->ExpectTag(80)) goto parse_camera_type; + if (input->ExpectTag(88)) goto parse_camera_type; break; } - // optional uint32 camera_type = 10; - case 10: { + // optional uint32 camera_type = 11; + case 11: { if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { parse_camera_type: @@ -1576,22 +2173,6 @@ bool RGBDImage::MergePartialFromCodedStream( } else { goto handle_uninterpreted; } - if (input->ExpectTag(88)) goto parse_timestamp; - break; - } - - // optional uint64 timestamp = 11; - case 11: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_timestamp: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::uint64, ::google::protobuf::internal::WireFormatLite::TYPE_UINT64>( - input, ×tamp_))); - set_has_timestamp(); - } else { - goto handle_uninterpreted; - } if (input->ExpectTag(101)) goto parse_roll; break; } @@ -1780,61 +2361,62 @@ bool RGBDImage::MergePartialFromCodedStream( void RGBDImage::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // required uint32 cols = 1; + // 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(1, this->cols(), output); + ::google::protobuf::internal::WireFormatLite::WriteUInt32(2, this->cols(), output); } - // required uint32 rows = 2; + // required uint32 rows = 3; if (has_rows()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(2, this->rows(), output); + ::google::protobuf::internal::WireFormatLite::WriteUInt32(3, this->rows(), output); } - // required uint32 step1 = 3; + // required uint32 step1 = 4; if (has_step1()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(3, this->step1(), output); + ::google::protobuf::internal::WireFormatLite::WriteUInt32(4, this->step1(), output); } - // required uint32 type1 = 4; + // required uint32 type1 = 5; if (has_type1()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(4, this->type1(), output); + ::google::protobuf::internal::WireFormatLite::WriteUInt32(5, this->type1(), output); } - // required bytes imageData1 = 5; + // required bytes imageData1 = 6; if (has_imagedata1()) { ::google::protobuf::internal::WireFormatLite::WriteBytes( - 5, this->imagedata1(), output); + 6, this->imagedata1(), output); } - // required uint32 step2 = 6; + // required uint32 step2 = 7; if (has_step2()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(6, this->step2(), output); + ::google::protobuf::internal::WireFormatLite::WriteUInt32(7, this->step2(), output); } - // required uint32 type2 = 7; + // required uint32 type2 = 8; if (has_type2()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(7, this->type2(), output); + ::google::protobuf::internal::WireFormatLite::WriteUInt32(8, this->type2(), output); } - // required bytes imageData2 = 8; + // required bytes imageData2 = 9; if (has_imagedata2()) { ::google::protobuf::internal::WireFormatLite::WriteBytes( - 8, this->imagedata2(), output); + 9, this->imagedata2(), output); } - // optional uint32 camera_config = 9; + // optional uint32 camera_config = 10; if (has_camera_config()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(9, this->camera_config(), output); + ::google::protobuf::internal::WireFormatLite::WriteUInt32(10, this->camera_config(), output); } - // optional uint32 camera_type = 10; + // optional uint32 camera_type = 11; if (has_camera_type()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(10, this->camera_type(), output); - } - - // optional uint64 timestamp = 11; - if (has_timestamp()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt64(11, this->timestamp(), output); + ::google::protobuf::internal::WireFormatLite::WriteUInt32(11, this->camera_type(), output); } // optional float roll = 12; @@ -1896,63 +2478,65 @@ void RGBDImage::SerializeWithCachedSizes( ::google::protobuf::uint8* RGBDImage::SerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // required uint32 cols = 1; + // 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(1, this->cols(), target); + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(2, this->cols(), target); } - // required uint32 rows = 2; + // required uint32 rows = 3; if (has_rows()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(2, this->rows(), target); + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(3, this->rows(), target); } - // required uint32 step1 = 3; + // required uint32 step1 = 4; if (has_step1()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(3, this->step1(), target); + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(4, this->step1(), target); } - // required uint32 type1 = 4; + // required uint32 type1 = 5; if (has_type1()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(4, this->type1(), target); + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(5, this->type1(), target); } - // required bytes imageData1 = 5; + // required bytes imageData1 = 6; if (has_imagedata1()) { target = ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( - 5, this->imagedata1(), target); + 6, this->imagedata1(), target); } - // required uint32 step2 = 6; + // required uint32 step2 = 7; if (has_step2()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(6, this->step2(), target); + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(7, this->step2(), target); } - // required uint32 type2 = 7; + // required uint32 type2 = 8; if (has_type2()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(7, this->type2(), target); + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(8, this->type2(), target); } - // required bytes imageData2 = 8; + // required bytes imageData2 = 9; if (has_imagedata2()) { target = ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( - 8, this->imagedata2(), target); + 9, this->imagedata2(), target); } - // optional uint32 camera_config = 9; + // optional uint32 camera_config = 10; if (has_camera_config()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(9, this->camera_config(), target); + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(10, this->camera_config(), target); } - // optional uint32 camera_type = 10; + // optional uint32 camera_type = 11; if (has_camera_type()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(10, this->camera_type(), target); - } - - // optional uint64 timestamp = 11; - if (has_timestamp()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt64ToArray(11, this->timestamp(), target); + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(11, this->camera_type(), target); } // optional float roll = 12; @@ -2017,85 +2601,85 @@ int RGBDImage::ByteSize() const { int total_size = 0; if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required uint32 cols = 1; + // 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 = 2; + // required uint32 rows = 3; if (has_rows()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::UInt32Size( this->rows()); } - // required uint32 step1 = 3; + // required uint32 step1 = 4; if (has_step1()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::UInt32Size( this->step1()); } - // required uint32 type1 = 4; + // required uint32 type1 = 5; if (has_type1()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::UInt32Size( this->type1()); } - // required bytes imageData1 = 5; + // required bytes imageData1 = 6; if (has_imagedata1()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::BytesSize( this->imagedata1()); } - // required uint32 step2 = 6; + // required uint32 step2 = 7; if (has_step2()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::UInt32Size( this->step2()); } - // required uint32 type2 = 7; + // required uint32 type2 = 8; if (has_type2()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::UInt32Size( this->type2()); } - // required bytes imageData2 = 8; + } + 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()); } - } - if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) { - // optional uint32 camera_config = 9; + // optional uint32 camera_config = 10; if (has_camera_config()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::UInt32Size( this->camera_config()); } - // optional uint32 camera_type = 10; + // optional uint32 camera_type = 11; if (has_camera_type()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::UInt32Size( this->camera_type()); } - // optional uint64 timestamp = 11; - if (has_timestamp()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::UInt64Size( - this->timestamp()); - } - // optional float roll = 12; if (has_roll()) { total_size += 1 + 4; @@ -2178,6 +2762,9 @@ 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()); } @@ -2199,20 +2786,17 @@ void RGBDImage::MergeFrom(const RGBDImage& from) { 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_bits_[8 / 32] & (0xffu << (8 % 32))) { 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_timestamp()) { - set_timestamp(from.timestamp()); - } if (from.has_roll()) { set_roll(from.roll()); } @@ -2259,13 +2843,17 @@ void RGBDImage::CopyFrom(const RGBDImage& from) { } bool RGBDImage::IsInitialized() const { - if ((_has_bits_[0] & 0x000000ff) != 0x000000ff) return false; + 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_); @@ -2276,7 +2864,6 @@ void RGBDImage::Swap(RGBDImage* other) { std::swap(imagedata2_, other->imagedata2_); std::swap(camera_config_, other->camera_config_); std::swap(camera_type_, other->camera_type_); - std::swap(timestamp_, other->timestamp_); std::swap(roll_, other->roll_); std::swap(pitch_, other->pitch_); std::swap(yaw_, other->yaw_); @@ -2302,6 +2889,1900 @@ void RGBDImage::Swap(RGBDImage* other) { } +// =================================================================== + +#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 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; +} + + +// =================================================================== + +#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; +} + + // @@protoc_insertion_point(namespace_scope) } // namespace px