Browse Source

Merge branch 'master' of github.com:mavlink/qgroundcontrol

QGC4.4
LM 13 years ago
parent
commit
ec6036477a
  1. 43
      README
  2. 12
      READMEvc2010.txt
  3. 3
      qgcunittest.pro
  4. 64
      qgroundcontrol.pri
  5. 10
      qgroundcontrol.pro
  6. 45
      src/uas/UAS.cc
  7. 75
      src/uas/UAS.h
  8. 23
      src/uas/UASInterface.h
  9. 427
      src/ui/map3D/GLOverlayGeode.cc
  10. 49
      src/ui/map3D/GLOverlayGeode.h
  11. 65
      src/ui/map3D/Pixhawk3DWidget.cc
  12. 5
      src/ui/map3D/Pixhawk3DWidget.h
  13. 6
      src/ui/map3D/SystemContainer.cc
  14. 3
      src/ui/map3D/SystemContainer.h
  15. 23
      src/ui/map3D/SystemViewParams.cc
  16. 6
      src/ui/map3D/SystemViewParams.h
  17. 34
      src/ui/map3D/ViewParamWidget.cc
  18. 6
      src/ui/map3D/ViewParamWidget.h
  19. 30
      thirdParty/mavlink/include/mavlink_protobuf_manager.hpp
  20. 3805
      thirdParty/mavlink/include/pixhawk/pixhawk.pb.h
  21. 139
      thirdParty/mavlink/message_definitions/pixhawk.proto
  22. 83
      thirdParty/mavlink/message_definitions/sensesoar.xml
  23. 4951
      thirdParty/mavlink/src/pixhawk/pixhawk.pb.cc

43
README

@ -78,52 +78,25 @@ Done. @@ -78,52 +78,25 @@ Done.
Windows
=======
DETAILED STEPS BELOW THE VISUAL STUDIO 2010 NOTES.
GNU GCC / MINGW IS UNTESTED, COULD WORK
VISUAL STUDIO 2008 / 2010 EXPRESS EDITION IS FREE!
-------------------------------------------------------------------------------------
VISUAL STUDIO 2010 NOTES (VS 2008 runs out-of-the-box, just follow the steps below):
For use of Qt 4x with Visual Studio 2010 Add-in.
Visual studio adds automatically certain defines that are wrong and cause errors.
To resolve this, execute these steps:
In the projects properties -> C/C++ ->preprocessor change:
in DEBUG:
delete QT_NO_DEBUG
in both (DEBUG / RELEASE):
delete QT_NO_DYNAMIC_CAST
-------------------------------------------------------------------------------------
Steps for Visual Studio 2008 / 2010. (VS 2008 is easier, VS 2010 only recommended for
expert developers)
Steps for Visual Studio 2008 / 2010:
Windows XP/7:
1) Download and install the Qt SDK for Windows from http://qt.nokia.com/downloads/ (Visual Studio 2008 version) OR download Qt source and compile with VS 2010
2) Download and install Visual Studio 2008 Express Edition (free) OR VS 2010 Express Edition
3) Go to the QGroundControl folder and then to thirdParty -> libxbee
1) Download and install the Qt libraries for Windows from https://qt.nokia.com/downloads/ (the Visual Studio 2008 or 2010 version as appropriate)
4) Build the library. See win32.README
2) Download and install Visual Studio 2008 or 2010 Express Edition (free) from https://www.microsoft.com/visualstudio
5) Go to the source folder of QGroundControl with the Qt 4.7.x Command Prompt tool (from the applications menu)
3) Go to the QGroundControl folder and then to thirdParty/libxbee and build it following the instructions in win32.README
6) Create the Visual Studio project by typing:
4) Open the Qt Command Prompt program (should be in the Start Menu), navigate to the source folder of QGroundControl and create the Visual Studio project by typing:
qmake -tp vc qgroundcontrol.pro
`qmake -tp vc qgroundcontrol.pro`
7) Now start Visual Studio and load the qgroundcontrol.vcproj file
5) Now start Visual Studio and load the qgroundcontrol.vcproj if using Visual Studio 2008 or qgroundcontrol.vcxproj if using Visual Studio 2010
8) Compile and edit in Visual Studio. If you need to add new files, add them to qgroundcontrol.pro and re-run "quake -tp vc qgroundcontrol.pro"
6) Compile and edit in Visual Studio. If you need to add new files, add them to qgroundcontrol.pro and re-run `qmake -tp vc qgroundcontrol.pro`

12
READMEvc2010.txt

@ -1,12 +0,0 @@ @@ -1,12 +0,0 @@
For use of qt 4x and visual studio2010 and add in.
The Visual studio adds automatically certain defines
In the projects properties -> C/C++ ->preprocessor change:
in DEBUG:
delete QT_NO_DEBUG
Both:
delete QT_NO_DYNAMIC_CAST

3
qgcunittest.pro

@ -141,7 +141,4 @@ HEADERS += src/uas/UASInterface.h \ @@ -141,7 +141,4 @@ HEADERS += src/uas/UASInterface.h \
src/uas/QGCMAVLinkUASFactory.h
DEFINES += SRCDIR=\\\"$$PWD/\\\"

64
qgroundcontrol.pri

@ -20,13 +20,6 @@ @@ -20,13 +20,6 @@
message(Qt version $$[QT_VERSION])
message(Using Qt from $$(QTDIR))
release {
# DEFINES += QT_NO_DEBUG_OUTPUT
# DEFINES += QT_NO_WARNING_OUTPUT
}
win32-msvc2008|win32-msvc2010 {
QMAKE_POST_LINK += $$quote(echo "Copying files"$$escape_expand(\\n))
} else {
@ -39,38 +32,11 @@ DEFINES += _TTY_NOWARN_ @@ -39,38 +32,11 @@ DEFINES += _TTY_NOWARN_
# MAC OS X
macx|macx-g++42|macx-g++: {
# COMPILER_VERSION = $$system(gcc -v)
#message(Using compiler $$COMPILER_VERSION)
CONFIG += x86_64 cocoa phonon
CONFIG -= x86
#HARDWARE_PLATFORM = $$system(uname -a)
#contains( $$HARDWARE_PLATFORM, "9.6.0" ) || contains( $$HARDWARE_PLATFORM, "9.7.0" ) || contains( $$HARDWARE_PLATFORM, "9.8.0" ) || contains( $$HARDWARE_PLATFORM, "9.9.0" ) {
# x86 Mac OS X Leopard 10.5 and earlier
#message(Building for Mac OS X 32bit/Leopard 10.5 and earlier)
# Enable function-profiling with the OS X saturn tool
#debug {
#QMAKE_CXXFLAGS += -finstrument-functions
#LIBS += -lSaturn
# CONFIG += console
#}
#} else {
# x64 Mac OS X Snow Leopard 10.6 and later
# CONFIG += x86_64 x86 cocoa phonon
#CONFIG -= x86 # phonon
#message(Building for Mac OS X 64bit/Snow Leopard 10.6 and later)
# debug {
#QMAKE_CXXFLAGS += -finstrument-functions
#LIBS += -lSaturn
# }
#}
QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.6
#DESTDIR = $$BASEDIR/bin/mac
INCLUDEPATH += -framework SDL
LIBS += -framework IOKit \
@ -150,11 +116,6 @@ macx|macx-g++42|macx-g++: { @@ -150,11 +116,6 @@ macx|macx-g++42|macx-g++: {
# CORE OSG LIBRARY
QMAKE_POST_LINK += && install_name_tool -change libOpenThreads.dylib "@executable_path/../libs/libOpenThreads.dylib" $$TARGETDIR/qgroundcontrol.app/Contents/libs/libosg.dylib
# Copy model files
#QMAKE_POST_LINK += && cp -f $$BASEDIR/models/*.dae $$TARGETDIR/qgroundcontrol.app/Contents/MacOs
#exists(/Library/Frameworks/osg.framework):exists(/Library/Frameworks/OpenThreads.framework) {
# No check for GLUT.framework since it's a MAC default
message("Building support for OpenSceneGraph")
DEPENDENCIES_PRESENT += osg
@ -174,7 +135,6 @@ macx|macx-g++42|macx-g++: { @@ -174,7 +135,6 @@ macx|macx-g++42|macx-g++: {
-losgDB \
-losgText \
-losgWidget
#}
exists(/usr/local/include/google/protobuf) {
message("Building support for Protocol Buffers")
@ -202,17 +162,10 @@ linux-g++|linux-g++-64{ @@ -202,17 +162,10 @@ linux-g++|linux-g++-64{
CONFIG -= console
debug {
#CONFIG += debug console
}
release {
DEFINES += QT_NO_DEBUG
#CONFIG -= console
}
#QMAKE_POST_LINK += cp -rf $$BASEDIR/audio $$DESTDIR/.
INCLUDEPATH += /usr/include \
/usr/local/include \
/usr/include/qt4/phonon
@ -295,7 +248,7 @@ linux-g++-64 { @@ -295,7 +248,7 @@ linux-g++-64 {
}
}
# Windows (32bit)
# Windows (32bit), Visual Studio
win32-msvc2008|win32-msvc2010 {
win32-msvc2008 {
@ -316,19 +269,19 @@ win32-msvc2008|win32-msvc2010 { @@ -316,19 +269,19 @@ win32-msvc2008|win32-msvc2010 {
# QWebkit is not needed on MS-Windows compilation environment
CONFIG -= webkit
release {
CONFIG -= console
# For release builds remove support for various Qt debugging macros.
CONFIG(release, debug|release) {
DEFINES += QT_NO_DEBUG
}
debug {
# For debug releases we just want the debugging console.
CONFIG(debug, debug|release) {
CONFIG += console
}
INCLUDEPATH += $$BASEDIR/lib/sdl/msvc/include \
$$BASEDIR/lib/opal/include \
$$BASEDIR/lib/msinttypes
#"C:\Program Files\Microsoft SDKs\Windows\v7.0\Include"
LIBS += -L$$BASEDIR/lib/sdl/msvc/lib \
-lSDLmain -lSDL \
@ -357,7 +310,6 @@ DEFINES += QGC_OSG_ENABLED @@ -357,7 +310,6 @@ DEFINES += QGC_OSG_ENABLED
BASEDIR_WIN = $$replace(BASEDIR,"/","\\")
TARGETDIR_WIN = $$replace(TARGETDIR,"/","\\")
CONFIG(debug, debug|release) {
QMAKE_POST_LINK += $$quote(xcopy /D /Y "$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /D /Y "$$BASEDIR_WIN\\files" "$$TARGETDIR_WIN\\debug\\files" /E /I $$escape_expand(\\n))
@ -415,8 +367,7 @@ win32-g++ { @@ -415,8 +367,7 @@ win32-g++ {
DEFINES += NOMINMAX
INCLUDEPATH += $$BASEDIR/lib/sdl/include \
$$BASEDIR/lib/opal/include #\ #\
#"C:\Program Files\Microsoft SDKs\Windows\v7.0\Include"
$$BASEDIR/lib/opal/include
LIBS += -L$$BASEDIR/lib/sdl/win32 \
-lmingw32 -lSDLmain -lSDL -mwindows \
@ -427,14 +378,12 @@ win32-g++ { @@ -427,14 +378,12 @@ win32-g++ {
debug {
#DESTDIR = $$BUILDDIR/debug
CONFIG += console
}
release {
CONFIG -= console
DEFINES += QT_NO_DEBUG
#DESTDIR = $$BUILDDIR/release
}
RC_FILE = $$BASEDIR/qgroundcontrol.rc
@ -482,4 +431,3 @@ win32-g++ { @@ -482,4 +431,3 @@ win32-g++ {
# see http://osgearth.org/wiki/FAQ for details.
QMAKE_CXXFLAGS += -Wl,-E
}
# vim:ts=4:sw=4:expandtab

10
qgroundcontrol.pro

@ -398,7 +398,8 @@ contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) { @@ -398,7 +398,8 @@ contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) {
# Enable only if protobuf is available
HEADERS += thirdParty/mavlink/include/pixhawk/pixhawk.pb.h \
src/ui/map3D/ObstacleGroupNode.h
src/ui/map3D/ObstacleGroupNode.h \
src/ui/map3D/GLOverlayGeode.h
}
contains(DEPENDENCIES_PRESENT, libfreenect) {
message("Including headers for libfreenect")
@ -535,6 +536,7 @@ contains(DEPENDENCIES_PRESENT, osg) { @@ -535,6 +536,7 @@ contains(DEPENDENCIES_PRESENT, osg) {
src/ui/map3D/HUDScaleGeode.cc \
src/ui/map3D/WaypointGroupNode.cc \
src/ui/map3D/TerrainParamDialog.cc
contains(DEPENDENCIES_PRESENT, osgearth) {
message("Including sources for osgEarth")
@ -547,7 +549,8 @@ contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) { @@ -547,7 +549,8 @@ contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) {
# Enable only if protobuf is available
SOURCES += thirdParty/mavlink/src/pixhawk/pixhawk.pb.cc \
src/ui/map3D/ObstacleGroupNode.cc
src/ui/map3D/ObstacleGroupNode.cc \
src/ui/map3D/GLOverlayGeode.cc
}
contains(DEPENDENCIES_PRESENT, libfreenect) {
message("Including sources for libfreenect")
@ -596,8 +599,7 @@ win32-msvc2008|win32-msvc2010|linux{ @@ -596,8 +599,7 @@ win32-msvc2008|win32-msvc2010|linux{
src/ui/XbeeConfigurationWindow.cpp
DEFINES += XBEELINK
INCLUDEPATH += thirdParty/libxbee
# TO DO: build library when it does not exists already
# TO DO: build library when it does not exist already
LIBS += -LthirdParty/libxbee/lib \
-llibxbee
}

45
src/uas/UAS.cc

@ -79,10 +79,11 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), @@ -79,10 +79,11 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
yaw(0.0),
statusTimeout(new QTimer(this)),
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
receivedPointCloudTimestamp(0.0),
receivedRGBDImageTimestamp(0.0),
receivedOverlayTimestamp(0.0),
receivedObstacleListTimestamp(0.0),
receivedPathTimestamp(0.0),
receivedPointCloudTimestamp(0.0),
receivedRGBDImageTimestamp(0.0),
#endif
paramsOnceRequested(false),
airframe(QGC_AIRFRAME_EASYSTAR),
@ -1146,21 +1147,13 @@ void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<googl @@ -1146,21 +1147,13 @@ void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<googl
}
#ifdef QGC_USE_PIXHAWK_MESSAGES
if (message->GetTypeName() == pointCloud.GetTypeName())
if (message->GetTypeName() == overlay.GetTypeName())
{
receivedPointCloudTimestamp = QGC::groundTimeSeconds();
pointCloudMutex.lock();
pointCloud.CopyFrom(*message);
pointCloudMutex.unlock();
emit pointCloudChanged(this);
}
else if (message->GetTypeName() == rgbdImage.GetTypeName())
{
receivedRGBDImageTimestamp = QGC::groundTimeSeconds();
rgbdImageMutex.lock();
rgbdImage.CopyFrom(*message);
rgbdImageMutex.unlock();
emit rgbdImageChanged(this);
receivedOverlayTimestamp = QGC::groundTimeSeconds();
overlayMutex.lock();
overlay.CopyFrom(*message);
overlayMutex.unlock();
emit overlayChanged(this);
}
else if (message->GetTypeName() == obstacleList.GetTypeName())
{
@ -1178,6 +1171,22 @@ void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<googl @@ -1178,6 +1171,22 @@ void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<googl
pathMutex.unlock();
emit pathChanged(this);
}
else if (message->GetTypeName() == pointCloud.GetTypeName())
{
receivedPointCloudTimestamp = QGC::groundTimeSeconds();
pointCloudMutex.lock();
pointCloud.CopyFrom(*message);
pointCloudMutex.unlock();
emit pointCloudChanged(this);
}
else if (message->GetTypeName() == rgbdImage.GetTypeName())
{
receivedRGBDImageTimestamp = QGC::groundTimeSeconds();
rgbdImageMutex.lock();
rgbdImage.CopyFrom(*message);
rgbdImageMutex.unlock();
emit rgbdImageChanged(this);
}
#endif
}
@ -2350,9 +2359,7 @@ void UAS::shutdown() @@ -2350,9 +2359,7 @@ void UAS::shutdown()
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_NAV_PATHPLANNING, 1, 1, 0, 0, yaw, x, y, z);
sendMessage(msg);
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_NAV_PATHPLANNING, 1, 0, 1, 0, yaw, x, y, z);
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_NAV_PATHPLANNING, 1, 1, 1, 0, yaw, x, y, z);
sendMessage(msg);
}

75
src/uas/UAS.h

@ -137,26 +137,15 @@ public: @@ -137,26 +137,15 @@ public:
bool getSelected() const;
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
px::PointCloudXYZRGB getPointCloud() {
QMutexLocker locker(&pointCloudMutex);
return pointCloud;
px::GLOverlay getOverlay() {
QMutexLocker locker(&overlayMutex);
return overlay;
}
px::PointCloudXYZRGB getPointCloud(qreal& receivedTimestamp) {
receivedTimestamp = receivedPointCloudTimestamp;
QMutexLocker locker(&pointCloudMutex);
return pointCloud;
}
px::RGBDImage getRGBDImage() {
QMutexLocker locker(&rgbdImageMutex);
return rgbdImage;
}
px::RGBDImage getRGBDImage(qreal& receivedTimestamp) {
receivedTimestamp = receivedRGBDImageTimestamp;
QMutexLocker locker(&rgbdImageMutex);
return rgbdImage;
px::GLOverlay getOverlay(qreal& receivedTimestamp) {
receivedTimestamp = receivedOverlayTimestamp;
QMutexLocker locker(&overlayMutex);
return overlay;
}
px::ObstacleList getObstacleList() {
@ -180,6 +169,28 @@ public: @@ -180,6 +169,28 @@ public:
QMutexLocker locker(&pathMutex);
return path;
}
px::PointCloudXYZRGB getPointCloud() {
QMutexLocker locker(&pointCloudMutex);
return pointCloud;
}
px::PointCloudXYZRGB getPointCloud(qreal& receivedTimestamp) {
receivedTimestamp = receivedPointCloudTimestamp;
QMutexLocker locker(&pointCloudMutex);
return pointCloud;
}
px::RGBDImage getRGBDImage() {
QMutexLocker locker(&rgbdImageMutex);
return rgbdImage;
}
px::RGBDImage getRGBDImage(qreal& receivedTimestamp) {
receivedTimestamp = receivedRGBDImageTimestamp;
QMutexLocker locker(&rgbdImageMutex);
return rgbdImage;
}
#endif
friend class UASWaypointManager;
@ -270,13 +281,9 @@ protected: //COMMENTS FOR TEST UNIT @@ -270,13 +281,9 @@ protected: //COMMENTS FOR TEST UNIT
quint64 imageStart;
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
px::PointCloudXYZRGB pointCloud;
QMutex pointCloudMutex;
qreal receivedPointCloudTimestamp;
px::RGBDImage rgbdImage;
QMutex rgbdImageMutex;
qreal receivedRGBDImageTimestamp;
px::GLOverlay overlay;
QMutex overlayMutex;
qreal receivedOverlayTimestamp;
px::ObstacleList obstacleList;
QMutex obstacleListMutex;
@ -285,6 +292,14 @@ protected: //COMMENTS FOR TEST UNIT @@ -285,6 +292,14 @@ protected: //COMMENTS FOR TEST UNIT
px::Path path;
QMutex pathMutex;
qreal receivedPathTimestamp;
px::PointCloudXYZRGB pointCloud;
QMutex pointCloudMutex;
qreal receivedPointCloudTimestamp;
px::RGBDImage rgbdImage;
QMutex rgbdImageMutex;
qreal receivedRGBDImageTimestamp;
#endif
QMap<int, QMap<QString, QVariant>* > parameters; ///< All parameters
@ -616,16 +631,6 @@ signals: @@ -616,16 +631,6 @@ signals:
void imageStarted(quint64 timestamp);
/** @brief A new camera image has arrived */
void imageReady(UASInterface* uas);
#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 */
void rgbdImageChanged(UASInterface* uas);
/** @brief Obstacle list data has been changed */
void obstacleListChanged(UASInterface* uas);
/** @brief Path data has been changed */
void pathChanged(UASInterface* uas);
#endif
/** @brief HIL controls have changed */
void hilControlsChanged(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode);

23
src/uas/UASInterface.h

@ -97,14 +97,16 @@ public: @@ -97,14 +97,16 @@ public:
virtual bool getSelected() const = 0;
#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;
virtual px::RGBDImage getRGBDImage(qreal& receivedTimestamp) = 0;
virtual px::GLOverlay getOverlay() = 0;
virtual px::GLOverlay getOverlay(qreal& receivedTimestamp) = 0;
virtual px::ObstacleList getObstacleList() = 0;
virtual px::ObstacleList getObstacleList(qreal& receivedTimestamp) = 0;
virtual px::Path getPath() = 0;
virtual px::Path getPath(qreal& receivedTimestamp) = 0;
virtual px::PointCloudXYZRGB getPointCloud() = 0;
virtual px::PointCloudXYZRGB getPointCloud(qreal& receivedTimestamp) = 0;
virtual px::RGBDImage getRGBDImage() = 0;
virtual px::RGBDImage getRGBDImage(qreal& receivedTimestamp) = 0;
#endif
virtual bool isArmed() const = 0;
@ -489,6 +491,19 @@ signals: @@ -489,6 +491,19 @@ signals:
/** @brief Radio Calibration Data has been received from the MAV*/
void radioCalibrationReceived(const QPointer<RadioCalibrationData>&);
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
/** @brief Overlay data has been changed */
void overlayChanged(UASInterface* uas);
/** @brief Obstacle list data has been changed */
void obstacleListChanged(UASInterface* uas);
/** @brief Path data has been changed */
void pathChanged(UASInterface* uas);
/** @brief Point cloud data has been changed */
void pointCloudChanged(UASInterface* uas);
/** @brief RGBD image data has been changed */
void rgbdImageChanged(UASInterface* uas);
#endif
/**
* @brief Localization quality changed
* @param fix 0: lost, 1: 2D local position hold, 2: 2D localization, 3: 3D localization

427
src/ui/map3D/GLOverlayGeode.cc

@ -0,0 +1,427 @@ @@ -0,0 +1,427 @@
#include "GLOverlayGeode.h"
GLOverlayGeode::GLOverlayGeode()
: mDrawable(new GLOverlayDrawable)
, mMessageTimestamp(0.0)
{
addDrawable(mDrawable);
}
void
GLOverlayGeode::setOverlay(px::GLOverlay &overlay)
{
mDrawable->setOverlay(overlay);
mCoordinateFrameType = overlay.coordinateframetype();
dirtyBound();
}
px::GLOverlay::CoordinateFrameType
GLOverlayGeode::coordinateFrameType(void) const
{
return mCoordinateFrameType;
}
void
GLOverlayGeode::setMessageTimestamp(qreal timestamp)
{
mMessageTimestamp = timestamp;
}
qreal
GLOverlayGeode::messageTimestamp(void) const
{
return mMessageTimestamp;
}
GLOverlayGeode::GLOverlayDrawable::GLOverlayDrawable()
{
setUseDisplayList(true);
}
GLOverlayGeode::GLOverlayDrawable::GLOverlayDrawable(const GLOverlayDrawable& drawable,
const osg::CopyOp& copyop)
: osg::Drawable(drawable,copyop)
{
setUseDisplayList(true);
}
void
GLOverlayGeode::GLOverlayDrawable::setOverlay(px::GLOverlay &overlay)
{
if (!overlay.IsInitialized())
{
return;
}
mOverlay = overlay;
mBBox.init();
const std::string& data = mOverlay.data();
for (size_t i = 0; i < data.size(); ++i)
{
switch (data.at(i)) {
case px::GLOverlay::POINTS:
break;
case px::GLOverlay::LINES:
break;
case px::GLOverlay::LINE_STRIP:
break;
case px::GLOverlay::LINE_LOOP:
break;
case px::GLOverlay::TRIANGLES:
break;
case px::GLOverlay::TRIANGLE_STRIP:
break;
case px::GLOverlay::TRIANGLE_FAN:
break;
case px::GLOverlay::QUADS:
break;
case px::GLOverlay::QUAD_STRIP:
break;
case px::GLOverlay::POLYGON:
break;
case px::GLOverlay::WIRE_CIRCLE:
i += sizeof(float) * 4;
break;
case px::GLOverlay::SOLID_CIRCLE:
i += sizeof(float) * 4;
break;
case px::GLOverlay::SOLID_CUBE:
i += sizeof(float) * 5;
break;
case px::GLOverlay::WIRE_CUBE:
i += sizeof(float) * 5;
break;
case px::GLOverlay::END:
break;
case px::GLOverlay::VERTEX2F:
i += sizeof(float) * 2;
break;
case px::GLOverlay::VERTEX3F:
{
float x = getFloatValue(data, i);
float y = getFloatValue(data, i);
float z = getFloatValue(data, i);
mBBox.expandBy(x, y, z);
}
break;
case px::GLOverlay::ROTATEF:
i += sizeof(float) * 4;
break;
case px::GLOverlay::TRANSLATEF:
i += sizeof(float) * 3;
break;
case px::GLOverlay::SCALEF:
i += sizeof(float) * 3;
break;
case px::GLOverlay::PUSH_MATRIX:
break;
case px::GLOverlay::POP_MATRIX:
break;
case px::GLOverlay::COLOR3F:
i += sizeof(float) * 3;
break;
case px::GLOverlay::COLOR4F:
i += sizeof(float) * 4;
break;
case px::GLOverlay::POINTSIZE:
i += sizeof(float);
break;
case px::GLOverlay::LINEWIDTH:
i += sizeof(float);
break;
}
}
dirtyDisplayList();
}
void
GLOverlayGeode::GLOverlayDrawable::drawImplementation(osg::RenderInfo&) const
{
if (!mOverlay.IsInitialized())
{
return;
}
glPushMatrix();
glScalef(-1.0f, 1.0f, 1.0f);
glRotatef(90.0f, 0.0f, 0.0f, 1.0f);
const std::string& data = mOverlay.data();
for (size_t i = 0; i < data.size(); ++i)
{
switch (data.at(i)) {
case px::GLOverlay::POINTS:
glBegin(GL_POINTS);
break;
case px::GLOverlay::LINES:
glBegin(GL_LINES);
break;
case px::GLOverlay::LINE_STRIP:
glBegin(GL_LINE_STRIP);
break;
case px::GLOverlay::LINE_LOOP:
glBegin(GL_LINE_LOOP);
break;
case px::GLOverlay::TRIANGLES:
glBegin(GL_TRIANGLES);
break;
case px::GLOverlay::TRIANGLE_STRIP:
glBegin(GL_TRIANGLE_STRIP);
break;
case px::GLOverlay::TRIANGLE_FAN:
glBegin(GL_TRIANGLE_FAN);
break;
case px::GLOverlay::QUADS:
glBegin(GL_QUADS);
break;
case px::GLOverlay::QUAD_STRIP:
glBegin(GL_QUAD_STRIP);
break;
case px::GLOverlay::POLYGON:
glBegin(GL_POLYGON);
break;
case px::GLOverlay::WIRE_CIRCLE:
{
float x = getFloatValue(data, i);
float y = getFloatValue(data, i);
float z = getFloatValue(data, i);
float r = getFloatValue(data, i);
glBegin(GL_LINE_LOOP);
for (int i = 0; i < 20; i++)
{
float angle = i / 20.0f * M_PI * 2.0f;
glVertex3f(x + r * cosf(angle), y + r * sinf(angle), z);
}
glEnd();
}
break;
case px::GLOverlay::SOLID_CIRCLE:
{
float x = getFloatValue(data, i);
float y = getFloatValue(data, i);
float z = getFloatValue(data, i);
float r = getFloatValue(data, i);
glBegin(GL_POLYGON);
for (int i = 0; i < 20; i++)
{
float angle = i / 20.0f * M_PI * 2.0f;
glVertex3f(x + r * cosf(angle), y + r * sinf(angle), z);
}
glEnd();
}
break;
case px::GLOverlay::SOLID_CUBE:
{
float x = getFloatValue(data, i);
float y = getFloatValue(data, i);
float z = getFloatValue(data, i);
float w = getFloatValue(data, i);
float h = getFloatValue(data, i);
float w_2 = w / 2.0f;
float h_2 = h / 2.0f;
glBegin(GL_QUADS);
// face 1
glNormal3f(1.0f, 0.0f, 0.0f);
glVertex3f(x + w_2, y - w_2, z + h_2);
glVertex3f(x + w_2, y - w_2, z - h_2);
glVertex3f(x + w_2, y + w_2, z - h_2);
glVertex3f(x + w_2, y + w_2, z + h_2);
// face 2
glNormal3f(0.0f, 1.0f, 0.0f);
glVertex3f(x + w_2, y + w_2, z + h_2);
glVertex3f(x + w_2, y + w_2, z - h_2);
glVertex3f(x - w_2, y + w_2, z - h_2);
glVertex3f(x - w_2, y + w_2, z + h_2);
// face 3
glNormal3f(0.0f, 0.0f, 1.0f);
glVertex3f(x + w_2, y + w_2, z + h_2);
glVertex3f(x - w_2, y + w_2, z + h_2);
glVertex3f(x - w_2, y - w_2, z + h_2);
glVertex3f(x + w_2, y - w_2, z + h_2);
// face 4
glNormal3f(-1.0f, 0.0f, 0.0f);
glVertex3f(x - w_2, y - w_2, z + h_2);
glVertex3f(x - w_2, y + w_2, z + h_2);
glVertex3f(x - w_2, y + w_2, z - h_2);
glVertex3f(x - w_2, y - w_2, z - h_2);
// face 5
glNormal3f(0.0f, -1.0f, 0.0f);
glVertex3f(x - w_2, y - w_2, z + h_2);
glVertex3f(x - w_2, y - w_2, z - h_2);
glVertex3f(x + w_2, y - w_2, z - h_2);
glVertex3f(x + w_2, y - w_2, z + h_2);
// face 6
glNormal3f(0.0f, 0.0f, -1.0f);
glVertex3f(x - w_2, y - w_2, z - h_2);
glVertex3f(x - w_2, y + w_2, z - h_2);
glVertex3f(x + w_2, y + w_2, z - h_2);
glVertex3f(x + w_2, y - w_2, z - h_2);
glEnd();
}
break;
case px::GLOverlay::WIRE_CUBE:
{
float x = getFloatValue(data, i);
float y = getFloatValue(data, i);
float z = getFloatValue(data, i);
float w = getFloatValue(data, i);
float h = getFloatValue(data, i);
float w_2 = w / 2.0f;
float h_2 = h / 2.0f;
// face 1
glBegin(GL_LINE_LOOP);
glVertex3f(x + w_2, y - w_2, z + h_2);
glVertex3f(x + w_2, y - w_2, z - h_2);
glVertex3f(x + w_2, y + w_2, z - h_2);
glVertex3f(x + w_2, y + w_2, z + h_2);
glEnd();
// face 2
glBegin(GL_LINE_LOOP);
glVertex3f(x + w_2, y + w_2, z + h_2);
glVertex3f(x + w_2, y + w_2, z - h_2);
glVertex3f(x - w_2, y + w_2, z - h_2);
glVertex3f(x - w_2, y + w_2, z + h_2);
glEnd();
// face 3
glBegin(GL_LINE_LOOP);
glVertex3f(x + w_2, y + w_2, z + h_2);
glVertex3f(x - w_2, y + w_2, z + h_2);
glVertex3f(x - w_2, y - w_2, z + h_2);
glVertex3f(x + w_2, y - w_2, z + h_2);
glEnd();
// face 4
glBegin(GL_LINE_LOOP);
glVertex3f(x - w_2, y - w_2, z + h_2);
glVertex3f(x - w_2, y + w_2, z + h_2);
glVertex3f(x - w_2, y + w_2, z - h_2);
glVertex3f(x - w_2, y - w_2, z - h_2);
glEnd();
// face 5
glBegin(GL_LINE_LOOP);
glVertex3f(x - w_2, y - w_2, z + h_2);
glVertex3f(x - w_2, y - w_2, z - h_2);
glVertex3f(x + w_2, y - w_2, z - h_2);
glVertex3f(x + w_2, y - w_2, z + h_2);
glEnd();
// face 6
glBegin(GL_LINE_LOOP);
glVertex3f(x - w_2, y - w_2, z - h_2);
glVertex3f(x - w_2, y + w_2, z - h_2);
glVertex3f(x + w_2, y + w_2, z - h_2);
glVertex3f(x + w_2, y - w_2, z - h_2);
glEnd();
}
break;
case px::GLOverlay::END:
glEnd();
break;
case px::GLOverlay::VERTEX2F:
{
float x = getFloatValue(data, i);
float y = getFloatValue(data, i);
glVertex2f(x, y);
}
break;
case px::GLOverlay::VERTEX3F:
{
float x = getFloatValue(data, i);
float y = getFloatValue(data, i);
float z = getFloatValue(data, i);
glVertex3f(x, y, z);
}
break;
case px::GLOverlay::ROTATEF:
{
float angle = getFloatValue(data, i);
float x = getFloatValue(data, i);
float y = getFloatValue(data, i);
float z = getFloatValue(data, i);
glRotatef(angle, x, y, z);
}
break;
case px::GLOverlay::TRANSLATEF:
{
float x = getFloatValue(data, i);
float y = getFloatValue(data, i);
float z = getFloatValue(data, i);
glTranslatef(x, y, z);
}
break;
case px::GLOverlay::SCALEF:
{
float x = getFloatValue(data, i);
float y = getFloatValue(data, i);
float z = getFloatValue(data, i);
glScalef(x, y, z);
}
break;
case px::GLOverlay::PUSH_MATRIX:
glPushMatrix();
break;
case px::GLOverlay::POP_MATRIX:
glPopMatrix();
break;
case px::GLOverlay::COLOR3F:
{
float red = getFloatValue(data, i);
float green = getFloatValue(data, i);
float blue = getFloatValue(data, i);
glColor3f(red, green, blue);
}
break;
case px::GLOverlay::COLOR4F:
{
float red = getFloatValue(data, i);
float green = getFloatValue(data, i);
float blue = getFloatValue(data, i);
float alpha = getFloatValue(data, i);
glColor4f(red, green, blue, alpha);
}
break;
case px::GLOverlay::POINTSIZE:
glPointSize(getFloatValue(data, i));
break;
case px::GLOverlay::LINEWIDTH:
glLineWidth(getFloatValue(data, i));
break;
}
}
glPopMatrix();
}
osg::BoundingBox
GLOverlayGeode::GLOverlayDrawable::computeBound() const
{
return mBBox;
}
float
GLOverlayGeode::GLOverlayDrawable::getFloatValue(const std::string& data,
size_t& mark) const
{
char temp[4];
for (int i = 0; i < 4; ++i)
{
++mark;
temp[i] = data.at(mark);
}
char *cp = &(temp[0]);
float *fp = reinterpret_cast<float *>(cp);
return *fp;
}

49
src/ui/map3D/GLOverlayGeode.h

@ -0,0 +1,49 @@ @@ -0,0 +1,49 @@
#ifndef GLOVERLAYGEODE_H
#define GLOVERLAYGEODE_H
#include <mavlink_protobuf_manager.hpp>
#include <osg/Geode>
#include <QtGlobal>
class GLOverlayGeode : public osg::Geode
{
public:
GLOverlayGeode();
void setOverlay(px::GLOverlay& overlay);
px::GLOverlay::CoordinateFrameType coordinateFrameType(void) const;
void setMessageTimestamp(qreal timestamp);
qreal messageTimestamp(void) const;
private:
class GLOverlayDrawable : public osg::Drawable
{
public:
GLOverlayDrawable();
GLOverlayDrawable(const GLOverlayDrawable& drawable,
const osg::CopyOp& copyop = osg::CopyOp::SHALLOW_COPY);
void setOverlay(px::GLOverlay& overlay);
META_Object(GLOverlayDrawableApp, GLOverlayDrawable)
virtual void drawImplementation(osg::RenderInfo&) const;
virtual osg::BoundingBox computeBound() const;
private:
float getFloatValue(const std::string& data, size_t& mark) const;
px::GLOverlay mOverlay;
osg::BoundingBox mBBox;
};
osg::ref_ptr<GLOverlayDrawable> mDrawable;
px::GLOverlay::CoordinateFrameType mCoordinateFrameType;
qreal mMessageTimestamp;
};
#endif // GLOVERLAYGEODE_H

65
src/ui/map3D/Pixhawk3DWidget.cc

@ -139,6 +139,10 @@ Pixhawk3DWidget::systemCreated(UASInterface *uas) @@ -139,6 +139,10 @@ Pixhawk3DWidget::systemCreated(UASInterface *uas)
this, SLOT(attitudeChanged(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(userPositionSetPointsChanged(int,float,float,float,float)),
this, SLOT(setpointChanged(int,float,float,float,float)));
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
connect(uas, SIGNAL(overlayChanged(UASInterface*)),
this, SLOT(addOverlay(UASInterface*)));
#endif
initializeSystem(systemId, uas->getColor());
@ -546,6 +550,43 @@ Pixhawk3DWidget::loadTerrainModel(void) @@ -546,6 +550,43 @@ Pixhawk3DWidget::loadTerrainModel(void)
}
}
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
void
Pixhawk3DWidget::addOverlay(UASInterface *uas)
{
int systemId = uas->getUASID();
if (!mSystemContainerMap.contains(systemId))
{
return;
}
SystemContainer& systemData = mSystemContainerMap[systemId];
qreal receivedTimestamp;
px::GLOverlay overlay = uas->getOverlay(receivedTimestamp);
QString overlayName = QString::fromStdString(overlay.name());
osg::ref_ptr<SystemGroupNode>& systemNode = m3DWidget->systemGroup(systemId);
if (!systemData.overlayNodeMap().contains(overlayName))
{
osg::ref_ptr<GLOverlayGeode> overlayNode = new GLOverlayGeode;
systemData.overlayNodeMap().insert(overlayName, overlayNode);
systemNode->allocentricMap()->addChild(overlayNode, false);
systemNode->rollingMap()->addChild(overlayNode, false);
emit overlayCreatedSignal(systemId, overlayName);
}
osg::ref_ptr<GLOverlayGeode>& overlayNode = systemData.overlayNodeMap()[overlayName];
overlayNode->setOverlay(overlay);
overlayNode->setMessageTimestamp(receivedTimestamp);
}
#endif
void
Pixhawk3DWidget::selectTargetHeading(void)
{
@ -904,6 +945,30 @@ Pixhawk3DWidget::update(void) @@ -904,6 +945,30 @@ Pixhawk3DWidget::update(void)
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
rollingMap->setChildValue(systemData.obstacleGroupNode(),
systemViewParams->displayObstacleList());
QMutableMapIterator<QString, osg::ref_ptr<GLOverlayGeode> > itOverlay(systemData.overlayNodeMap());
while (itOverlay.hasNext())
{
itOverlay.next();
osg::ref_ptr<GLOverlayGeode>& overlayNode = itOverlay.value();
bool displayOverlay = systemViewParams->displayOverlay().value(itOverlay.key());
bool visible;
visible = (overlayNode->coordinateFrameType() == px::GLOverlay::GLOBAL) &&
displayOverlay &&
(QGC::groundTimeSeconds() - overlayNode->messageTimestamp() < kMessageTimeout);
allocentricMap->setChildValue(overlayNode, visible);
visible = (overlayNode->coordinateFrameType() == px::GLOverlay::LOCAL) &&
displayOverlay &&
(QGC::groundTimeSeconds() - overlayNode->messageTimestamp() < kMessageTimeout);;
rollingMap->setChildValue(overlayNode, visible);
}
rollingMap->setChildValue(systemData.plannedPathNode(),
systemViewParams->displayPlannedPath());

5
src/ui/map3D/Pixhawk3DWidget.h

@ -64,6 +64,7 @@ public slots: @@ -64,6 +64,7 @@ public slots:
signals:
void systemCreatedSignal(UASInterface* uas);
void overlayCreatedSignal(int systemId, const QString& name);
private slots:
void clearData(void);
@ -75,6 +76,10 @@ private slots: @@ -75,6 +76,10 @@ private slots:
void setBirdEyeView(void);
void loadTerrainModel(void);
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
void addOverlay(UASInterface* uas);
#endif
void selectTargetHeading(void);
void selectTarget(void);
void setTarget(void);

6
src/ui/map3D/SystemContainer.cc

@ -99,6 +99,12 @@ SystemContainer::obstacleGroupNode(void) @@ -99,6 +99,12 @@ SystemContainer::obstacleGroupNode(void)
return mObstacleGroupNode;
}
QMap<QString,osg::ref_ptr<GLOverlayGeode> >&
SystemContainer::overlayNodeMap(void)
{
return mOverlayNodeMap;
}
osg::ref_ptr<osg::Geode>&
SystemContainer::plannedPathNode(void)
{

3
src/ui/map3D/SystemContainer.h

@ -10,6 +10,7 @@ @@ -10,6 +10,7 @@
#include "WaypointGroupNode.h"
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
#include "GLOverlayGeode.h"
#include "ObstacleGroupNode.h"
#endif
@ -37,6 +38,7 @@ public: @@ -37,6 +38,7 @@ public:
osg::ref_ptr<WaypointGroupNode>& waypointGroupNode(void);
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
osg::ref_ptr<ObstacleGroupNode>& obstacleGroupNode(void);
QMap<QString,osg::ref_ptr<GLOverlayGeode> >& overlayNodeMap(void);
osg::ref_ptr<osg::Geode>& plannedPathNode(void);
#endif
@ -62,6 +64,7 @@ private: @@ -62,6 +64,7 @@ private:
osg::ref_ptr<WaypointGroupNode> mWaypointGroupNode;
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
osg::ref_ptr<ObstacleGroupNode> mObstacleGroupNode;
QMap<QString,osg::ref_ptr<GLOverlayGeode> > mOverlayNodeMap;
osg::ref_ptr<osg::Geode> mPlannedPathNode;
#endif
};

23
src/ui/map3D/SystemViewParams.cc

@ -54,6 +54,18 @@ SystemViewParams::displayObstacleList(void) const @@ -54,6 +54,18 @@ SystemViewParams::displayObstacleList(void) const
return mDisplayObstacleList;
}
QMap<QString,bool>&
SystemViewParams::displayOverlay(void)
{
return mDisplayOverlay;
}
QMap<QString,bool>
SystemViewParams::displayOverlay(void) const
{
return mDisplayOverlay;
}
bool&
SystemViewParams::displayPlannedPath(void)
{
@ -228,6 +240,17 @@ SystemViewParams::toggleObstacleList(int state) @@ -228,6 +240,17 @@ SystemViewParams::toggleObstacleList(int state)
}
void
SystemViewParams::toggleOverlay(const QString& name)
{
if (!mDisplayOverlay.contains(name))
{
return;
}
mDisplayOverlay[name] = !mDisplayOverlay[name];
}
void
SystemViewParams::togglePlannedPath(int state)
{
if (state == Qt::Checked)

6
src/ui/map3D/SystemViewParams.h

@ -1,6 +1,7 @@ @@ -1,6 +1,7 @@
#ifndef SYSTEMVIEWPARAMS_H
#define SYSTEMVIEWPARAMS_H
#include <QMap>
#include <QObject>
#include <QSharedPointer>
#include <QVector>
@ -21,6 +22,9 @@ public: @@ -21,6 +22,9 @@ public:
bool& displayObstacleList(void);
bool displayObstacleList(void) const;
QMap<QString,bool>& displayOverlay(void);
QMap<QString,bool> displayOverlay(void) const;
bool& displayPlannedPath(void);
bool displayPlannedPath(void) const;
@ -57,6 +61,7 @@ public slots: @@ -57,6 +61,7 @@ public slots:
void toggleColorPointCloud(int state);
void toggleLocalGrid(int state);
void toggleObstacleList(int state);
void toggleOverlay(const QString& name);
void togglePlannedPath(int state);
void togglePointCloud(int state);
void toggleRGBD(int state);
@ -74,6 +79,7 @@ private: @@ -74,6 +79,7 @@ private:
bool mColorPointCloudByDistance;
bool mDisplayLocalGrid;
bool mDisplayObstacleList;
QMap<QString,bool> mDisplayOverlay;
bool mDisplayPlannedPath;
bool mDisplayPointCloud;
bool mDisplayRGBD;

34
src/ui/map3D/ViewParamWidget.cc

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
#include <osg/LineWidth>
#include <QCheckBox>
#include <QFormLayout>
#include <QGroupBox>
#include <QLabel>
#include <QPushButton>
@ -28,8 +28,13 @@ ViewParamWidget::ViewParamWidget(GlobalViewParamsPtr& globalViewParams, @@ -28,8 +28,13 @@ ViewParamWidget::ViewParamWidget(GlobalViewParamsPtr& globalViewParams,
mTabWidget->setFocusPolicy(Qt::NoFocus);
mOverlaySignalMapper = new QSignalMapper(this);
connect(parent, SIGNAL(systemCreatedSignal(UASInterface*)),
this, SLOT(systemCreated(UASInterface*)));
connect(parent, SIGNAL(overlayCreatedSignal(int,QString)),
this, SLOT(overlayCreated(int,QString)));
}
void
@ -48,6 +53,28 @@ ViewParamWidget::setFollowCameraId(int id) @@ -48,6 +53,28 @@ ViewParamWidget::setFollowCameraId(int id)
}
void
ViewParamWidget::overlayCreated(int systemId, const QString& name)
{
if (!mOverlayLayout.contains(systemId))
{
return;
}
SystemViewParamsPtr systemViewParams = mSystemViewParamMap[systemId];
systemViewParams->displayOverlay().insert(name, true);
QCheckBox* checkbox = new QCheckBox(this);
checkbox->setChecked(systemViewParams->displayOverlay().value(name));
mOverlayLayout[systemId]->addRow(name, checkbox);
mOverlaySignalMapper->setMapping(checkbox, name);
connect(checkbox, SIGNAL(clicked()),
mOverlaySignalMapper, SLOT(map()));
connect(mOverlaySignalMapper, SIGNAL(mapped(QString)),
systemViewParams.data(), SLOT(toggleOverlay(QString)));
}
void
ViewParamWidget::systemCreated(UASInterface *uas)
{
addTab(uas->getUASID());
@ -173,6 +200,10 @@ ViewParamWidget::addTab(int systemId) @@ -173,6 +200,10 @@ ViewParamWidget::addTab(int systemId)
QCheckBox* waypointsCheckBox = new QCheckBox(this);
waypointsCheckBox->setChecked(systemViewParams->displayWaypoints());
QGroupBox* overlayGroupBox = new QGroupBox(tr("Overlays"), this);
mOverlayLayout[systemId] = new QFormLayout;
overlayGroupBox->setLayout(mOverlayLayout[systemId]);
QFormLayout* formLayout = new QFormLayout;
page->setLayout(formLayout);
@ -188,6 +219,7 @@ ViewParamWidget::addTab(int systemId) @@ -188,6 +219,7 @@ ViewParamWidget::addTab(int systemId)
formLayout->addRow(tr("Target"), targetCheckBox);
formLayout->addRow(tr("Trails"), trailsCheckBox);
formLayout->addRow(tr("Waypoints"), waypointsCheckBox);
formLayout->addRow(overlayGroupBox);
QString label("MAV ");
label += QString::number(systemId);

6
src/ui/map3D/ViewParamWidget.h

@ -3,6 +3,8 @@ @@ -3,6 +3,8 @@
#include <QComboBox>
#include <QDockWidget>
#include <QFormLayout>
#include <QSignalMapper>
#include <QSpinBox>
#include <QTabWidget>
#include <QVBoxLayout>
@ -26,6 +28,7 @@ public: @@ -26,6 +28,7 @@ public:
signals:
private slots:
void overlayCreated(int systemId, const QString& name);
void systemCreated(UASInterface* uas);
void setpointsCheckBoxToggled(int state);
@ -43,7 +46,10 @@ private: @@ -43,7 +46,10 @@ private:
// child widgets
QComboBox* mFollowCameraComboBox;
QSpinBox* mSetpointHistoryLengthSpinBox;
QMap<int, QFormLayout*> mOverlayLayout;
QTabWidget* mTabWidget;
QSignalMapper* mOverlaySignalMapper;
};
#endif // VIEWPARAMWIDGET_H

30
thirdParty/mavlink/include/mavlink_protobuf_manager.hpp vendored

@ -24,39 +24,45 @@ public: @@ -24,39 +24,45 @@ public:
, kExtendedHeaderSize(MAVLINK_EXTENDED_HEADER_LEN)
, kExtendedPayloadMaxSize(MAVLINK_MAX_EXTENDED_PAYLOAD_LEN)
{
// register PointCloudXYZI
// register GLOverlay
{
std::tr1::shared_ptr<px::PointCloudXYZI> msg(new px::PointCloudXYZI);
std::tr1::shared_ptr<px::GLOverlay> msg(new px::GLOverlay);
registerType(msg);
}
// register PointCloudXYZRGB
// register ObstacleList
{
std::tr1::shared_ptr<px::PointCloudXYZRGB> msg(new px::PointCloudXYZRGB);
std::tr1::shared_ptr<px::ObstacleList> msg(new px::ObstacleList);
registerType(msg);
}
// register RGBDImage
// register ObstacleMap
{
std::tr1::shared_ptr<px::RGBDImage> msg(new px::RGBDImage);
std::tr1::shared_ptr<px::ObstacleMap> msg(new px::ObstacleMap);
registerType(msg);
}
// register ObstacleList
// register Path
{
std::tr1::shared_ptr<px::ObstacleList> msg(new px::ObstacleList);
std::tr1::shared_ptr<px::Path> msg(new px::Path);
registerType(msg);
}
// register ObstacleMap
// register PointCloudXYZI
{
std::tr1::shared_ptr<px::ObstacleMap> msg(new px::ObstacleMap);
std::tr1::shared_ptr<px::PointCloudXYZI> msg(new px::PointCloudXYZI);
registerType(msg);
}
// register Path
// register PointCloudXYZRGB
{
std::tr1::shared_ptr<px::Path> msg(new px::Path);
std::tr1::shared_ptr<px::PointCloudXYZRGB> msg(new px::PointCloudXYZRGB);
registerType(msg);
}
// register RGBDImage
{
std::tr1::shared_ptr<px::RGBDImage> msg(new px::RGBDImage);
registerType(msg);
}

3805
thirdParty/mavlink/include/pixhawk/pixhawk.pb.h vendored

File diff suppressed because it is too large Load Diff

139
thirdParty/mavlink/message_definitions/pixhawk.proto vendored

@ -1,11 +1,107 @@ @@ -1,11 +1,107 @@
package px;
message HeaderInfo {
message HeaderInfo
{
required int32 source_sysid = 1;
required int32 source_compid = 2;
required double timestamp = 3; // in seconds
}
message GLOverlay
{
required HeaderInfo header = 1;
optional string name = 2;
enum CoordinateFrameType
{
GLOBAL = 0;
LOCAL = 1;
}
optional CoordinateFrameType coordinateFrameType = 3;
optional double origin_x = 4;
optional double origin_y = 5;
optional double origin_z = 6;
optional bytes data = 7;
enum Mode
{
POINTS = 0;
LINES = 1;
LINE_STRIP = 2;
LINE_LOOP = 3;
TRIANGLES = 4;
TRIANGLE_STRIP = 5;
TRIANGLE_FAN = 6;
QUADS = 7;
QUAD_STRIP = 8;
POLYGON = 9;
SOLID_CIRCLE = 10;
WIRE_CIRCLE = 11;
SOLID_CUBE = 12;
WIRE_CUBE = 13;
}
enum Identifier
{
END = 14;
VERTEX2F = 15;
VERTEX3F = 16;
ROTATEF = 17;
TRANSLATEF = 18;
SCALEF = 19;
PUSH_MATRIX = 20;
POP_MATRIX = 21;
COLOR3F = 22;
COLOR4F = 23;
POINTSIZE = 24;
LINEWIDTH = 25;
}
}
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 Path
{
required HeaderInfo header = 1;
repeated Waypoint waypoints = 2;
}
message PointCloudXYZI {
message PointXYZI {
required float x = 1;
@ -56,40 +152,6 @@ message RGBDImage @@ -56,40 +152,6 @@ 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;
@ -99,10 +161,3 @@ message Waypoint @@ -99,10 +161,3 @@ message Waypoint
optional double pitch = 5;
optional double yaw = 6;
}
message Path
{
required HeaderInfo header = 1;
repeated Waypoint waypoints = 2;
}

83
thirdParty/mavlink/message_definitions/sensesoar.xml vendored

@ -0,0 +1,83 @@ @@ -0,0 +1,83 @@
<?xml version='1.0'?>
<mavlink>
<include>common.xml</include>
<enums>
<enum name="SENSESOAR_MODE">
<description> Different flight modes </description>
<entry name="SENSESOAR_MODE_GLIDING"> Gliding mode with motors off</entry>
<entry name="SENSESOAR_MODE_AUTONOMOUS"> Autonomous flight</entry>
<entry name="SENSESOAR_MODE_MANUAL"> RC controlled</entry>
</enum>
</enums>
<messages>
<message id="170" name="OBS_POSITION">
Position estimate of the observer in global frame
<field type="int32_t" name="lon">Longitude expressed in 1E7</field>
<field type="int32_t" name="lat">Latitude expressed in 1E7</field>
<field type="int32_t" name="alt">Altitude expressed in milimeters</field>
</message>
<message id="172" name="OBS_VELOCITY">
velocity estimate of the observer in NED inertial frame
<field type="float[3]" name="vel">Velocity</field>
</message>
<message id="174" name="OBS_ATTITUDE">
attitude estimate of the observer
<field type="double[4]" name="quat">Quaternion re;im</field>
</message>
<message id="176" name="OBS_WIND">
Wind estimate in NED inertial frame
<field type="float[3]" name="wind">Wind</field>
</message>
<message id="178" name="OBS_AIR_VELOCITY">
Estimate of the air velocity
<field type="float" name="magnitude">Air speed</field>
<field type="float" name="aoa">angle of attack</field>
<field type="float" name="slip">slip angle</field>
</message>
<message id="180" name="OBS_BIAS">
IMU biases
<field type="float[3]" name="accBias">accelerometer bias</field>
<field type="float[3]" name="gyroBias">gyroscope bias</field>
</message>
<message id="182" name="OBS_QFF">
estimate of the pressure at sea level
<field type="float" name="qff">Wind</field>
</message>
<message id="183" name="OBS_AIR_TEMP">
ambient air temperature
<field type="float" name="airT">Air Temperatur</field>
</message>
<message id="184" name="FILT_ROT_VEL">
filtered rotational velocity
<field type="float[3]" name="rotVel">rotational velocity</field>
</message>
<message id="186" name="LLC_OUT">
low level control output
<field type="int16_t[4]" name="servoOut">Servo signal</field>
<field type="int16_t[2]" name="MotorOut">motor signal</field>
</message>
<message id="188" name="PM_ELEC">
Power managment
<field type="float" name="PwCons">current power consumption</field>
<field type="float" name="BatStat">battery status</field>
<field type="float[3]" name="PwGen">Power generation from each module</field>
</message>
<message id="190" name="SYS_Stat">
system status
<field type="uint8_t" name="gps">gps status</field>
<field type="uint8_t" name="act">actuator status</field>
<field type="uint8_t" name="mod">module status</field>
<field type="uint8_t" name="commRssi">module status</field>
</message>
<message id="192" name="CMD_AIRSPEED_CHNG">
change commanded air speed
<field type="uint8_t" name="target">Target ID</field>
<field type="float" name="spCmd">commanded airspeed</field>
</message>
<message id="194" name="CMD_AIRSPEED_ACK">
accept change of airspeed
<field type="float" name="spCmd">commanded airspeed</field>
<field type="uint8_t" name="ack">0:ack, 1:nack</field>
</message>
</messages>
</mavlink>

4951
thirdParty/mavlink/src/pixhawk/pixhawk.pb.cc vendored

File diff suppressed because it is too large Load Diff
Loading…
Cancel
Save