Commit c7deeaa8 authored by hengli's avatar hengli

Disable references to pixhawk protoc files if pixhawk is not included in MAVLINK_CONF.

parent 1f491fff
......@@ -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) {
......
......@@ -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<google::protobuf::Message> protobuf_msg;
......@@ -262,6 +264,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
}
}
}
#endif
position += extended_message.extended_payload_len;
......
......@@ -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 <tr1/memory>
#include <google/protobuf/message.h>
#if defined(QGC_USE_PIXHAWK_MESSAGES)
#include <mavlink_protobuf_manager.hpp>
#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<google::protobuf::Message> message);
#endif
......
......@@ -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<google::protobuf::Message> message)
{
UAS::receiveExtendedMessage(link, message);
......
......@@ -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<google::protobuf::Message> message);
#endif
......
......@@ -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),
......@@ -1022,7 +1022,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<google::protobuf::Message> message)
{
if (!link)
......@@ -1069,6 +1069,7 @@ void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<googl
return;
}
#ifdef QGC_USE_PIXHAWK_MESSAGES
if (message->GetTypeName() == pointCloud.GetTypeName())
{
receivedPointCloudTimestamp = QGC::groundTimeSeconds();
......@@ -1101,6 +1102,7 @@ void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<googl
pathMutex.unlock();
emit pathChanged(this);
}
#endif
}
#endif
......
......@@ -134,7 +134,7 @@ public:
}
bool getSelected() const;
#ifdef QGC_PROTOBUF_ENABLED
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
px::PointCloudXYZRGB getPointCloud() {
QMutexLocker locker(&pointCloudMutex);
return pointCloud;
......@@ -263,7 +263,7 @@ protected: //COMMENTS FOR TEST UNIT
QImage image; ///< Image data of last completely transmitted image
quint64 imageStart;
#ifdef QGC_PROTOBUF_ENABLED
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
px::PointCloudXYZRGB pointCloud;
QMutex pointCloudMutex;
qreal receivedPointCloudTimestamp;
......@@ -610,7 +610,7 @@ signals:
void imageStarted(quint64 timestamp);
/** @brief A new camera image has arrived */
void imageReady(UASInterface* uas);
#ifdef QGC_PROTOBUF_ENABLED
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
/** @brief Point cloud data has been changed */
void pointCloudChanged(UASInterface* uas);
/** @brief RGBD image data has been changed */
......
......@@ -46,8 +46,10 @@ This file is part of the QGROUNDCONTROL project
#ifdef QGC_PROTOBUF_ENABLED
#include <tr1/memory>
#ifdef QGC_USE_PIXHAWK_MESSAGES
#include <pixhawk/pixhawk.pb.h>
#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;
......
......@@ -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))
......
......@@ -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 <tr1/memory>
#include <pixhawk/pixhawk.pb.h>
#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)
{
......
......@@ -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> waypointGroupNode;
osg::ref_ptr<osg::Node> targetNode;
osg::ref_ptr<osg::Geode> rgbd3DNode;
#ifdef QGC_PROTOBUF_ENABLED
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
osg::ref_ptr<ObstacleGroupNode> obstacleGroupNode;
osg::ref_ptr<osg::Geode> pathNode;
#endif
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment