diff --git a/images/earth.html b/images/earth.html
index 8f8aadf..6f423cb 100644
--- a/images/earth.html
+++ b/images/earth.html
@@ -1,8 +1,9 @@
-
+
+
QGroundControl Google Earth View
diff --git a/qgroundcontrol.pri b/qgroundcontrol.pri
index 4c31610..a04bca8 100644
--- a/qgroundcontrol.pri
+++ b/qgroundcontrol.pri
@@ -1,399 +1,395 @@
-#-------------------------------------------------
-#
-# QGroundControl - Micro Air Vehicle Groundstation
-#
-# Please see our website at
-#
-# Author:
-# Lorenz Meier
-#
-# (c) 2009-2010 PIXHAWK Team
-#
-# This file is part of the mav groundstation project
-# QGroundControl is free software: you can redistribute it and/or modify
-# it under the terms of the GNU General Public License as published by
-# the Free Software Foundation, either version 3 of the License, or
-# (at your option) any later version.
-# QGroundControl is distributed in the hope that it will be useful,
-# but WITHOUT ANY WARRANTY; without even the implied warranty of
-# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
-# GNU General Public License for more details.
-# You should have received a copy of the GNU General Public License
-# along with QGroundControl. If not, see .
-#
-#-------------------------------------------------
-
-#$$BASEDIR/lib/qextserialport/include
-# $$BASEDIR/lib/openjaus/libjaus/include \
-# $$BASEDIR/lib/openjaus/libopenJaus/include
-
-message(Qt version $$[QT_VERSION])
-
-release {
-# DEFINES += QT_NO_DEBUG_OUTPUT
-# DEFINES += QT_NO_WARNING_OUTPUT
-}
-
-QMAKE_POST_LINK += echo "Copying files"
-
-#QMAKE_POST_LINK += && cp -rf $$BASEDIR/models $$TARGETDIR/debug/.
-#QMAKE_POST_LINK += && cp -rf $$BASEDIR/models $$TARGETDIR/release/.
-
-# MAC OS X
-macx {
-
- COMPILER_VERSION = system(gcc -v)
- message(Using compiler $$COMPILER_VERSION)
-
- 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
- CONFIG += x86 cocoa phonon
- 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
- }
- } else {
- # x64 Mac OS X Snow Leopard 10.6 and later
- CONFIG += x86_64 cocoa
- CONFIG -= x86 phonon
- message(Building for Mac OS X 64bit/Snow Leopard 10.6 and later)
- }
-
- QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.5
-
- #DESTDIR = $$BASEDIR/bin/mac
- INCLUDEPATH += -framework SDL
-
- LIBS += -framework IOKit \
- -framework SDL \
- -framework CoreFoundation \
- -framework ApplicationServices \
- -lm
-
- ICON = $$BASEDIR/images/icons/macx.icns
-
- # Copy audio files if needed
- QMAKE_POST_LINK += && cp -rf $$BASEDIR/audio $$TARGETDIR/qgroundcontrol.app/Contents/MacOs
- # Copy google earth starter file
- QMAKE_POST_LINK += && cp -f $$BASEDIR/images/earth.html $$TARGETDIR/qgroundcontrol.app/Contents/MacOs
- # Copy CSS stylesheet
- QMAKE_POST_LINK += && cp -f $$BASEDIR/images/style-mission.css $$TARGETDIR/qgroundcontrol.app/Contents/MacOs/qgroundcontrol.css
- # 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
- DEFINES += QGC_OSG_ENABLED
- # Include OpenSceneGraph libraries
- INCLUDEPATH += -framework GLUT \
- -framework Carbon \
- -framework OpenThreads \
- -framework osg \
- -framework osgViewer \
- -framework osgGA \
- -framework osgDB \
- -framework osgText \
- -framework osgWidget
-
- LIBS += -framework GLUT \
- -framework Carbon \
- -framework OpenThreads \
- -framework osg \
- -framework osgViewer \
- -framework osgGA \
- -framework osgDB \
- -framework osgText \
- -framework osgWidget
- }
-
- exists(/usr/include/osgEarth) {
- message("Building support for osgEarth")
- DEPENDENCIES_PRESENT += osgearth
- # Include osgEarth libraries
- INCLUDEPATH += -framework GDAL \
- $$IN_PWD/lib/mac32-gcc/include \
- -framework GEOS \
- -framework SQLite3 \
- -framework osgFX \
- -framework osgTerrain
-
- LIBS += -framework GDAL \
- -framework GEOS \
- -framework SQLite3 \
- -framework osgFX \
- -framework osgTerrain
- DEFINES += QGC_OSGEARTH_ENABLED
- }
-
-
- exists(/opt/local/include/libfreenect) {
- message("ENABLED support for libfreenect")
- DEPENDENCIES_PRESENT += libfreenect
- # Include libfreenect libraries
- LIBS += -lfreenect
- DEFINES += QGC_LIBFREENECT_ENABLED
- } else {
- message("DISABLED libfreenect support")
- }
-
- # osg/osgEarth dynamic casts might fail without this compiler option.
- # see http://osgearth.org/wiki/FAQ for details.
- #QMAKE_CXXFLAGS += -Wl,-E
-}
-
-# GNU/Linux
-linux-g++ {
-
- debug {
- DESTDIR = $$TARGETDIR/debug
- CONFIG += debug
- }
-
- release {
- DESTDIR = $$TARGETDIR/release
- }
-
- QMAKE_POST_LINK += cp -rf $$BASEDIR/audio $$DESTDIR/.
-
- INCLUDEPATH += /usr/include \
- /usr/include/qt4/phonon
- # $$BASEDIR/lib/flite/include \
- # $$BASEDIR/lib/flite/lang
-
-
- message(Building for GNU/Linux 32bit/i386)
-
- LIBS += \
- -L/usr/lib \
- -lm \
- -lflite_cmu_us_kal \
- -lflite_usenglish \
- -lflite_cmulex \
- -lflite \
- -lSDL \
- -lSDLmain
-
- exists(/usr/include/osg) {
- message("Building support for OpenSceneGraph")
- DEPENDENCIES_PRESENT += osg
- # Include OpenSceneGraph libraries
- LIBS += -losg \
- -losgViewer
- DEFINES += QGC_OSG_ENABLED
- }
-
- exists(/usr/include/osgEarth) | exists(/usr/local/include/osgEarth) {
- message("Building support for osgEarth")
- DEPENDENCIES_PRESENT += osgearth
- # Include osgEarth libraries
- LIBS += -losgEarth \
- -losgEarthUtil
- DEFINES += QGC_OSGEARTH_ENABLED
- }
-
- exists(/usr/local/include/libfreenect/libfreenect.h) {
- message("Building support for libfreenect")
- DEPENDENCIES_PRESENT += libfreenect
- INCLUDEPATH += /usr/include/libusb-1.0
- # Include libfreenect libraries
- LIBS += -lfreenect
- DEFINES += QGC_LIBFREENECT_ENABLED
- }
-
- QMAKE_POST_LINK += && cp -rf $$BASEDIR/models $$DESTDIR
- QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$DESTDIR
- QMAKE_POST_LINK += && mkdir -p $$DESTDIR/images
- QMAKE_POST_LINK += && cp -f $$BASEDIR/images/Vera.ttf $$DESTDIR/images/Vera.ttf
- QMAKE_POST_LINK += && cp -rf $$BASEDIR/images/patterns $$DESTDIR/images
-
- # osg/osgEarth dynamic casts might fail without this compiler option.
- # see http://osgearth.org/wiki/FAQ for details.
- QMAKE_CXXFLAGS += -Wl,-E
-}
-
-linux-g++-64 {
-
- debug {
- DESTDIR = $$TARGETDIR/debug
- CONFIG += debug
- }
-
- release {
- DESTDIR = $$TARGETDIR/release
- }
-
- QMAKE_POST_LINK += cp -rf $$BASEDIR/audio $$DESTDIR/.
-
- INCLUDEPATH += /usr/include \
- /usr/include/qt4/phonon
- # $$BASEDIR/lib/flite/include \
- # $$BASEDIR/lib/flite/lang
-
-
- # 64-bit Linux
- message(Building for GNU/Linux 64bit/x64 (g++-64))
-
- LIBS += \
- -L/usr/lib \
- -lm \
- -lflite_cmu_us_kal \
- -lflite_usenglish \
- -lflite_cmulex \
- -lflite \
- -lSDL \
- -lSDLmain
-
- exists(/usr/include/osg) {
- message("Building support for OpenSceneGraph")
- DEPENDENCIES_PRESENT += osg
- # Include OpenSceneGraph libraries
- LIBS += -losg \
- -losgViewer
- DEFINES += QGC_OSG_ENABLED
- }
-
- exists(/usr/include/osgEarth) {
- message("Building support for osgEarth")
- DEPENDENCIES_PRESENT += osgearth
- # Include osgEarth libraries
- LIBS += -losgEarth \
- -losgEarthUtil
- DEFINES += QGC_OSGEARTH_ENABLED
- }
-
- exists(/usr/local/include/libfreenect) {
- message("Building support for libfreenect")
- DEPENDENCIES_PRESENT += libfreenect
- INCLUDEPATH += /usr/include/libusb-1.0
- # Include libfreenect libraries
- LIBS += -lfreenect
- DEFINES += QGC_LIBFREENECT_ENABLED
- }
-
- QMAKE_POST_LINK += && cp -rf $$BASEDIR/models $$DESTDIR
- QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$DESTDIR
- QMAKE_POST_LINK += && mkdir -p $$DESTDIR/images
- QMAKE_POST_LINK += && cp -f $$BASEDIR/images/Vera.ttf $$DESTDIR/images/Vera.ttf
- QMAKE_POST_LINK += && cp -rf $$BASEDIR/images/patterns $$DESTDIR/images
-
- # osg/osgEarth dynamic casts might fail without this compiler option.
- # see http://osgearth.org/wiki/FAQ for details.
- QMAKE_CXXFLAGS += -Wl,-E
-}
-
-# Windows (32bit)
-win32-msvc2008 {
-
- message(Building for Windows Visual Studio 2008 (32bit))
-
- CONFIG += qaxcontainer
-
- # Special settings for debug
- #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
-
-exists($$BASEDIR/lib/osg123) {
-message("Building support for OSG")
-DEPENDENCIES_PRESENT += osg
-
-# Include OpenSceneGraph and osgEarth libraries
-INCLUDEPATH += $$BASEDIR/lib/osgEarth/win32/include \
- $$BASEDIR/lib/osgEarth_3rdparty/win32/OpenSceneGraph-2.8.2/include
-LIBS += -L$$BASEDIR/lib/osgEarth_3rdparty/win32/OpenSceneGraph-2.8.2/lib \
- -losg \
- -losgViewer \
- -losgGA \
- -losgDB \
- -losgText \
- -lOpenThreads
-DEFINES += QGC_OSG_ENABLED
-exists($$BASEDIR/lib/osgEarth123) {
- DEPENDENCIES_PRESENT += osgearth
- message("Building support for osgEarth")
- DEFINES += QGC_OSGEARTH_ENABLED
- LIBS += -L$$BASEDIR/lib/osgEarth/win32/lib \
- -losgEarth \
- -losgEarthUtil
-}
-}
-
- RC_FILE = $$BASEDIR/qgroundcontrol.rc
-
- # Copy dependencies
- BASEDIR_WIN = $$replace(BASEDIR,"/","\\")
- TARGETDIR_WIN = $$replace(TARGETDIR,"/","\\")
-
- debug {
- QMAKE_POST_LINK += && copy /Y \"$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll\" \"$$TARGETDIR_WIN\\debug\\SDL.dll\"
- QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\audio\" \"$$TARGETDIR_WIN\debug\audio\" /S /E /Y
- QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\models\" \"$$TARGETDIR_WIN\debug\models\" /S /E /Y
- QMAKE_POST_LINK += && copy /Y \"$$BASEDIR/images/earth.html $$TARGETDIR_WIN\debug\"
- }
-
- release {
- QMAKE_POST_LINK += && copy /Y \"$$BASEDIR_WIN\lib\sdl\win32\SDL.dll\" \"$$TARGETDIR_WIN\release\SDL.dll\"
- QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\audio\" \"$$TARGETDIR_WIN\release\audio\" /S /E /Y
- QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\models\" \"$$TARGETDIR_WIN\release\models\" /S /E /Y
- QMAKE_POST_LINK += && copy /Y \"$$BASEDIR/images/earth.html $$TARGETDIR_WIN\release\"
- }
-
-}
-
-# Windows (32bit)
-win32-g++ {
-
- message(Building for Windows Platform (32bit))
-
- # Special settings for debug
- #CONFIG += CONSOLE
-
- INCLUDEPATH += $$BASEDIR/lib/sdl/include \
- $$BASEDIR/lib/opal/include #\ #\
- #"C:\Program Files\Microsoft SDKs\Windows\v7.0\Include"
-
- LIBS += -L$$BASEDIR/lib/sdl/win32 \
- -lmingw32 -lSDLmain -lSDL -mwindows
-
-
-
- debug {
- #DESTDIR = $$BUILDDIR/debug
- }
-
- release {
- #DESTDIR = $$BUILDDIR/release
- }
-
- RC_FILE = $$BASEDIR/qgroundcontrol.rc
-
- # Copy dependencies
-
- debug {
- QMAKE_POST_LINK += && cp $$BASEDIR/lib/sdl/win32/SDL.dll $$TARGETDIR/debug/SDL.dll
- QMAKE_POST_LINK += && cp -r $$BASEDIR/audio $$TARGETDIR/debug/audio
- QMAKE_POST_LINK += && cp -r $$BASEDIR/models $$TARGETDIR/debug/models
- }
-
- release {
- QMAKE_POST_LINK += && cp $$BASEDIR/lib/sdl/win32/SDL.dll $$TARGETDIR/release/SDL.dll
- QMAKE_POST_LINK += && cp -r $$BASEDIR/audio $$TARGETDIR/release/audio
- QMAKE_POST_LINK += && cp -r $$BASEDIR/models $$TARGETDIR/release/models
- }
-
- # osg/osgEarth dynamic casts might fail without this compiler option.
- # see http://osgearth.org/wiki/FAQ for details.
- QMAKE_CXXFLAGS += -Wl,-E
-}
+#-------------------------------------------------
+#
+# QGroundControl - Micro Air Vehicle Groundstation
+#
+# Please see our website at
+#
+# Author:
+# Lorenz Meier
+#
+# (c) 2009-2010 PIXHAWK Team
+#
+# This file is part of the mav groundstation project
+# QGroundControl is free software: you can redistribute it and/or modify
+# it under the terms of the GNU General Public License as published by
+# the Free Software Foundation, either version 3 of the License, or
+# (at your option) any later version.
+# QGroundControl is distributed in the hope that it will be useful,
+# but WITHOUT ANY WARRANTY; without even the implied warranty of
+# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+# GNU General Public License for more details.
+# You should have received a copy of the GNU General Public License
+# along with QGroundControl. If not, see .
+#
+#-------------------------------------------------
+
+
+#$$BASEDIR/lib/qextserialport/include
+# $$BASEDIR/lib/openjaus/libjaus/include \
+# $$BASEDIR/lib/openjaus/libopenJaus/include
+
+message(Qt version $$[QT_VERSION])
+
+release {
+# DEFINES += QT_NO_DEBUG_OUTPUT
+# DEFINES += QT_NO_WARNING_OUTPUT
+}
+
+QMAKE_POST_LINK += echo "Copying files"
+
+#QMAKE_POST_LINK += && cp -rf $$BASEDIR/models $$TARGETDIR/debug/.
+#QMAKE_POST_LINK += && cp -rf $$BASEDIR/models $$TARGETDIR/release/.
+
+# MAC OS X
+macx {
+
+ COMPILER_VERSION = system(gcc -v)
+ message(Using compiler $$COMPILER_VERSION)
+
+ 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
+ CONFIG += x86 cocoa phonon
+ 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
+ }
+ } else {
+ # x64 Mac OS X Snow Leopard 10.6 and later
+ CONFIG += x86_64 cocoa
+ CONFIG -= x86 phonon
+ message(Building for Mac OS X 64bit/Snow Leopard 10.6 and later)
+ }
+
+ QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.5
+
+ #DESTDIR = $$BASEDIR/bin/mac
+ INCLUDEPATH += -framework SDL
+
+ LIBS += -framework IOKit \
+ -framework SDL \
+ -framework CoreFoundation \
+ -framework ApplicationServices \
+ -lm
+
+ ICON = $$BASEDIR/images/icons/macx.icns
+
+ # Copy audio files if needed
+ QMAKE_POST_LINK += && cp -rf $$BASEDIR/audio $$TARGETDIR/qgroundcontrol.app/Contents/MacOs
+ # Copy google earth starter file
+ QMAKE_POST_LINK += && cp -f $$BASEDIR/images/earth.html $$TARGETDIR/qgroundcontrol.app/Contents/MacOs
+ # 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
+ DEFINES += QGC_OSG_ENABLED
+ # Include OpenSceneGraph libraries
+ INCLUDEPATH += -framework GLUT \
+ -framework Carbon \
+ -framework OpenThreads \
+ -framework osg \
+ -framework osgViewer \
+ -framework osgGA \
+ -framework osgDB \
+ -framework osgText \
+ -framework osgWidget
+
+ LIBS += -framework GLUT \
+ -framework Carbon \
+ -framework OpenThreads \
+ -framework osg \
+ -framework osgViewer \
+ -framework osgGA \
+ -framework osgDB \
+ -framework osgText \
+ -framework osgWidget
+ }
+
+ exists(/usr/include/osgEarth) {
+ message("Building support for osgEarth")
+ DEPENDENCIES_PRESENT += osgearth
+ # Include osgEarth libraries
+ INCLUDEPATH += -framework GDAL \
+ $$IN_PWD/lib/mac32-gcc/include \
+ -framework GEOS \
+ -framework SQLite3 \
+ -framework osgFX \
+ -framework osgTerrain
+
+ LIBS += -framework GDAL \
+ -framework GEOS \
+ -framework SQLite3 \
+ -framework osgFX \
+ -framework osgTerrain
+ DEFINES += QGC_OSGEARTH_ENABLED
+ }
+
+
+ exists(/opt/local/include/libfreenect) {
+ message("Building support for libfreenect")
+ DEPENDENCIES_PRESENT += libfreenect
+ # Include libfreenect libraries
+ LIBS += -lfreenect
+ DEFINES += QGC_LIBFREENECT_ENABLED
+ }
+
+ # osg/osgEarth dynamic casts might fail without this compiler option.
+ # see http://osgearth.org/wiki/FAQ for details.
+ #QMAKE_CXXFLAGS += -Wl,-E
+}
+
+# GNU/Linux
+linux-g++ {
+
+ debug {
+ DESTDIR = $$TARGETDIR/debug
+ CONFIG += debug
+ }
+
+ release {
+ DESTDIR = $$TARGETDIR/release
+ }
+
+ QMAKE_POST_LINK += cp -rf $$BASEDIR/audio $$DESTDIR/.
+
+ INCLUDEPATH += /usr/include \
+ /usr/local/include \
+ /usr/include/qt4/phonon
+ # $$BASEDIR/lib/flite/include \
+ # $$BASEDIR/lib/flite/lang
+
+
+ message(Building for GNU/Linux 32bit/i386)
+
+ LIBS += \
+ -L/usr/lib \
+ -lm \
+ -lflite_cmu_us_kal \
+ -lflite_usenglish \
+ -lflite_cmulex \
+ -lflite \
+ -lSDL \
+ -lSDLmain
+
+ exists(/usr/include/osg) {
+ message("Building support for OpenSceneGraph")
+ DEPENDENCIES_PRESENT += osg
+ # Include OpenSceneGraph libraries
+ LIBS += -losg \
+ -losgViewer
+ DEFINES += QGC_OSG_ENABLED
+ }
+
+ exists(/usr/include/osgEarth) | exists(/usr/local/include/osgEarth) {
+ message("Building support for osgEarth")
+ DEPENDENCIES_PRESENT += osgearth
+ # Include osgEarth libraries
+ LIBS += -losgEarth \
+ -losgEarthUtil
+ DEFINES += QGC_OSGEARTH_ENABLED
+ }
+
+ exists(/usr/local/include/libfreenect/libfreenect.h) {
+ message("Building support for libfreenect")
+ DEPENDENCIES_PRESENT += libfreenect
+ INCLUDEPATH += /usr/include/libusb-1.0
+ # Include libfreenect libraries
+ LIBS += -lfreenect
+ DEFINES += QGC_LIBFREENECT_ENABLED
+ }
+
+ QMAKE_POST_LINK += && cp -rf $$BASEDIR/models $$DESTDIR
+ QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$DESTDIR
+ QMAKE_POST_LINK += && mkdir -p $$DESTDIR/images
+ QMAKE_POST_LINK += && cp -rf $$BASEDIR/images/Vera.ttf $$DESTDIR/images/Vera.ttf
+
+ # osg/osgEarth dynamic casts might fail without this compiler option.
+ # see http://osgearth.org/wiki/FAQ for details.
+ QMAKE_CXXFLAGS += -Wl,-E
+}
+
+linux-g++-64 {
+
+ debug {
+ DESTDIR = $$TARGETDIR/debug
+ CONFIG += debug
+ }
+
+ release {
+ DESTDIR = $$TARGETDIR/release
+ }
+
+ QMAKE_POST_LINK += cp -rf $$BASEDIR/audio $$DESTDIR/.
+
+ INCLUDEPATH += /usr/include \
+ /usr/include/qt4/phonon
+ # $$BASEDIR/lib/flite/include \
+ # $$BASEDIR/lib/flite/lang
+
+
+ # 64-bit Linux
+ message(Building for GNU/Linux 64bit/x64 (g++-64))
+
+ LIBS += \
+ -L/usr/lib \
+ -lm \
+ -lflite_cmu_us_kal \
+ -lflite_usenglish \
+ -lflite_cmulex \
+ -lflite \
+ -lSDL \
+ -lSDLmain
+
+ exists(/usr/include/osg) {
+ message("Building support for OpenSceneGraph")
+ DEPENDENCIES_PRESENT += osg
+ # Include OpenSceneGraph libraries
+ LIBS += -losg \
+ -losgViewer
+ DEFINES += QGC_OSG_ENABLED
+ }
+
+ exists(/usr/include/osgEarth) {
+ message("Building support for osgEarth")
+ DEPENDENCIES_PRESENT += osgearth
+ # Include osgEarth libraries
+ LIBS += -losgEarth \
+ -losgEarthUtil
+ DEFINES += QGC_OSGEARTH_ENABLED
+ }
+
+ exists(/usr/local/include/libfreenect) {
+ message("Building support for libfreenect")
+ DEPENDENCIES_PRESENT += libfreenect
+ INCLUDEPATH += /usr/include/libusb-1.0
+ # Include libfreenect libraries
+ LIBS += -lfreenect
+ DEFINES += QGC_LIBFREENECT_ENABLED
+ }
+
+ QMAKE_POST_LINK += && cp -rf $$BASEDIR/models $$DESTDIR
+ QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$DESTDIR
+ QMAKE_POST_LINK += && mkdir -p $$DESTDIR/images
+ QMAKE_POST_LINK += && cp -rf $$BASEDIR/images/Vera.ttf $$DESTDIR/images/Vera.ttf
+
+ # osg/osgEarth dynamic casts might fail without this compiler option.
+ # see http://osgearth.org/wiki/FAQ for details.
+ QMAKE_CXXFLAGS += -Wl,-E
+}
+
+# Windows (32bit)
+win32-msvc2008 {
+
+ message(Building for Windows Visual Studio 2008 (32bit))
+
+ CONFIG += qaxcontainer
+
+ # Special settings for debug
+ #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
+
+exists($$BASEDIR/lib/osg123) {
+message("Building support for OSG")
+DEPENDENCIES_PRESENT += osg
+
+# Include OpenSceneGraph and osgEarth libraries
+INCLUDEPATH += $$BASEDIR/lib/osgEarth/win32/include \
+ $$BASEDIR/lib/osgEarth_3rdparty/win32/OpenSceneGraph-2.8.2/include
+LIBS += -L$$BASEDIR/lib/osgEarth_3rdparty/win32/OpenSceneGraph-2.8.2/lib \
+ -losg \
+ -losgViewer \
+ -losgGA \
+ -losgDB \
+ -losgText \
+ -lOpenThreads
+DEFINES += QGC_OSG_ENABLED
+exists($$BASEDIR/lib/osgEarth123) {
+ DEPENDENCIES_PRESENT += osgearth
+ message("Building support for osgEarth")
+ DEFINES += QGC_OSGEARTH_ENABLED
+ LIBS += -L$$BASEDIR/lib/osgEarth/win32/lib \
+ -losgEarth \
+ -losgEarthUtil
+}
+}
+
+ RC_FILE = $$BASEDIR/qgroundcontrol.rc
+
+ # Copy dependencies
+ BASEDIR_WIN = $$replace(BASEDIR,"/","\\")
+ TARGETDIR_WIN = $$replace(TARGETDIR,"/","\\")
+
+ debug {
+ QMAKE_POST_LINK += && copy /Y \"$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll\" \"$$TARGETDIR_WIN\\debug\\SDL.dll\"
+ QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\audio\" \"$$TARGETDIR_WIN\debug\audio\" /S /E /Y
+ QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\models\" \"$$TARGETDIR_WIN\debug\models\" /S /E /Y
+ QMAKE_POST_LINK += && copy /Y \"$$BASEDIR/images/earth.html $$TARGETDIR_WIN\debug\"
+ }
+
+ release {
+ QMAKE_POST_LINK += && copy /Y \"$$BASEDIR_WIN\lib\sdl\win32\SDL.dll\" \"$$TARGETDIR_WIN\release\SDL.dll\"
+ QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\audio\" \"$$TARGETDIR_WIN\release\audio\" /S /E /Y
+ QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\models\" \"$$TARGETDIR_WIN\release\models\" /S /E /Y
+ QMAKE_POST_LINK += && copy /Y \"$$BASEDIR/images/earth.html $$TARGETDIR_WIN\release\"
+ }
+
+}
+
+# Windows (32bit)
+win32-g++ {
+
+ message(Building for Windows Platform (32bit))
+
+ # Special settings for debug
+ #CONFIG += CONSOLE
+
+ INCLUDEPATH += $$BASEDIR/lib/sdl/include \
+ $$BASEDIR/lib/opal/include #\ #\
+ #"C:\Program Files\Microsoft SDKs\Windows\v7.0\Include"
+
+ LIBS += -L$$BASEDIR/lib/sdl/win32 \
+ -lmingw32 -lSDLmain -lSDL -mwindows
+
+
+
+ debug {
+ #DESTDIR = $$BUILDDIR/debug
+ }
+
+ release {
+ #DESTDIR = $$BUILDDIR/release
+ }
+
+ RC_FILE = $$BASEDIR/qgroundcontrol.rc
+
+ # Copy dependencies
+
+ debug {
+ QMAKE_POST_LINK += && cp $$BASEDIR/lib/sdl/win32/SDL.dll $$TARGETDIR/debug/SDL.dll
+ QMAKE_POST_LINK += && cp -r $$BASEDIR/audio $$TARGETDIR/debug/audio
+ QMAKE_POST_LINK += && cp -r $$BASEDIR/models $$TARGETDIR/debug/models
+ }
+
+ release {
+ QMAKE_POST_LINK += && cp $$BASEDIR/lib/sdl/win32/SDL.dll $$TARGETDIR/release/SDL.dll
+ QMAKE_POST_LINK += && cp -r $$BASEDIR/audio $$TARGETDIR/release/audio
+ QMAKE_POST_LINK += && cp -r $$BASEDIR/models $$TARGETDIR/release/models
+ }
+
+ # osg/osgEarth dynamic casts might fail without this compiler option.
+ # see http://osgearth.org/wiki/FAQ for details.
+ QMAKE_CXXFLAGS += -Wl,-E
+}
diff --git a/src/Core.cc b/src/Core.cc
index d35e3ce..e49a06c 100644
--- a/src/Core.cc
+++ b/src/Core.cc
@@ -157,7 +157,7 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv)
**/
Core::~Core()
{
- mainWindow->storeSettings();
+ //mainWindow->storeSettings();
mainWindow->hide();
mainWindow->deleteLater();
// Delete singletons
diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc
index 76c4fde..802cf17 100644
--- a/src/comm/LinkManager.cc
+++ b/src/comm/LinkManager.cc
@@ -32,6 +32,7 @@ This file is part of the QGROUNDCONTROL project
#include
#include
#include "LinkManager.h"
+#include
#include
@@ -65,6 +66,7 @@ LinkManager::~LinkManager()
void LinkManager::add(LinkInterface* link)
{
+ if(!link) return;
links.append(link);
emit newLink(link);
}
@@ -73,6 +75,7 @@ void LinkManager::addProtocol(LinkInterface* link, ProtocolInterface* protocol)
{
// Connect link to protocol
// the protocol will receive new bytes from the link
+ if(!link || !protocol) return;
connect(link, SIGNAL(bytesReceived(LinkInterface*, QByteArray)), protocol, SLOT(receiveBytes(LinkInterface*, QByteArray)));
// Store the connection information in the protocol links map
protocolLinks.insertMulti(protocol, link);
@@ -91,7 +94,8 @@ bool LinkManager::connectAll()
foreach (LinkInterface* link, links)
{
- if(! link->connect()) allConnected = false;
+ if(!link) {}
+ else if(!link->connect()) allConnected = false;
}
return allConnected;
@@ -103,7 +107,9 @@ bool LinkManager::disconnectAll()
foreach (LinkInterface* link, links)
{
- if(! link->disconnect()) allDisconnected = false;
+ //static int i=0;
+ if(!link){}
+ else if(!link->disconnect()) allDisconnected = false;
}
return allDisconnected;
@@ -111,14 +117,32 @@ bool LinkManager::disconnectAll()
bool LinkManager::connectLink(LinkInterface* link)
{
+ if(!link) return false;
return link->connect();
}
bool LinkManager::disconnectLink(LinkInterface* link)
{
+ if(!link) return false;
return link->disconnect();
}
+bool LinkManager::removeLink(LinkInterface* link)
+{
+ if(link)
+ {
+ for (int i=0; i < QList(links).size(); i++)
+ {
+ if(link==links.at(i))
+ {
+ links.removeAt(i); //remove from link list
+ }
+ }
+ return true;
+ }
+ return false;
+}
+
/**
* The access time is linear in the number of links.
*
diff --git a/src/comm/LinkManager.h b/src/comm/LinkManager.h
index b176875..8d283c3 100644
--- a/src/comm/LinkManager.h
+++ b/src/comm/LinkManager.h
@@ -67,6 +67,8 @@ public slots:
void add(LinkInterface* link);
void addProtocol(LinkInterface* link, ProtocolInterface* protocol);
+ bool removeLink(LinkInterface* link);
+
bool connectAll();
bool connectLink(LinkInterface* link);
diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc
index 8350641..b992633 100644
--- a/src/comm/MAVLinkProtocol.cc
+++ b/src/comm/MAVLinkProtocol.cc
@@ -159,7 +159,9 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
switch (heartbeat.autopilot)
{
case MAV_AUTOPILOT_GENERIC:
+
uas = new UAS(this, message.sysid);
+
// Connect this robot to the UAS object
connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), uas, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
break;
@@ -202,11 +204,15 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
break;
}
+ // Set the autopilot type
+ uas->setAutopilotType((int)heartbeat.autopilot);
// Make UAS aware that this link can be used to communicate with the actual robot
uas->addLink(link);
+
// Now add UAS to "official" list, which makes the whole application aware of it
UASManager::instance()->addUAS(uas);
+
}
// Only count message if UAS exists for this message
diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc
index eec64a2..f35a129 100644
--- a/src/comm/MAVLinkSimulationLink.cc
+++ b/src/comm/MAVLinkSimulationLink.cc
@@ -660,7 +660,7 @@ qint64 MAVLinkSimulationLink::bytesAvailable()
void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
{
- qDebug() << "Simulation received " << size << " bytes from groundstation: ";
+ //qDebug() << "Simulation received " << size << " bytes from groundstation: ";
// Increase write counter
//bitsSentTotal += size * 8;
@@ -838,9 +838,9 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
}
unsigned char v=data[i];
- fprintf(stderr,"%02x ", v);
+ //fprintf(stderr,"%02x ", v);
}
- fprintf(stderr,"\n");
+ //fprintf(stderr,"\n");
readyBufferMutex.lock();
for (int i = 0; i < streampointer; i++)
diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc
index d96320b..404a8db 100644
--- a/src/comm/SerialLink.cc
+++ b/src/comm/SerialLink.cc
@@ -36,6 +36,7 @@ This file is part of the QGROUNDCONTROL project
#include "LinkManager.h"
#include "QGC.h"
#include
+#include
#ifdef _WIN32
#include "windows.h"
#endif
@@ -59,9 +60,18 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
// Load defaults from settings
QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
+ settings.sync();
if (settings.contains("SERIALLINK_COMM_PORT"))
{
this->porthandle = settings.value("SERIALLINK_COMM_PORT").toString();
+ }
+
+ // *nix (Linux, MacOS tested) serial port support
+ port = new QextSerialPort(porthandle, QextSerialPort::Polling);
+ //port = new QextSerialPort(porthandle, QextSerialPort::EventDriven);
+
+ if (settings.contains("SERIALLINK_COMM_PORT"))
+ {
setBaudRate(settings.value("SERIALLINK_COMM_BAUD").toInt());
setParityType(settings.value("SERIALLINK_COMM_PARITY").toInt());
setStopBitsType(settings.value("SERIALLINK_COMM_STOPBITS").toInt());
@@ -76,6 +86,12 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
this->stopBits = stopBits;
this->timeout = 1; ///< The timeout controls how long the program flow should wait for new serial bytes. As we're polling, we don't want to wait at all.
}
+ port->setTimeout(timeout); // Timeout of 0 ms, we don't want to wait for data, we just poll again next time
+ port->setBaudRate(baudrate);
+ port->setFlowControl(flow);
+ port->setParity(parity);
+ port->setDataBits(dataBits);
+ port->setStopBits(stopBits);
// Set the port name
if (porthandle == "")
@@ -104,15 +120,7 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
//some other error occurred. Inform user.
}
#else
- // *nix (Linux, MacOS tested) serial port support
- port = new QextSerialPort(porthandle, QextSerialPort::Polling);
- //port = new QextSerialPort(porthandle, QextSerialPort::EventDriven);
- port->setTimeout(timeout); // Timeout of 0 ms, we don't want to wait for data, we just poll again next time
- port->setBaudRate(baudrate);
- port->setFlowControl(flow);
- port->setParity(parity);
- port->setDataBits(dataBits);
- port->setStopBits(stopBits);
+
#endif
// Link is setup, register it with link manager
@@ -122,7 +130,7 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
SerialLink::~SerialLink()
{
disconnect();
- delete port;
+ if(port) delete port;
port = NULL;
}
@@ -186,7 +194,7 @@ void SerialLink::writeBytes(const char* data, qint64 size)
{
unsigned char v=data[i];
- fprintf(stderr,"%02x ", v);
+ //fprintf(stderr,"%02x ", v);
}
}
}
@@ -255,6 +263,8 @@ bool SerialLink::disconnect()
port->close();
dataMutex.unlock();
+ if(this->isRunning()) this->terminate(); //stop running the thread, restart it upon connect
+
bool closed = true;
//port->isOpen();
@@ -298,15 +308,6 @@ bool SerialLink::connect()
**/
bool SerialLink::hardwareConnect()
{
- // Store settings
- QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
- settings.setValue("SERIALLINK_COMM_PORT", this->porthandle);
- settings.setValue("SERIALLINK_COMM_BAUD", this->baudrate);
- settings.setValue("SERIALLINK_COMM_PARITY", this->parity);
- settings.setValue("SERIALLINK_COMM_STOPBITS", this->stopBits);
- settings.setValue("SERIALLINK_COMM_DATABITS", this->dataBits);
- settings.sync();
-
QObject::connect(port, SIGNAL(aboutToClose()), this, SIGNAL(disconnected()));
port->open(QIODevice::ReadWrite);
@@ -323,6 +324,15 @@ bool SerialLink::hardwareConnect()
if(connectionUp) {
emit connected();
emit connected(true);
+
+ // Store settings
+ QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
+ settings.setValue("SERIALLINK_COMM_PORT", this->porthandle);
+ settings.setValue("SERIALLINK_COMM_BAUD", getBaudRate());
+ settings.setValue("SERIALLINK_COMM_PARITY", getParityType());
+ settings.setValue("SERIALLINK_COMM_STOPBITS", getStopBitsType());
+ settings.setValue("SERIALLINK_COMM_DATABITS", getDataBitsType());
+ settings.sync();
}
return connectionUp;
@@ -336,7 +346,14 @@ bool SerialLink::hardwareConnect()
**/
bool SerialLink::isConnected()
{
- return port->isOpen();
+ if (port)
+ {
+ return port->isOpen();
+ }
+ else
+ {
+ return false;
+ }
}
int SerialLink::getId()
@@ -541,7 +558,7 @@ bool SerialLink::setPortName(QString portName)
this->porthandle = "\\\\.\\" + this->porthandle;
}
#endif
- delete port;
+ if(port) delete port;
port = new QextSerialPort(porthandle, QextSerialPort::Polling);
port->setBaudRate(baudrate);
@@ -732,9 +749,16 @@ bool SerialLink::setBaudRate(int rate)
break;
}
- port->setBaudRate(this->baudrate);
- if(reconnect) connect();
- return accepted;
+ if (port)
+ {
+ port->setBaudRate(this->baudrate);
+ if(reconnect) connect();
+ return accepted;
+ }
+ else
+ {
+ return false;
+ }
}
bool SerialLink::setFlowType(int flow)
diff --git a/src/uas/SlugsMAV.cc b/src/uas/SlugsMAV.cc
index 025087b..edc2a4d 100644
--- a/src/uas/SlugsMAV.cc
+++ b/src/uas/SlugsMAV.cc
@@ -169,10 +169,16 @@ void SlugsMAV::emitSignals (void){
case 2:
emit slugsAirData(uasId, mlAirData);
emit slugsDiagnostic(uasId,mlDiagnosticData);
+
break;
case 3:
- emit slugsPilotConsolePWM(uasId,mlPilotConsoleData);
+ emit remoteControlChannelScaledChanged(0,(mlPilotConsoleData.de- 1000.0f)/1000.0f);
+ emit remoteControlChannelScaledChanged(1,(mlPilotConsoleData.dla- 1000.0f)/1000.0f);
+ emit remoteControlChannelScaledChanged(2,(mlPilotConsoleData.dr- 1000.0f)/1000.0f);
+ emit remoteControlChannelScaledChanged(3,(mlPilotConsoleData.dra- 1000.0f)/1000.0f);
+ emit remoteControlChannelScaledChanged(0,(mlPilotConsoleData.dt- 1000.0f)/1000.0f);
+
emit slugsPWM(uasId, mlPwmCommands);
break;
@@ -184,11 +190,13 @@ void SlugsMAV::emitSignals (void){
case 5:
emit slugsFilteredData(uasId,mlFilteredData);
emit slugsGPSDateTime(uasId, mlGpsDateTime);
+
break;
case 6:
emit slugsActionAck(uasId,mlActionAck);
emit emitGpsSignals();
+
break;
}
@@ -212,20 +220,30 @@ void SlugsMAV::emitSignals (void){
#ifdef MAVLINK_ENABLED_SLUGS
void SlugsMAV::emitGpsSignals (void){
- if (mlGpsData.fix_type > 0){
+ qDebug()<<"After Emit GPS Signal"< 0){
emit globalPositionChanged(this,
mlGpsData.lon,
mlGpsData.lat,
mlGpsData.alt,
0.0);
- // Smaller than threshold and not NaN
- if (mlGpsData.v < 1000000 && mlGpsData.v == mlGpsData.v){
- emit speedChanged(this, (double)mlGpsData.v, 0.0, 0.0, 0.0);
- } else {
- emit textMessageReceived(uasId, uasId, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(mlGpsData.v));
- }
- }
+ emit slugsGPSCogSog(uasId,mlGpsData.hdg, mlGpsData.v);
+
+// // Smaller than threshold and not NaN
+// if (mlGpsData.v < 1000000 && mlGpsData.v == mlGpsData.v){
+// // emit speedChanged(this, (double)mlGpsData.v, 0.0, 0.0, 0.0);
+
+// }
+// else {
+// emit textMessageReceived(uasId, uasId, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(mlGpsData.v));
+// }
+ //}
+
}
void SlugsMAV::emitPidSignal()
diff --git a/src/uas/SlugsMAV.h b/src/uas/SlugsMAV.h
index 295c820..c30996d 100644
--- a/src/uas/SlugsMAV.h
+++ b/src/uas/SlugsMAV.h
@@ -47,6 +47,7 @@ public slots:
signals:
void slugsRawImu(int uasId, const mavlink_raw_imu_t& rawData);
+ void slugsGPSCogSog(int uasId, double cog, double sog);
#ifdef MAVLINK_ENABLED_SLUGS
@@ -67,6 +68,8 @@ signals:
void slugsBootMsg(int uasId, mavlink_boot_t& boot);
void slugsAttitude(int uasId, mavlink_attitude_t& attitude);
+
+
#endif
protected:
diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc
index 3f42d6f..f503a06 100644
--- a/src/uas/UAS.cc
+++ b/src/uas/UAS.cc
@@ -43,12 +43,16 @@ This file is part of the QGROUNDCONTROL project
#include "GAudioOutput.h"
#include "MAVLinkProtocol.h"
#include "QGCMAVLink.h"
+#include "LinkManager.h"
+#include "SerialLink.h"
+
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
uasId(id),
startTime(MG::TIME::getGroundTimeNow()),
commStatus(COMM_DISCONNECTED),
name(""),
+ autopilot(-1),
links(new QList()),
unknownPackets(),
mavlink(protocol),
@@ -93,6 +97,7 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
UAS::~UAS()
{
delete links;
+ links=NULL;
}
int UAS::getUASID() const
@@ -124,6 +129,7 @@ void UAS::setSelected()
void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
+ if (!link) return;
if (!links->contains(link))
{
addLink(link);
@@ -149,8 +155,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
if (this->type != mavlink_msg_heartbeat_get_type(&message))
{
this->type = mavlink_msg_heartbeat_get_type(&message);
+ this->autopilot = mavlink_msg_heartbeat_get_autopilot(&message);
emit systemTypeSet(this, type);
}
+
break;
case MAVLINK_MSG_ID_BOOT:
getStatusForCode((int)MAV_STATE_BOOT, uasState, stateDescription);
@@ -328,6 +336,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "Vz", pos.vz, time);
emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
+
+// qDebug()<<"Local Position = "<notifyPositive();
}
positionLock = true;
-
- // Send to patch antenna
- // FIXME Message re-routing should be implemented differently
- //mavlink_message_t msg;
- //mavlink_msg_global_position_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, pos.usec, pos.lat, pos.lon, pos.alt, pos.vx, pos.vy, pos.vz);
- //sendMessage(msg);
+ //TODO fix this hack for forwarding of global position for patch antenna tracking
+ forwardMessage(message);
}
break;
case MAVLINK_MSG_ID_GPS_RAW:
@@ -830,8 +838,31 @@ void UAS::sendMessage(mavlink_message_t message)
}
}
+void UAS::forwardMessage(mavlink_message_t message)
+{
+ // Emit message on all links that are currently connected
+ QListlink_list = LinkManager::instance()->getLinksForProtocol(mavlink);
+ foreach(LinkInterface* link, link_list)
+ {
+ SerialLink* serial = dynamic_cast(link);
+ if(serial != 0)
+ {
+
+ for(int i=0;isize();i++)
+ {
+ if(serial != links->at(i))
+ {
+ qDebug()<<"Forwarding Over link: "<getName()<<" "<append(link);
}
//links->append(link);
- //qDebug() << " ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK";
+ qDebug() << link<<" ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK";
}
/**
diff --git a/src/uas/UAS.h b/src/uas/UAS.h
index 241e3db..22c655f 100644
--- a/src/uas/UAS.h
+++ b/src/uas/UAS.h
@@ -79,25 +79,26 @@ public:
/** @brief Get the links associated with this robot */
QList* getLinks();
- double getLocalX() const { return localX; };
- double getLocalY() const { return localY; };
- double getLocalZ() const { return localZ; };
- double getLatitude() const { return latitude; };
- double getLongitude() const { return longitude; };
- double getAltitude() const { return altitude; };
+ double getLocalX() const { return localX; }
+ double getLocalY() const { return localY; }
+ double getLocalZ() const { return localZ; }
+ double getLatitude() const { return latitude; }
+ double getLongitude() const { return longitude; }
+ double getAltitude() const { return altitude; }
- double getRoll() const { return roll; };
- double getPitch() const { return pitch; };
- double getYaw() const { return yaw; };
+ double getRoll() const { return roll; }
+ double getPitch() const { return pitch; }
+ double getYaw() const { return yaw; }
friend class UASWaypointManager;
protected:
int uasId; ///< Unique system ID
- int type; ///< UAS type (from type enum)
+ unsigned char type; ///< UAS type (from type enum)
quint64 startTime; ///< The time the UAS was switched on
CommStatus commStatus; ///< Communication status
QString name; ///< Human-friendly name of the vehicle, e.g. bravo
+ int autopilot; ///< Type of the Autopilot: -1: None, 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
QList* links; ///< List of links this UAS can be reached by
QList unknownPackets; ///< Packet IDs which are unknown and have been received
MAVLinkProtocol* mavlink; ///< Reference to the MAVLink instance
@@ -164,6 +165,8 @@ protected:
public:
UASWaypointManager &getWaypointManager(void) { return waypointManager; }
int getSystemType();
+ int getAutopilotType() {return autopilot;}
+ void setAutopilotType(int apType) { autopilot = apType;}
public slots:
/** @brief Launches the system **/
@@ -215,6 +218,9 @@ public slots:
/** @brief Send a message over all links this UAS can be reached with (!= all links) */
void sendMessage(mavlink_message_t message);
+ /** @brief Temporary Hack for sending packets to patch Antenna. Send a message over all serial links except for this UAS's */
+ void forwardMessage(mavlink_message_t message);
+
/** @brief Set this UAS as the system currently in focus, e.g. in the main display widgets */
void setSelected();
diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h
index 1aa7c88..332f90e 100644
--- a/src/uas/UASInterface.h
+++ b/src/uas/UASInterface.h
@@ -157,6 +157,9 @@ public:
return color;
}
+ virtual int getAutopilotType() = 0;
+ virtual void setAutopilotType(int apType)= 0;
+
public slots:
/** @brief Launches the system/Liftof **/
@@ -241,6 +244,8 @@ public slots:
virtual void startGyroscopeCalibration() = 0;
virtual void startPressureCalibration() = 0;
+
+
protected:
QColor color;
diff --git a/src/uas/UASManager.cc b/src/uas/UASManager.cc
index bba66dd..fabfec6 100644
--- a/src/uas/UASManager.cc
+++ b/src/uas/UASManager.cc
@@ -85,6 +85,11 @@ void UASManager::addUAS(UASInterface* uas)
}
}
+QList UASManager::getUASList()
+{
+ return systems.values();
+}
+
UASInterface* UASManager::getActiveUAS()
{
if(!activeUAS)
@@ -96,6 +101,11 @@ UASInterface* UASManager::getActiveUAS()
return activeUAS; ///< Return zero pointer if no UAS has been loaded
}
+UASInterface* UASManager::silentGetActiveUAS()
+{
+ return activeUAS; ///< Return zero pointer if no UAS has been loaded
+}
+
bool UASManager::launchActiveUAS()
{
// If the active UAS is set, execute command
diff --git a/src/uas/UASManager.h b/src/uas/UASManager.h
index 7b8dabf..b4d9778 100644
--- a/src/uas/UASManager.h
+++ b/src/uas/UASManager.h
@@ -57,6 +57,7 @@ public:
* @return NULL pointer if no UAS exists, active UAS else
**/
UASInterface* getActiveUAS();
+ UASInterface* silentGetActiveUAS();
/**
* @brief Get the UAS with this id
*
@@ -68,6 +69,8 @@ public:
**/
UASInterface* getUASForId(int id);
+ QList getUASList();
+
public slots:
diff --git a/src/ui/CommConfigurationWindow.cc b/src/ui/CommConfigurationWindow.cc
index 0708aee..33e57ba 100644
--- a/src/ui/CommConfigurationWindow.cc
+++ b/src/ui/CommConfigurationWindow.cc
@@ -47,6 +47,7 @@ This file is part of the QGROUNDCONTROL project
#endif
#include "MAVLinkProtocol.h"
#include "MAVLinkSettingsWidget.h"
+#include "LinkManager.h"
CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolInterface* protocol, QWidget *parent, Qt::WindowFlags flags) : QWidget(parent, flags)
{
@@ -58,6 +59,10 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
// add link types
ui.linkType->addItem("Serial",QGC_LINK_SERIAL);
ui.linkType->addItem("UDP",QGC_LINK_UDP);
+ ui.linkType->addItem("Simulation",QGC_LINK_SIMULATION);
+ ui.linkType->addItem("Serial Forwarding",QGC_LINK_FORWARDING);
+
+ ui.connectionType->addItem("MAVLink", QGC_PROTOCOL_MAVLINK);
// Create action to open this menu
// Create configuration action for this link
@@ -195,11 +200,20 @@ void CommConfigurationWindow::setLinkName(QString name)
void CommConfigurationWindow::remove()
{
- link->disconnect();
- //delete link;
- //delete action;
+ if(action) delete action; //delete action first since it has a pointer to link
+ action=NULL;
+
+ if(link)
+ {
+ LinkManager::instance()->removeLink(link); //remove link from LinkManager list
+ link->disconnect(); //disconnect port, and also calls terminate() to stop the thread
+ if (link->isRunning()) link->terminate(); // terminate() the serial thread just in case it is still running
+ link->wait(); // wait() until thread is stoped before deleting
+ delete link;
+ }
+ link=NULL;
+
this->window()->close();
- qDebug() << "TODO: Link cannot be deleted: CommConfigurationWindow::remove() NOT IMPLEMENTED!";
}
void CommConfigurationWindow::connectionState(bool connect)
diff --git a/src/ui/CommConfigurationWindow.h b/src/ui/CommConfigurationWindow.h
index fce37db..93f1566 100644
--- a/src/ui/CommConfigurationWindow.h
+++ b/src/ui/CommConfigurationWindow.h
@@ -42,7 +42,14 @@ This file is part of the QGROUNDCONTROL project
enum qgc_link_t
{
QGC_LINK_SERIAL,
- QGC_LINK_UDP
+ QGC_LINK_UDP,
+ QGC_LINK_SIMULATION,
+ QGC_LINK_FORWARDING
+};
+
+enum qgc_protocol_t
+{
+ QGC_PROTOCOL_MAVLINK
};
#ifdef OPAL_RT
diff --git a/src/ui/CommSettings.ui b/src/ui/CommSettings.ui
index 8aec750..71a4c30 100644
--- a/src/ui/CommSettings.ui
+++ b/src/ui/CommSettings.ui
@@ -43,23 +43,7 @@
-
-
-
-
-
- Serial Link
-
-
- -
-
- UDP
-
-
- -
-
- Simulation
-
-
-
+
-
@@ -71,13 +55,8 @@
-
- 0
+ -1
-
-
-
- MAVLink
-
-
diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc
index ece981a..b19f097 100644
--- a/src/ui/MainWindow.cc
+++ b/src/ui/MainWindow.cc
@@ -45,8 +45,10 @@
*
* @see QMainWindow::show()
**/
-MainWindow::MainWindow(QWidget *parent) :
+MainWindow::MainWindow(QWidget *parent):
QMainWindow(parent),
+ toolsMenuActions(),
+ currentView(VIEW_MAVLINK),
settings()
{
this->hide();
@@ -55,11 +57,11 @@ MainWindow::MainWindow(QWidget *parent) :
// Setup user interface
ui.setupUi(this);
- buildWidgets();
+ buildCommonWidgets();
- connectWidgets();
+ connectCommonWidgets();
- arrangeCenterStack();
+ arrangeCommonCenterStack();
configureWindowName();
@@ -73,24 +75,15 @@ MainWindow::MainWindow(QWidget *parent) :
// Set style sheet as last step
reloadStylesheet();
-
// Create actions
- connectActions();
+ connectCommonActions();
- // Load widgets and show application windowa
- loadWidgets();
+ // Load mavlink view as default widget set
+ loadMAVLinkView();
// Adjust the size
adjustSize();
- // Set menu
- QMenu* widgetMenu = createDockWidgetMenu();
- widgetMenu->setTitle("Widgets");
- ui.menuBar->addMenu(widgetMenu);
-// QMenu* centerMenu = createCenterWidgetMenu();
-// centerMenu->setTitle("Center");
-// ui.menuBar->addMenu(centerMenu);
-
// Load previous widget setup
// FIXME WORK IN PROGRESS
@@ -125,109 +118,148 @@ MainWindow::~MainWindow()
statusBar = NULL;
}
-void MainWindow::storeSettings()
+void MainWindow::buildCommonWidgets()
{
- QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
+ //TODO: move protocol outside UI
+ mavlink = new MAVLinkProtocol();
- QList dockwidgets = qFindChildren(this);
- if (dockwidgets.size())
- {
- settings.beginGroup("mainwindow/dockwidgets");
- for (int i = 0; i < dockwidgets.size(); ++i)
- {
- QDockWidget *dockWidget = dockwidgets.at(i);
- if (dockWidget->parentWidget() == this)
- {
- settings.setValue(dockWidget->windowTitle(), QVariant(dockWidget->isVisible()));
- }
- }
- settings.endGroup();
- }
- settings.sync();
-}
+ // Dock widgets
+ controlDockWidget = new QDockWidget(tr("Control"), this);
+ controlDockWidget->setWidget( new UASControlWidget(this) );
+ addToToolsMenu (controlDockWidget, tr("UAS Control"), SLOT(showToolWidget()), MENU_UAS_CONTROL, Qt::LeftDockWidgetArea);
+
+ listDockWidget = new QDockWidget(tr("Unmanned Systems"), this);
+ listDockWidget->setWidget( new UASListWidget(this) );
+ addToToolsMenu (listDockWidget, tr("UAS List"), SLOT(showToolWidget()), MENU_UAS_LIST, Qt::RightDockWidgetArea);
+
+ waypointsDockWidget = new QDockWidget(tr("Waypoint List"), this);
+ waypointsDockWidget->setWidget( new WaypointList(this, NULL) );
+ addToToolsMenu (waypointsDockWidget, tr("Waypoints List"), SLOT(showToolWidget()), MENU_WAYPOINTS, Qt::BottomDockWidgetArea);
+
+ infoDockWidget = new QDockWidget(tr("Status Details"), this);
+ infoDockWidget->setWidget( new UASInfoWidget(this) );
+ addToToolsMenu (infoDockWidget, tr("Status Details"), SLOT(showToolWidget()), MENU_STATUS, Qt::RightDockWidgetArea);
+
+
+ debugConsoleDockWidget = new QDockWidget(tr("Communication Console"), this);
+ debugConsoleDockWidget->setWidget( new DebugConsole(this) );
+ addToToolsMenu (debugConsoleDockWidget, tr("Communication Console"), SLOT(showToolWidget()), MENU_DEBUG_CONSOLE, Qt::BottomDockWidgetArea);
+
+ // Center widgets
+ mapWidget = new MapWidget(this);
+ addToCentralWidgetsMenu (mapWidget, "Maps", SLOT(showCentralWidget()),CENTRAL_MAP);
+
+ protocolWidget = new XMLCommProtocolWidget(this);
+ addToCentralWidgetsMenu (protocolWidget, "Mavlink Generator", SLOT(showCentralWidget()),CENTRAL_PROTOCOL);
-QMenu* MainWindow::createCenterWidgetMenu()
-{
- QMenu* menu = NULL;
- QStackedWidget* centerStack = dynamic_cast(centralWidget());
- if (centerStack)
- {
- if (centerStack->count() > 0)
- {
- menu = new QMenu(this);
- for (int i = 0; i < centerStack->count(); ++i)
- {
- //menu->addAction(centerStack->widget(i)->actions())
- }
- }
- }
- return menu;
-}
-QMenu* MainWindow::createDockWidgetMenu()
-{
- QMenu *menu = 0;
-#ifndef QT_NO_DOCKWIDGET
- QList dockwidgets = qFindChildren(this);
- if (dockwidgets.size())
- {
- menu = new QMenu(this);
- for (int i = 0; i < dockwidgets.size(); ++i)
- {
- QDockWidget *dockWidget = dockwidgets.at(i);
- if (dockWidget->parentWidget() == this)
- {
- menu->addAction(dockwidgets.at(i)->toggleViewAction());
- }
- }
- menu->addSeparator();
- }
-#endif
- return menu;
}
-//QList* MainWindow::getMainWidgets()
+//=======
+//void MainWindow::storeSettings()
//{
+// QSettings settings(QGC::COMPANYNAME, QGC::APPNAME);
+
+// QList dockwidgets = qFindChildren(this);
+// if (dockwidgets.size())
+// {
+// settings.beginGroup("mainwindow/dockwidgets");
+// for (int i = 0; i < dockwidgets.size(); ++i)
+// {
+// QDockWidget *dockWidget = dockwidgets.at(i);
+// if (dockWidget->parentWidget() == this)
+// {
+// settings.setValue(dockWidget->windowTitle(), QVariant(dockWidget->isVisible()));
+// }
+// }
+// settings.endGroup();
+// }
+// settings.sync();
+//}
+//QMenu* MainWindow::createCenterWidgetMenu()
+//{
+// QMenu* menu = NULL;
+// QStackedWidget* centerStack = dynamic_cast(centralWidget());
+// if (centerStack)
+// {
+// if (centerStack->count() > 0)
+// {
+// menu = new QMenu(this);
+// for (int i = 0; i < centerStack->count(); ++i)
+// {
+// //menu->addAction(centerStack->widget(i)->actions())
+// }
+// }
+// }
+// return menu;
//}
-//QMenu* QMainWindow::getDockWidgetMenu()
+//QMenu* MainWindow::createDockWidgetMenu()
//{
-// Q_D(QMainWindow);
// QMenu *menu = 0;
//#ifndef QT_NO_DOCKWIDGET
// QList dockwidgets = qFindChildren(this);
-// if (dockwidgets.size()) {
+// if (dockwidgets.size())
+// {
// menu = new QMenu(this);
-// for (int i = 0; i < dockwidgets.size(); ++i) {
+// for (int i = 0; i < dockwidgets.size(); ++i)
+// {
// QDockWidget *dockWidget = dockwidgets.at(i);
-// if (dockWidget->parentWidget() == this
-// && d->layout->contains(dockWidget)) {
+// if (dockWidget->parentWidget() == this)
+// {
// menu->addAction(dockwidgets.at(i)->toggleViewAction());
// }
// }
// menu->addSeparator();
// }
-//#endif // QT_NO_DOCKWIDGET
-//#ifndef QT_NO_TOOLBAR
-// QList toolbars = qFindChildren(this);
-// if (toolbars.size()) {
-// if (!menu)
-// menu = new QMenu(this);
-// for (int i = 0; i < toolbars.size(); ++i) {
-// QToolBar *toolBar = toolbars.at(i);
-// if (toolBar->parentWidget() == this
-// && d->layout->contains(toolBar)) {
-// menu->addAction(toolbars.at(i)->toggleViewAction());
-// }
-// }
-// }
//#endif
-// Q_UNUSED(d);
// return menu;
//}
-void MainWindow::buildWidgets()
+////QList* MainWindow::getMainWidgets()
+////{
+
+////}
+
+////QMenu* QMainWindow::getDockWidgetMenu()
+////{
+//// Q_D(QMainWindow);
+//// QMenu *menu = 0;
+////#ifndef QT_NO_DOCKWIDGET
+//// QList dockwidgets = qFindChildren(this);
+//// if (dockwidgets.size()) {
+//// menu = new QMenu(this);
+//// for (int i = 0; i < dockwidgets.size(); ++i) {
+//// QDockWidget *dockWidget = dockwidgets.at(i);
+//// if (dockWidget->parentWidget() == this
+//// && d->layout->contains(dockWidget)) {
+//// menu->addAction(dockwidgets.at(i)->toggleViewAction());
+//// }
+//// }
+//// menu->addSeparator();
+//// }
+////#endif // QT_NO_DOCKWIDGET
+////#ifndef QT_NO_TOOLBAR
+//// QList toolbars = qFindChildren(this);
+//// if (toolbars.size()) {
+//// if (!menu)
+//// menu = new QMenu(this);
+//// for (int i = 0; i < toolbars.size(); ++i) {
+//// QToolBar *toolBar = toolbars.at(i);
+//// if (toolBar->parentWidget() == this
+//// && d->layout->contains(toolBar)) {
+//// menu->addAction(toolbars.at(i)->toggleViewAction());
+//// }
+//// }
+//// }
+////#endif
+//// Q_UNUSED(d);
+//// return menu;
+////}
+//>>>>>>> master
+
+void MainWindow::buildPxWidgets()
{
//FIXME: memory of acceptList will never be freed again
QStringList* acceptList = new QStringList();
@@ -243,148 +275,465 @@ void MainWindow::buildWidgets()
acceptList2->append("Battery");
acceptList2->append("Pressure");
- //TODO: move protocol outside UI
- mavlink = new MAVLinkProtocol();
-
// Center widgets
linechartWidget = new Linecharts(this);
+ addToCentralWidgetsMenu(linechartWidget, "Line Plots", SLOT(showCentralWidget()), CENTRAL_LINECHART);
+
+
hudWidget = new HUD(320, 240, this);
- mapWidget = new MapWidget(this);
- protocolWidget = new XMLCommProtocolWidget(this);
+ addToCentralWidgetsMenu(hudWidget, "HUD", SLOT(showCentralWidget()), CENTRAL_HUD);
+
dataplotWidget = new QGCDataPlot2D(this);
+ addToCentralWidgetsMenu(dataplotWidget, "Data Plots", SLOT(showCentralWidget()), CENTRAL_DATA_PLOT);
+
#ifdef QGC_OSG_ENABLED
_3DWidget = Q3DWidgetFactory::get("PIXHAWK");
+ addToCentralWidgetsMenu(_3DWidget, "Local 3D", SLOT(showCentralWidget()), CENTRAL_3D_LOCAL);
+
#endif
#ifdef QGC_OSGEARTH_ENABLED
_3DMapWidget = Q3DWidgetFactory::get("MAP3D");
+ addToCentralWidgetsMenu(_3DMapWidget, "OSG Earth 3D", SLOT(showCentralWidget()), CENTRAL_OSGEARTH);
+
#endif
#if (defined Q_OS_WIN) | (defined Q_OS_MAC)
gEarthWidget = new QGCGoogleEarthView(this);
+ addToCentralWidgetsMenu(gEarthWidget, "Google Earth", SLOT(showCentralWidget()), CENTRAL_GOOGLE_EARTH);
+
#endif
// Dock widgets
- controlDockWidget = new QDockWidget(tr("Control"), this);
- controlDockWidget->setWidget( new UASControlWidget(this) );
- addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
- controlDockWidget->hide();
-
- infoDockWidget = new QDockWidget(tr("Status Details"), this);
- infoDockWidget->setWidget( new UASInfoWidget(this) );
- addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
- //infoDockWidget->hide();
-
- listDockWidget = new QDockWidget(tr("Unmanned Systems"), this);
- listDockWidget->setWidget( new UASListWidget(this) );
- addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
- listDockWidget->hide();
-
- waypointsDockWidget = new QDockWidget(tr("Waypoint List"), this);
- waypointsDockWidget->setWidget( new WaypointList(this, NULL) );
- addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
- waypointsDockWidget->hide();
detectionDockWidget = new QDockWidget(tr("Object Recognition"), this);
detectionDockWidget->setWidget( new ObjectDetectionView("images/patterns", this) );
- addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget);
- detectionDockWidget->hide();
+ addToToolsMenu (detectionDockWidget, tr("Object Recognition"), SLOT(showToolWidget()), MENU_DETECTION, Qt::RightDockWidgetArea);
- debugConsoleDockWidget = new QDockWidget(tr("Communication Console"), this);
- debugConsoleDockWidget->setWidget( new DebugConsole(this) );
- addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
parametersDockWidget = new QDockWidget(tr("Onboard Parameters"), this);
parametersDockWidget->setWidget( new ParameterInterface(this) );
- addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
+ addToToolsMenu (parametersDockWidget, tr("Onboard Parameters"), SLOT(showToolWidget()), MENU_PARAMETERS, Qt::RightDockWidgetArea);
watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this);
watchdogControlDockWidget->setWidget( new WatchdogControl(this) );
- addDockWidget(Qt::RightDockWidgetArea, watchdogControlDockWidget);
- watchdogControlDockWidget->hide();
+ addToToolsMenu (watchdogControlDockWidget, tr("Process Control"), SLOT(showToolWidget()), MENU_WATCHDOG, Qt::BottomDockWidgetArea);
+
hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this);
hsiDockWidget->setWidget( new HSIDisplay(this) );
- addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget);
+ addToToolsMenu (hsiDockWidget, tr("HSI"), SLOT(showToolWidget()), MENU_HSI, Qt::BottomDockWidgetArea);
+//=======
+// controlDockWidget = new QDockWidget(tr("Control"), this);
+// controlDockWidget->setWidget( new UASControlWidget(this) );
+// addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
+// controlDockWidget->hide();
+
+// infoDockWidget = new QDockWidget(tr("Status Details"), this);
+// infoDockWidget->setWidget( new UASInfoWidget(this) );
+// addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
+// //infoDockWidget->hide();
+
+// listDockWidget = new QDockWidget(tr("Unmanned Systems"), this);
+// listDockWidget->setWidget( new UASListWidget(this) );
+// addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
+// listDockWidget->hide();
+
+// waypointsDockWidget = new QDockWidget(tr("Waypoint List"), this);
+// waypointsDockWidget->setWidget( new WaypointList(this, NULL) );
+// addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
+// waypointsDockWidget->hide();
+
+// detectionDockWidget = new QDockWidget(tr("Object Recognition"), this);
+// detectionDockWidget->setWidget( new ObjectDetectionView("images/patterns", this) );
+// addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget);
+// detectionDockWidget->hide();
+
+// debugConsoleDockWidget = new QDockWidget(tr("Communication Console"), this);
+// debugConsoleDockWidget->setWidget( new DebugConsole(this) );
+// addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
+
+// parametersDockWidget = new QDockWidget(tr("Onboard Parameters"), this);
+// parametersDockWidget->setWidget( new ParameterInterface(this) );
+// addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
+
+// watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this);
+// watchdogControlDockWidget->setWidget( new WatchdogControl(this) );
+// addDockWidget(Qt::RightDockWidgetArea, watchdogControlDockWidget);
+// watchdogControlDockWidget->hide();
+
+// hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this);
+// hsiDockWidget->setWidget( new HSIDisplay(this) );
+// addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget);
+//>>>>>>> master
headDown1DockWidget = new QDockWidget(tr("System Stats"), this);
headDown1DockWidget->setWidget( new HDDisplay(acceptList, this) );
- addDockWidget(Qt::RightDockWidgetArea, headDown1DockWidget);
+
+ addToToolsMenu (headDown1DockWidget, tr("Flight Display"), SLOT(showToolWidget()), MENU_HDD_1, Qt::RightDockWidgetArea);
headDown2DockWidget = new QDockWidget(tr("Payload Status"), this);
headDown2DockWidget->setWidget( new HDDisplay(acceptList2, this) );
- addDockWidget(Qt::RightDockWidgetArea, headDown2DockWidget);
+ addToToolsMenu (headDown2DockWidget, tr("Payload Status"), SLOT(showToolWidget()), MENU_HDD_2, Qt::RightDockWidgetArea);
rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
- addDockWidget(Qt::BottomDockWidgetArea, rcViewDockWidget);
- rcViewDockWidget->hide();
+ addToToolsMenu (rcViewDockWidget, tr("Radio Control"), SLOT(showToolWidget()), MENU_RC_VIEW, Qt::BottomDockWidgetArea);
+//=======
+// addDockWidget(Qt::RightDockWidgetArea, headDown1DockWidget);
+
+// headDown2DockWidget = new QDockWidget(tr("Payload Status"), this);
+// headDown2DockWidget->setWidget( new HDDisplay(acceptList2, this) );
+// addDockWidget(Qt::RightDockWidgetArea, headDown2DockWidget);
+
+// rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
+// rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
+// addDockWidget(Qt::BottomDockWidgetArea, rcViewDockWidget);
+// rcViewDockWidget->hide();
+//>>>>>>> master
+
+ headUpDockWidget = new QDockWidget(tr("HUD"), this);
+ headUpDockWidget->setWidget( new HUD(320, 240, this));
+ addToToolsMenu (headUpDockWidget, tr("Control Indicator"), SLOT(showToolWidget()), MENU_HUD, Qt::LeftDockWidgetArea);
+
+ // Dialogue widgets
+ //FIXME: free memory in destructor
+ joystick = new JoystickInput();
+}
+
+void MainWindow::buildSlugsWidgets()
+{
+ // Center widgets
+ linechartWidget = new Linecharts(this);
+
+ // Dock widgets
headUpDockWidget = new QDockWidget(tr("Control Indicator"), this);
headUpDockWidget->setWidget( new HUD(320, 240, this));
- this->addDockWidget(Qt::LeftDockWidgetArea, headUpDockWidget);
+ addToToolsMenu (headUpDockWidget, tr("HUD"), SLOT(showToolWidget()), MENU_HUD, Qt::LeftDockWidgetArea);
+
- // SLUGS
+ rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
+ rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
+ addToToolsMenu (rcViewDockWidget, tr("Radio Control"), SLOT(showToolWidget()), MENU_RC_VIEW, Qt::BottomDockWidgetArea);
+
+
+ // Dialog widgets
slugsDataWidget = new QDockWidget(tr("Slugs Data"), this);
slugsDataWidget->setWidget( new SlugsDataSensorView(this));
- addDockWidget(Qt::LeftDockWidgetArea, slugsDataWidget);
- slugsDataWidget->hide();
+ addToToolsMenu (slugsDataWidget, tr("Telemetry Data"), SLOT(showToolWidget()), MENU_SLUGS_DATA, Qt::RightDockWidgetArea);
+
+//=======
+// this->addDockWidget(Qt::LeftDockWidgetArea, headUpDockWidget);
+
+// // SLUGS
+// slugsDataWidget = new QDockWidget(tr("Slugs Data"), this);
+// slugsDataWidget->setWidget( new SlugsDataSensorView(this));
+// addDockWidget(Qt::LeftDockWidgetArea, slugsDataWidget);
+// slugsDataWidget->hide();
+//>>>>>>> master
slugsPIDControlWidget = new QDockWidget(tr("Slugs PID Control"), this);
slugsPIDControlWidget->setWidget(new SlugsPIDControl(this));
- addDockWidget(Qt::BottomDockWidgetArea, slugsPIDControlWidget);
- slugsPIDControlWidget->hide();
+ addToToolsMenu (slugsPIDControlWidget, tr("PID Configuration"), SLOT(showToolWidget()), MENU_SLUGS_PID, Qt::LeftDockWidgetArea);
slugsHilSimWidget = new QDockWidget(tr("Slugs Hil Sim"), this);
slugsHilSimWidget->setWidget( new SlugsHilSim(this));
- addDockWidget(Qt::BottomDockWidgetArea, slugsHilSimWidget);
- slugsHilSimWidget->hide();
+ addToToolsMenu (slugsHilSimWidget, tr("HIL Sim Configuration"), SLOT(showToolWidget()), MENU_SLUGS_HIL, Qt::LeftDockWidgetArea);
+//=======
+// addDockWidget(Qt::BottomDockWidgetArea, slugsPIDControlWidget);
+// slugsPIDControlWidget->hide();
+
+// slugsHilSimWidget = new QDockWidget(tr("Slugs Hil Sim"), this);
+// slugsHilSimWidget->setWidget( new SlugsHilSim(this));
+// addDockWidget(Qt::BottomDockWidgetArea, slugsHilSimWidget);
+// slugsHilSimWidget->hide();
+//>>>>>>> master
slugsCamControlWidget = new QDockWidget(tr("Slugs Video Camera Control"), this);
slugsCamControlWidget->setWidget(new SlugsVideoCamControl(this));
- addDockWidget(Qt::BottomDockWidgetArea, slugsCamControlWidget);
- slugsCamControlWidget->hide();
+ addToToolsMenu (slugsCamControlWidget, tr("Camera Control"), SLOT(showToolWidget()), MENU_SLUGS_CAMERA, Qt::BottomDockWidgetArea);
- //FIXME: free memory in destructor
- joystick = new JoystickInput();
+}
+
+
+void MainWindow::addToCentralWidgetsMenu ( QWidget* widget,
+ const QString title,
+ const char * slotName,
+ TOOLS_WIDGET_NAMES centralWidget){
+ QAction* tempAction;
+
+
+ // Add the separator that will separate tools from central Widgets
+ if (!toolsMenuActions[CENTRAL_SEPARATOR]){
+ tempAction = ui.menuTools->addSeparator();
+ toolsMenuActions[CENTRAL_SEPARATOR] = tempAction;
+ tempAction->setData(CENTRAL_SEPARATOR);
+ }
+
+ tempAction = ui.menuTools->addAction(title);
+
+ tempAction->setCheckable(true);
+ tempAction->setData(centralWidget);
+
+ // populate the Hashes
+ toolsMenuActions[centralWidget] = tempAction;
+ dockWidgets[centralWidget] = widget;
+
+ QString chKey = buildMenuKey(SUB_SECTION_CHECKED, centralWidget, currentView);
+
+ if (!settings.contains(chKey)){
+ settings.setValue(chKey,false);
+ tempAction->setChecked(false);
+ }
+// else {
+// tempAction->setChecked(settings.value(chKey).toBool());
+// }
+
+ // connect the action
+ connect(tempAction,SIGNAL(triggered()),this, slotName);
+
+}
+
+
+void MainWindow::showCentralWidget(){
+ QAction* senderAction = qobject_cast(sender());
+ int tool = senderAction->data().toInt();
+ QString chKey;
+
+ // check the current action
+
+ if (senderAction && dockWidgets[tool]){
+
+ // uncheck all central widget actions
+ QHashIterator i(toolsMenuActions);
+ while (i.hasNext()) {
+ i.next();
+ qDebug() << "shCW" << i.key() << "read";
+ if (i.value() && i.value()->data().toInt() > 255){
+ i.value()->setChecked(false);
+
+ // update the settings
+ chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast(i.value()->data().toInt()), currentView);
+ settings.setValue(chKey,false);
+ }
+ }
+
+ // check the current action
+ qDebug() << senderAction->text();
+ senderAction->setChecked(true);
+
+ // update the central widget
+ centerStack->setCurrentWidget(dockWidgets[tool]);
+
+ // store the selected central widget
+ chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast(tool), currentView);
+ settings.setValue(chKey,true);
+
+ presentView();
+ }
+}
+
+void MainWindow::addToToolsMenu ( QWidget* widget,
+ const QString title,
+ const char * slotName,
+ TOOLS_WIDGET_NAMES tool,
+ Qt::DockWidgetArea location){
+ QAction* tempAction;
+ QString posKey, chKey;
+
+
+ if (toolsMenuActions[CENTRAL_SEPARATOR]){
+ tempAction = new QAction(title, this);
+ ui.menuTools->insertAction(toolsMenuActions[CENTRAL_SEPARATOR],
+ tempAction);
+ } else {
+ tempAction = ui.menuTools->addAction(title);
+ }
+
+ tempAction->setCheckable(true);
+ tempAction->setData(tool);
+
+ // populate the Hashes
+ toolsMenuActions[tool] = tempAction;
+ dockWidgets[tool] = widget;
+ qDebug() << widget;
+
+ posKey = buildMenuKey (SUB_SECTION_LOCATION,tool, currentView);
+
+ if (!settings.contains(posKey)){
+ settings.setValue(posKey,location);
+ dockWidgetLocations[tool] = location;
+ } else {
+ dockWidgetLocations[tool] = static_cast (settings.value(posKey).toInt());
+ }
+
+ chKey = buildMenuKey(SUB_SECTION_CHECKED,tool, currentView);
+
+ if (!settings.contains(chKey)){
+ settings.setValue(chKey,false);
+ tempAction->setChecked(false);
+ } else {
+ tempAction->setChecked(settings.value(chKey).toBool());
+ }
+
+ // connect the action
+ connect(tempAction,SIGNAL(triggered()),this, slotName);
+
+ connect(qobject_cast (dockWidgets[tool]),
+ SIGNAL(visibilityChanged(bool)), this, SLOT(updateVisibilitySettings(bool)));
+
+ connect(qobject_cast (dockWidgets[tool]),
+ SIGNAL(dockLocationChanged(Qt::DockWidgetArea)), this, SLOT(updateLocationSettings(Qt::DockWidgetArea)));
+
+}
+
+void MainWindow::showToolWidget(){
+ QAction* temp = qobject_cast(sender());
+ int tool = temp->data().toInt();
+
+
+ if (temp && dockWidgets[tool]){
+ if (temp->isChecked()){
+ addDockWidget(dockWidgetLocations[tool], qobject_cast (dockWidgets[tool]));
+ qobject_cast(dockWidgets[tool])->show();
+ } else {
+ removeDockWidget(qobject_cast(dockWidgets[tool]));
+ }
+ QString chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast(tool), currentView);
+ settings.setValue(chKey,temp->isChecked());
+ }
+}
+
+
+void MainWindow::showTheWidget (TOOLS_WIDGET_NAMES widget, VIEW_SECTIONS view){
+ bool tempVisible;
+ Qt::DockWidgetArea tempLocation;
+ QDockWidget* tempWidget = static_cast (dockWidgets[widget]);
+
+ tempVisible = settings.value(buildMenuKey (SUB_SECTION_CHECKED,widget,view)).toBool();
+
+ if (tempWidget){
+ toolsMenuActions[widget]->setChecked(tempVisible);
+ }
+
+
+ //qDebug() << buildMenuKey (SUB_SECTION_CHECKED,widget,view) << tempVisible;
+
+ tempLocation = static_cast (settings.value(buildMenuKey (SUB_SECTION_LOCATION,widget, view)).toInt());
+
+ if (tempWidget && tempVisible){
+ addDockWidget(tempLocation, tempWidget);
+ tempWidget->show();
+ }
+
+}
+
+QString MainWindow::buildMenuKey(SETTINGS_SECTIONS section, TOOLS_WIDGET_NAMES tool, VIEW_SECTIONS view){
+ // Key is built as follows: autopilot_type/section_menu/view/tool/section
+ int apType;
+
+ apType = (UASManager::instance() && UASManager::instance()->silentGetActiveUAS())?
+ UASManager::instance()->getActiveUAS()->getAutopilotType():
+ -1;
+
+ return (QString::number(apType) + "/" +
+ QString::number(SECTION_MENU) + "/" +
+ QString::number(view) + "/" +
+ QString::number(tool) + "/" +
+ QString::number(section) + "/" );
+}
+
+void MainWindow::updateVisibilitySettings (bool vis){
+ Q_UNUSED(vis);
+
+ // This is commented since when the application closes
+ // sets the visibility to false.
+
+ // TODO: A workaround is needed. The QApplication::aboutToQuit
+ // did not work
+
+ /*
+ QDockWidget* temp = qobject_cast(sender());
+
+ QHashIterator i(dockWidgets);
+ while (i.hasNext()) {
+ i.next();
+ if ((static_cast (dockWidgets[i.key()])) == temp){
+ QString chKey = buildMenuKey (SUB_SECTION_CHECKED,static_cast(i.key()));
+ qDebug() << "Key in visibility changed" << chKey;
+ settings.setValue(chKey,vis);
+ toolsMenuActions[i.key()]->setChecked(vis);
+ break;
+ }
+ }
+*/
+}
+
+void MainWindow::updateLocationSettings (Qt::DockWidgetArea location){
+ QDockWidget* temp = qobject_cast(sender());
+
+ QHashIterator i(dockWidgets);
+ while (i.hasNext()) {
+ i.next();
+ if ((static_cast (dockWidgets[i.key()])) == temp){
+ QString posKey = buildMenuKey (SUB_SECTION_LOCATION,static_cast(i.key()), currentView);
+ settings.setValue(posKey,location);
+ break;
+ }
+ }
+//=======
+// addDockWidget(Qt::BottomDockWidgetArea, slugsCamControlWidget);
+// slugsCamControlWidget->hide();
+
+// //FIXME: free memory in destructor
+// joystick = new JoystickInput();
+//>>>>>>> master
}
/**
- * Connect all signals and slots of the main window widgets
+ * Connect the signals and slots of the common window widgets
*/
-void MainWindow::connectWidgets()
+void MainWindow::connectCommonWidgets()
{
- if (linechartWidget)
- {
- connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)),
- linechartWidget, SLOT(addSystem(UASInterface*)));
- connect(UASManager::instance(), SIGNAL(activeUASSet(int)),
- linechartWidget, SLOT(selectSystem(int)));
- connect(linechartWidget, SIGNAL(logfileWritten(QString)),
- this, SLOT(loadDataView(QString)));
- }
if (infoDockWidget && infoDockWidget->widget())
{
connect(mavlink, SIGNAL(receiveLossChanged(int, float)),
infoDockWidget->widget(), SLOT(updateSendLoss(int, float)));
}
+
if (mapWidget && waypointsDockWidget->widget())
{
// clear path create on the map
connect(waypointsDockWidget->widget(), SIGNAL(clearPathclicked()), mapWidget, SLOT(clearPath()));
// add Waypoint widget in the WaypointList widget when mouse clicked
connect(mapWidget, SIGNAL(captureMapCoordinateClick(QPointF)), waypointsDockWidget->widget(), SLOT(addWaypointMouse(QPointF)));
- // it notifies that a waypoint global goes to do create
- //connect(mapWidget, SIGNAL(createGlobalWP(bool, QPointF)), waypointsDockWidget->widget(), SLOT(setIsWPGlobal(bool, QPointF)));
- //connect(mapWidget, SIGNAL(sendGeometryEndDrag(QPointF,int)), waypointsDockWidget->widget(), SLOT(waypointGlobalChanged(QPointF,int)) );
// it notifies that a waypoint global goes to do create and a map graphic too
connect(waypointsDockWidget->widget(), SIGNAL(createWaypointAtMap(QPointF)), mapWidget, SLOT(createWaypointGraphAtMap(QPointF)));
- // it notifies that a waypoint global change it¥s position by spinBox on Widget WaypointView
- //connect(waypointsDockWidget->widget(), SIGNAL(changePositionWPGlobalBySpinBox(int,float,float)), mapWidget, SLOT(changeGlobalWaypointPositionBySpinBox(int,float,float)));
- // connect(waypointsDockWidget->widget(), SIGNAL(changePositionWPGlobalBySpinBox(int,float,float)), mapWidget, SLOT(changeGlobalWaypointPositionBySpinBox(int,float,float)));
+ }
- connect(slugsCamControlWidget->widget(),SIGNAL(viewCamBorderAtMap(bool)),mapWidget,SLOT(drawBorderCamAtMap(bool)));
- connect(slugsCamControlWidget->widget(),SIGNAL(changeCamPosition(double,double,QString)),mapWidget,SLOT(updateCameraPosition(double,double, QString)));
+}
+
+void MainWindow::connectPxWidgets()
+{
+ if (linechartWidget)
+ {
+ connect(linechartWidget, SIGNAL(logfileWritten(QString)),
+ this, SLOT(loadDataView(QString)));
+ }
+
+}
+
+void MainWindow::connectSlugsWidgets()
+{
+ if (linechartWidget)
+ {
+ connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)),
+ linechartWidget, SLOT(addSystem(UASInterface*)));
+ connect(UASManager::instance(), SIGNAL(activeUASSet(int)),
+ linechartWidget, SLOT(selectSystem(int)));
+ connect(linechartWidget, SIGNAL(logfileWritten(QString)),
+ this, SLOT(loadDataView(QString)));
}
if (slugsHilSimWidget && slugsHilSimWidget->widget()){
@@ -400,14 +749,28 @@ void MainWindow::connectWidgets()
}
-void MainWindow::arrangeCenterStack()
+void MainWindow::arrangeCommonCenterStack()
{
+ centerStack = new QStackedWidget(this);
- QStackedWidget *centerStack = new QStackedWidget(this);
if (!centerStack) return;
- if (linechartWidget) centerStack->addWidget(linechartWidget);
- if (protocolWidget) centerStack->addWidget(protocolWidget);
+
if (mapWidget) centerStack->addWidget(mapWidget);
+ if (protocolWidget) centerStack->addWidget(protocolWidget);
+
+ setCentralWidget(centerStack);
+}
+
+void MainWindow::arrangePxCenterStack()
+{
+
+ if (!centerStack) {
+ qDebug() << "Center Stack not Created!";
+ return;
+ }
+
+ if (linechartWidget) centerStack->addWidget(linechartWidget);
+
#ifdef QGC_OSG_ENABLED
if (_3DWidget) centerStack->addWidget(_3DWidget);
#endif
@@ -420,7 +783,21 @@ void MainWindow::arrangeCenterStack()
if (hudWidget) centerStack->addWidget(hudWidget);
if (dataplotWidget) centerStack->addWidget(dataplotWidget);
- setCentralWidget(centerStack);
+}
+
+void MainWindow::arrangeSlugsCenterStack()
+{
+
+ if (!centerStack) {
+ qDebug() << "Center Stack not Created!";
+ return;
+ }
+
+ if (linechartWidget) centerStack->addWidget(linechartWidget);
+
+
+ if (hudWidget) centerStack->addWidget(hudWidget);
+
}
void MainWindow::configureWindowName()
@@ -539,15 +916,16 @@ void MainWindow::showStatusMessage(const QString& status)
* @brief Create all actions associated to the main window
*
**/
-void MainWindow::connectActions()
+void MainWindow::connectCommonActions()
{
+
// Connect actions from ui
connect(ui.actionAdd_Link, SIGNAL(triggered()), this, SLOT(addLink()));
// Connect internal actions
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(UASCreated(UASInterface*)));
- // Connect user interface controls
+ // Unmanned System controls
connect(ui.actionLiftoff, SIGNAL(triggered()), UASManager::instance(), SLOT(launchActiveUAS()));
connect(ui.actionLand, SIGNAL(triggered()), UASManager::instance(), SLOT(returnActiveUAS()));
connect(ui.actionEmergency_Land, SIGNAL(triggered()), UASManager::instance(), SLOT(stopActiveUAS()));
@@ -555,43 +933,33 @@ void MainWindow::connectActions()
connect(ui.actionConfiguration, SIGNAL(triggered()), UASManager::instance(), SLOT(configureActiveUAS()));
- // User interface actions
- connect(ui.actionPilotView, SIGNAL(triggered()), this, SLOT(loadPilotView()));
- connect(ui.actionEngineerView, SIGNAL(triggered()), this, SLOT(loadEngineerView()));
- connect(ui.actionOperatorView, SIGNAL(triggered()), this, SLOT(loadOperatorView()));
-#ifdef QGC_OSG_ENABLED
- connect(ui.action3DView, SIGNAL(triggered()), this, SLOT(load3DView()));
-#else
- ui.menuWindow->removeAction(ui.action3DView);
-#endif
+ // Views actions
+ connect(ui.actionPilotsView, SIGNAL(triggered()), this, SLOT(loadPilotView()));
+ connect(ui.actionEngineersView, SIGNAL(triggered()), this, SLOT(loadEngineerView()));
+ connect(ui.actionOperatorsView, SIGNAL(triggered()), this, SLOT(loadOperatorView()));
-#ifdef QGC_OSGEARTH_ENABLED
- connect(ui.action3DMapView, SIGNAL(triggered()), this, SLOT(load3DMapView()));
-#else
- ui.menuWindow->removeAction(ui.action3DMapView);
-#endif
- connect(ui.actionShow_full_view, SIGNAL(triggered()), this, SLOT(loadAllView()));
- connect(ui.actionShow_MAVLink_view, SIGNAL(triggered()), this, SLOT(loadMAVLinkView()));
- connect(ui.actionShow_data_analysis_view, SIGNAL(triggered()), this, SLOT(loadDataView()));
- connect(ui.actionStyleConfig, SIGNAL(triggered()), this, SLOT(reloadStylesheet()));
- connect(ui.actionGlobalOperatorView, SIGNAL(triggered()), this, SLOT(loadGlobalOperatorView()));
+ connect(ui.actionMavlinkView, SIGNAL(triggered()), this, SLOT(loadMAVLinkView()));
+ connect(ui.actionReloadStyle, SIGNAL(triggered()), this, SLOT(reloadStylesheet()));
+
+ // Help Actions
connect(ui.actionOnline_documentation, SIGNAL(triggered()), this, SLOT(showHelp()));
- connect(ui.actionCredits_Developers, SIGNAL(triggered()), this, SLOT(showCredits()));
+ connect(ui.actionDeveloper_Credits, SIGNAL(triggered()), this, SLOT(showCredits()));
connect(ui.actionProject_Roadmap, SIGNAL(triggered()), this, SLOT(showRoadMap()));
-#if (defined Q_OS_WIN) | (defined Q_OS_MAC)
- connect(ui.actionGoogleEarthView, SIGNAL(triggered()), this, SLOT(loadGoogleEarthView()));
-#else
- ui.menuWindow->removeAction(ui.actionGoogleEarthView);
-#endif
- // Joystick configuration
- connect(ui.actionJoystickSettings, SIGNAL(triggered()), this, SLOT(configure()));
+}
- // Slugs View
- connect(ui.actionShow_Slugs_View, SIGNAL(triggered()), this, SLOT(loadSlugsView()));
+void MainWindow::connectPxActions()
+{
- //GlobalOperatorView
- // connect(ui.actionGlobalOperatorView,SIGNAL(triggered()),waypointsDockWidget->widget(),SLOT())
+ ui.actionJoystickSettings->setVisible(true);
+
+ // Joystick configuration
+ connect(ui.actionJoystickSettings, SIGNAL(triggered()), this, SLOT(configure()));
+
+}
+
+void MainWindow::connectSlugsActions()
+{
}
@@ -746,21 +1114,60 @@ void MainWindow::UASCreated(UASInterface* uas)
// TODO Stylesheet reloading should in theory not be necessary
reloadStylesheet();
- // Check which type this UAS is of
- PxQuadMAV* mav = dynamic_cast(uas);
- if (mav) loadPixhawkView();
-
- if (slugsDataWidget) {
- SlugsDataSensorView* dataWidget = dynamic_cast(slugsDataWidget->widget());
- if (dataWidget) {
- SlugsMAV* mav2 = dynamic_cast(uas);
- if (mav2) {
- dataWidget->addUAS(uas);
- //loadSlugsView();
- loadGlobalOperatorView();
- }
- }
+ switch (uas->getAutopilotType()){
+ case (MAV_AUTOPILOT_GENERIC):
+ case (MAV_AUTOPILOT_ARDUPILOTMEGA):
+ case (MAV_AUTOPILOT_PIXHAWK):
+ {
+ // Build Pixhawk Widgets
+ buildPxWidgets();
+
+ // Connect Pixhawk Widgets
+ connectPxWidgets();
+
+ // Arrange Pixhawk Centerstack
+ arrangePxCenterStack();
+
+ // Connect Pixhawk Actions
+ connectPxActions();
+
+ // FIXME: This type checking might be redundant
+ // Check which type this UAS is of
+// PxQuadMAV* mav = dynamic_cast(uas);
+// if (mav) loadPixhawkEngineerView();
+ } break;
+
+ case (MAV_AUTOPILOT_SLUGS):
+ {
+ // Build Slugs Widgets
+ buildSlugsWidgets();
+
+ // Connect Slugs Widgets
+ connectSlugsWidgets();
+
+ // Arrange Slugs Centerstack
+ arrangeSlugsCenterStack();
+
+ // Connect Slugs Actions
+ connectSlugsActions();
+
+ // FIXME: This type checking might be redundant
+// if (slugsDataWidget) {
+// SlugsDataSensorView* dataWidget = dynamic_cast(slugsDataWidget->widget());
+// if (dataWidget) {
+// SlugsMAV* mav2 = dynamic_cast(uas);
+// if (mav2) {
+ (dynamic_cast(slugsDataWidget->widget()))->addUAS(uas);
+// //loadSlugsView();
+// loadGlobalOperatorView();
+// }
+// }
+// }
+ } break;
+
+ loadEngineerView();
}
+
}
}
@@ -769,21 +1176,25 @@ void MainWindow::UASCreated(UASInterface* uas)
*/
void MainWindow::clearView()
{
- // Halt HUD
+ // Halt HUD central widget
if (hudWidget) hudWidget->stop();
+
// Disable linechart
if (linechartWidget) linechartWidget->setActive(false);
+
// Halt HDDs
if (headDown1DockWidget)
{
HDDisplay* hddWidget = dynamic_cast( headDown1DockWidget->widget() );
if (hddWidget) hddWidget->stop();
}
+
if (headDown2DockWidget)
{
HDDisplay* hddWidget = dynamic_cast( headDown2DockWidget->widget() );
if (hddWidget) hddWidget->stop();
}
+
// Halt HSI
if (hsiDockWidget)
{
@@ -791,6 +1202,13 @@ void MainWindow::clearView()
if (hsi) hsi->stop();
}
+ // Halt HUD if in docked widget mode
+ if (headUpDockWidget)
+ {
+ HUD* hud = dynamic_cast( headUpDockWidget->widget() );
+ if (hud) hud->stop();
+ }
+
// Remove all dock widgets from main window
QObjectList childList( this->children() );
@@ -811,191 +1229,266 @@ void MainWindow::clearView()
}
}
-void MainWindow::loadSlugsView()
+void MainWindow::loadEngineerView()
{
- clearView();
- // Engineer view, used in EMAV2009
-
- // LINE CHART
- if (linechartWidget)
- {
- QStackedWidget *centerStack = dynamic_cast(centralWidget());
- if (centerStack)
- {
- linechartWidget->setActive(true);
- centerStack->setCurrentWidget(linechartWidget);
- }
- }
+ clearView();
- // UAS CONTROL
- if (controlDockWidget)
- {
- addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
- controlDockWidget->show();
- }
+ currentView = VIEW_ENGINEER;
- // UAS LIST
- if (listDockWidget)
- {
- addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
- listDockWidget->show();
- }
+ presentView();
+}
- // UAS STATUS
- if (infoDockWidget)
- {
- addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
- infoDockWidget->show();
- }
+void MainWindow::loadOperatorView()
+{
+ clearView();
+ currentView = VIEW_OPERATOR;
- // WAYPOINT LIST
- if (waypointsDockWidget)
- {
- addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
- waypointsDockWidget->show();
- }
+ presentView();
+}
- // DEBUG CONSOLE
- if (debugConsoleDockWidget)
- {
- addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
- debugConsoleDockWidget->show();
- }
+void MainWindow::loadPilotView()
+{
+ clearView();
- // Slugs Data View
- if (slugsDataWidget)
- {
- addDockWidget(Qt::RightDockWidgetArea, slugsDataWidget);
- slugsDataWidget->show();
- }
+ currentView = VIEW_PILOT;
- // Slugs Data View
- if (slugsHilSimWidget)
- {
- addDockWidget(Qt::LeftDockWidgetArea, slugsHilSimWidget);
- slugsHilSimWidget->show();
- }
+ presentView();
}
-void MainWindow::loadPixhawkView()
+void MainWindow::loadMAVLinkView()
{
clearView();
- // Engineer view, used in EMAV2009
+
+ currentView = VIEW_MAVLINK;
+
+ presentView();
+//=======
+// // Slugs Data View
+// if (slugsHilSimWidget)
+// {
+// addDockWidget(Qt::LeftDockWidgetArea, slugsHilSimWidget);
+// slugsHilSimWidget->show();
+// }
+//>>>>>>> master
+}
+
+void MainWindow::presentView() {
+
#ifdef QGC_OSG_ENABLED
- // 3D map
- if (_3DWidget)
- {
- QStackedWidget *centerStack = dynamic_cast(centralWidget());
- if (centerStack)
- {
- //map3DWidget->setActive(true);
- centerStack->setCurrentWidget(_3DWidget);
- }
- }
+ // 3D map
+ if (_3DWidget)
+ {
+ if (centerStack)
+ {
+ //map3DWidget->setActive(true);
+ centerStack->setCurrentWidget(_3DWidget);
+ }
+ }
#endif
- // UAS CONTROL
- if (controlDockWidget)
- {
- addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
- controlDockWidget->show();
- }
-
- // HORIZONTAL SITUATION INDICATOR
- if (hsiDockWidget)
- {
- HSIDisplay* hsi = dynamic_cast( hsiDockWidget->widget() );
- if (hsi)
- {
- hsi->start();
- addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget);
- hsiDockWidget->show();
+ qDebug() << "LC";
+ showTheCentralWidget(CENTRAL_LINECHART, currentView);
+ if (linechartWidget){
+ qDebug () << buildMenuKey (SUB_SECTION_CHECKED,CENTRAL_LINECHART,currentView) <<
+ settings.value(buildMenuKey (SUB_SECTION_CHECKED,CENTRAL_LINECHART,currentView)).toBool() ;
+ if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,CENTRAL_LINECHART,currentView)).toBool()){
+ if (centerStack) {
+ linechartWidget->setActive(true);
+ centerStack->setCurrentWidget(linechartWidget);
+ }
+ } else {
+ linechartWidget->setActive(false);
+ }
+ }
+
+
+
+ // MAP
+ qDebug() << "MAP";
+ showTheCentralWidget(CENTRAL_MAP, currentView);
+
+ // PROTOCOL
+ qDebug() << "CP";
+ showTheCentralWidget(CENTRAL_PROTOCOL, currentView);
+
+ // HEAD UP DISPLAY
+ showTheCentralWidget(CENTRAL_HUD, currentView);
+ qDebug() << "HUD";
+ if (hudWidget){
+ qDebug() << buildMenuKey(SUB_SECTION_CHECKED,CENTRAL_HUD,currentView) <<
+ settings.value(buildMenuKey (SUB_SECTION_CHECKED,CENTRAL_HUD,currentView)).toBool();
+ if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,CENTRAL_HUD,currentView)).toBool()){
+ if (centerStack) {
+ centerStack->setCurrentWidget(hudWidget);
+ hudWidget->start();
+ }
+ } else {
+ hudWidget->stop();
+ }
+ }
+
+ // Show docked widgets based on current view and autopilot type
+
+ // UAS CONTROL
+ showTheWidget(MENU_UAS_CONTROL, currentView);
+
+ // UAS LIST
+ showTheWidget(MENU_UAS_LIST, currentView);
+
+ // WAYPOINT LIST
+ showTheWidget(MENU_WAYPOINTS, currentView);
+
+ // UAS STATUS
+ showTheWidget(MENU_STATUS, currentView);
+
+ // DETECTION
+ showTheWidget(MENU_DETECTION, currentView);
+
+ // DEBUG CONSOLE
+ showTheWidget(MENU_DEBUG_CONSOLE, currentView);
+
+ // ONBOARD PARAMETERS
+ showTheWidget(MENU_PARAMETERS, currentView);
+
+ // WATCHDOG
+ showTheWidget(MENU_WATCHDOG, currentView);
+
+ // HUD
+ showTheWidget(MENU_HUD, currentView);
+ if (headUpDockWidget)
+ {
+ HUD* tmpHud = dynamic_cast( headUpDockWidget->widget() );
+ if (tmpHud){
+ if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HUD,currentView)).toBool()){
+ tmpHud->start();
+ addDockWidget(static_cast (settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HUD, currentView)).toInt()),
+ hsiDockWidget);
+ headUpDockWidget->show();
+ } else {
+ tmpHud->stop();
+ headUpDockWidget->hide();
}
- }
+ }
+ }
+
+
+ // RC View
+ showTheWidget(MENU_RC_VIEW, currentView);
+
+ // SLUGS DATA
+ showTheWidget(MENU_SLUGS_DATA, currentView);
+
+ // SLUGS PID
+ showTheWidget(MENU_SLUGS_PID, currentView);
+
+ // SLUGS HIL
+ showTheWidget(MENU_SLUGS_HIL, currentView);
+
+ // SLUGS CAMERA
+ showTheWidget(MENU_SLUGS_CAMERA, currentView);
+
+ // HORIZONTAL SITUATION INDICATOR
+ showTheWidget(MENU_HSI, currentView);
+ if (hsiDockWidget)
+ {
+ HSIDisplay* hsi = dynamic_cast( hsiDockWidget->widget() );
+ if (hsi){
+ if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HSI,currentView)).toBool()){
+ hsi->start();
+ addDockWidget(static_cast (settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HSI, currentView)).toInt()),
+ hsiDockWidget);
+ hsiDockWidget->show();
+ } else {
+ hsi->stop();
+ hsiDockWidget->hide();
+ }
+ }
+ }
+
+ // HEAD DOWN 1
+ showTheWidget(MENU_HDD_1, currentView);
+ if (headDown1DockWidget)
+ {
+ HDDisplay *hdd = dynamic_cast(headDown1DockWidget->widget());
+ if (hdd) {
+ if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HDD_1,currentView)).toBool()) {
+ addDockWidget(static_cast (settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HDD_1, currentView)).toInt()),
+ headDown1DockWidget);
+ headDown1DockWidget->show();
+ hdd->start();
+ } else {
+ headDown1DockWidget->hide();;
+ hdd->stop();
+ }
+ }
+ }
+
+ // HEAD DOWN 2
+ showTheWidget(MENU_HDD_2, currentView);
+ if (headDown2DockWidget)
+ {
+ HDDisplay *hdd = dynamic_cast(headDown2DockWidget->widget());
+ if (hdd){
+ if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HDD_2,currentView)).toBool()){
+ addDockWidget(static_cast (settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HDD_2, currentView)).toInt()),
+ headDown2DockWidget);
+ headDown2DockWidget->show();
+ hdd->start();
+ } else {
+ headDown2DockWidget->hide();
+ hdd->stop();
+ }
+ }
+ }
- // UAS LIST
- if (listDockWidget)
- {
- addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
- listDockWidget->show();
- }
+ this->show();
- // UAS STATUS
- if (infoDockWidget)
- {
- addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
- infoDockWidget->show();
- }
+}
- // WAYPOINT LIST
- if (waypointsDockWidget)
- {
- addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
- waypointsDockWidget->show();
- }
+void MainWindow::showTheCentralWidget (TOOLS_WIDGET_NAMES centralWidget, VIEW_SECTIONS view){
+ bool tempVisible;
+ QWidget* tempWidget = dockWidgets[centralWidget];
+//=======
+// // ONBOARD PARAMETERS
+// if (parametersDockWidget)
+// {
+// addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
+// parametersDockWidget->show();
+// }
+//}
+//>>>>>>> master
- // DEBUG CONSOLE
- if (debugConsoleDockWidget)
- {
- addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
- debugConsoleDockWidget->show();
- }
+ tempVisible = settings.value(buildMenuKey (SUB_SECTION_CHECKED,centralWidget,view)).toBool();
+ qDebug() << buildMenuKey (SUB_SECTION_CHECKED,centralWidget,view) << tempVisible;
+ if (toolsMenuActions[centralWidget]){
+ toolsMenuActions[centralWidget]->setChecked(tempVisible);
+ }
- // ONBOARD PARAMETERS
- if (parametersDockWidget)
- {
- addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
- parametersDockWidget->show();
- }
+ if (centerStack && tempWidget && tempVisible){
+ centerStack->setCurrentWidget(tempWidget);
+ }
}
-void MainWindow::loadDataView()
-{
- clearView();
- // DATAPLOT
- if (dataplotWidget)
- {
- QStackedWidget *centerStack = dynamic_cast(centralWidget());
- if (centerStack)
- centerStack->setCurrentWidget(dataplotWidget);
- }
-}
-void MainWindow::loadDataView(QString fileName)
+/*
+==========================================================
+ Potentially Deprecated
+==========================================================
+*/
+
+void MainWindow::loadPixhawkEngineerView()
{
- clearView();
- // DATAPLOT
- if (dataplotWidget)
- {
- QStackedWidget *centerStack = dynamic_cast(centralWidget());
- if (centerStack)
- {
- centerStack->setCurrentWidget(dataplotWidget);
- dataplotWidget->loadFile(fileName);
- }
- }
}
-void MainWindow::loadPilotView()
+
+void MainWindow::loadAllView()
{
clearView();
- // HEAD UP DISPLAY
- if (hudWidget)
- {
- QStackedWidget *centerStack = dynamic_cast(centralWidget());
- if (centerStack)
- {
- centerStack->setCurrentWidget(hudWidget);
- hudWidget->start();
- }
- }
-
- //connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), pfd, SLOT(setActiveUAS(UASInterface*)));
if (headDown1DockWidget)
{
HDDisplay *hdd = dynamic_cast(headDown1DockWidget->widget());
@@ -1005,7 +1498,7 @@ void MainWindow::loadPilotView()
headDown1DockWidget->show();
hdd->start();
}
-
+
}
if (headDown2DockWidget)
{
@@ -1017,21 +1510,24 @@ void MainWindow::loadPilotView()
hdd->start();
}
}
-}
-
-void MainWindow::loadOperatorView()
-{
- clearView();
+//<<<<<<< HEAD
+//=======
+//}
- // MAP
- if (mapWidget)
- {
- QStackedWidget *centerStack = dynamic_cast(centralWidget());
- if (centerStack)
- {
- centerStack->setCurrentWidget(mapWidget);
- }
- }
+//void MainWindow::loadOperatorView()
+//{
+// clearView();
+
+// // MAP
+// if (mapWidget)
+// {
+// QStackedWidget *centerStack = dynamic_cast(centralWidget());
+// if (centerStack)
+// {
+// centerStack->setCurrentWidget(mapWidget);
+// }
+// }
+//>>>>>>> master
// UAS CONTROL
if (controlDockWidget)
@@ -1061,16 +1557,11 @@ void MainWindow::loadOperatorView()
waypointsDockWidget->show();
}
- // HORIZONTAL SITUATION INDICATOR
- if (hsiDockWidget)
+ // DEBUG CONSOLE
+ if (debugConsoleDockWidget)
{
- HSIDisplay* hsi = dynamic_cast( hsiDockWidget->widget() );
- if (hsi)
- {
- addDockWidget(Qt::BottomDockWidgetArea, hsiDockWidget);
- hsiDockWidget->show();
- hsi->start();
- }
+ addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
+ debugConsoleDockWidget->show();
}
// OBJECT DETECTION
@@ -1080,58 +1571,62 @@ void MainWindow::loadOperatorView()
detectionDockWidget->show();
}
- // PROCESS CONTROL
- if (watchdogControlDockWidget)
- {
- addDockWidget(Qt::RightDockWidgetArea, watchdogControlDockWidget);
- watchdogControlDockWidget->show();
- }
-}
-
-void MainWindow::loadGlobalOperatorView()
-{
- clearView();
-
- // MAP
- if (mapWidget)
+ // LINE CHART
+ if (linechartWidget)
{
QStackedWidget *centerStack = dynamic_cast(centralWidget());
if (centerStack)
{
- centerStack->setCurrentWidget(mapWidget);
+ linechartWidget->setActive(true);
+ centerStack->setCurrentWidget(linechartWidget);
}
}
- // WAYPOINT LIST
- if (waypointsDockWidget)
- {
- addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
- waypointsDockWidget->show();
-
- }
-
- // Slugs Data View
- if (slugsDataWidget)
- {
- addDockWidget(Qt::RightDockWidgetArea, slugsDataWidget);
- slugsDataWidget->show();
- }
-
- // Slugs Data View
- if (slugsPIDControlWidget)
+ // ONBOARD PARAMETERS
+ if (parametersDockWidget)
{
- addDockWidget(Qt::LeftDockWidgetArea, slugsPIDControlWidget);
- slugsPIDControlWidget->show();
+ addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
+ parametersDockWidget->show();
}
+}
- if (slugsCamControlWidget)
- {
- addDockWidget(Qt::BottomDockWidgetArea, slugsCamControlWidget);
- slugsCamControlWidget->show();
- }
+void MainWindow::loadWidgets()
+{
+ //loadOperatorView();
+ loadMAVLinkView();
+ //loadPilotView();
}
-void MainWindow::load3DMapView()
+void MainWindow::loadDataView()
+{
+ clearView();
+
+ // DATAPLOT
+ if (dataplotWidget)
+ {
+ QStackedWidget *centerStack = dynamic_cast(centralWidget());
+ if (centerStack)
+ centerStack->setCurrentWidget(dataplotWidget);
+ }
+}
+
+void MainWindow::loadDataView(QString fileName)
+{
+ clearView();
+
+ // DATAPLOT
+ if (dataplotWidget)
+ {
+ QStackedWidget *centerStack = dynamic_cast(centralWidget());
+ if (centerStack)
+ {
+ centerStack->setCurrentWidget(dataplotWidget);
+ dataplotWidget->loadFile(fileName);
+ }
+ }
+}
+
+void MainWindow::load3DMapView()
{
#ifdef QGC_OSGEARTH_ENABLED
clearView();
@@ -1233,7 +1728,6 @@ void MainWindow::loadGoogleEarthView()
}
-
void MainWindow::load3DView()
{
#ifdef QGC_OSG_ENABLED
@@ -1285,64 +1779,61 @@ void MainWindow::load3DView()
#endif
}
-void MainWindow::loadEngineerView()
+/*
+ ==================================
+ ========== ATTIC =================
+ ==================================
+
+void MainWindow::buildCommonWidgets()
{
- clearView();
- // Engineer view, used in EMAV2009
+ //FIXME: memory of acceptList will never be freed again
+ QStringList* acceptList = new QStringList();
+ acceptList->append("roll IMU");
+ acceptList->append("pitch IMU");
+ acceptList->append("yaw IMU");
+ acceptList->append("rollspeed IMU");
+ acceptList->append("pitchspeed IMU");
+ acceptList->append("yawspeed IMU");
- // LINE CHART
- if (linechartWidget)
- {
- QStackedWidget *centerStack = dynamic_cast(centralWidget());
- if (centerStack)
- {
- linechartWidget->setActive(true);
- centerStack->setCurrentWidget(linechartWidget);
- }
- }
+ //FIXME: memory of acceptList2 will never be freed again
+ QStringList* acceptList2 = new QStringList();
+ acceptList2->append("Battery");
+ acceptList2->append("Pressure");
- // UAS CONTROL
- if (controlDockWidget)
- {
- addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
- controlDockWidget->show();
- }
+ //TODO: move protocol outside UI
+ mavlink = new MAVLinkProtocol();
- // UAS LIST
- if (listDockWidget)
- {
- addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
- listDockWidget->show();
- }
+ // Center widgets
+ linechartWidget = new Linecharts(this);
+ hudWidget = new HUD(320, 240, this);
+ mapWidget = new MapWidget(this);
+ protocolWidget = new XMLCommProtocolWidget(this);
+ dataplotWidget = new QGCDataPlot2D(this);
+#ifdef QGC_OSG_ENABLED
+ _3DWidget = Q3DWidgetFactory::get("PIXHAWK");
+#endif
- // UAS STATUS
- if (infoDockWidget)
- {
- addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
- infoDockWidget->show();
- }
+#ifdef QGC_OSGEARTH_ENABLED
+ _3DMapWidget = Q3DWidgetFactory::get("MAP3D");
+#endif
+#if (defined Q_OS_WIN) | (defined Q_OS_MAC)
+ gEarthWidget = new QGCGoogleEarthView(this);
+#endif
- // WAYPOINT LIST
- if (waypointsDockWidget)
- {
- addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
- waypointsDockWidget->show();
- }
+ // Dock widgets
+ controlDockWidget = new QDockWidget(tr("Control"), this);
+ controlDockWidget->setWidget( new UASControlWidget(this) );
- // DEBUG CONSOLE
- if (debugConsoleDockWidget)
- {
- addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
- debugConsoleDockWidget->show();
- }
+ listDockWidget = new QDockWidget(tr("Unmanned Systems"), this);
+ listDockWidget->setWidget( new UASListWidget(this) );
- // ONBOARD PARAMETERS
- if (parametersDockWidget)
- {
- addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
- parametersDockWidget->show();
- }
+<<<<<<< HEAD
+ waypointsDockWidget = new QDockWidget(tr("Waypoint List"), this);
+ waypointsDockWidget->setWidget( new WaypointList(this, NULL) );
+ infoDockWidget = new QDockWidget(tr("Status Details"), this);
+ infoDockWidget->setWidget( new UASInfoWidget(this) );
+=======
// RADIO CONTROL VIEW
if (rcViewDockWidget)
{
@@ -1350,11 +1841,53 @@ void MainWindow::loadEngineerView()
rcViewDockWidget->show();
}
}
+>>>>>>> master
-void MainWindow::loadMAVLinkView()
-{
- clearView();
+ detectionDockWidget = new QDockWidget(tr("Object Recognition"), this);
+ detectionDockWidget->setWidget( new ObjectDetectionView("images/patterns", this) );
+
+<<<<<<< HEAD
+ debugConsoleDockWidget = new QDockWidget(tr("Communication Console"), this);
+ debugConsoleDockWidget->setWidget( new DebugConsole(this) );
+
+ parametersDockWidget = new QDockWidget(tr("Onboard Parameters"), this);
+ parametersDockWidget->setWidget( new ParameterInterface(this) );
+
+ watchdogControlDockWidget = new QDockWidget(tr("Process Control"), this);
+ watchdogControlDockWidget->setWidget( new WatchdogControl(this) );
+
+ hsiDockWidget = new QDockWidget(tr("Horizontal Situation Indicator"), this);
+ hsiDockWidget->setWidget( new HSIDisplay(this) );
+ headDown1DockWidget = new QDockWidget(tr("Primary Flight Display"), this);
+ headDown1DockWidget->setWidget( new HDDisplay(acceptList, this) );
+
+ headDown2DockWidget = new QDockWidget(tr("Payload Status"), this);
+ headDown2DockWidget->setWidget( new HDDisplay(acceptList2, this) );
+
+ rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
+ rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
+
+ headUpDockWidget = new QDockWidget(tr("Control Indicator"), this);
+ headUpDockWidget->setWidget( new HUD(320, 240, this));
+
+ // Dialogue widgets
+ //FIXME: free memory in destructor
+ joystick = new JoystickInput();
+
+ slugsDataWidget = new QDockWidget(tr("Slugs Data"), this);
+ slugsDataWidget->setWidget( new SlugsDataSensorView(this));
+
+ slugsPIDControlWidget = new QDockWidget(tr("PID Control"), this);
+ slugsPIDControlWidget->setWidget(new SlugsPIDControl(this));
+
+ slugsHilSimWidget = new QDockWidget(tr("Slugs Hil Sim"), this);
+ slugsHilSimWidget->setWidget( new SlugsHilSim(this));
+
+ slugsCamControlWidget = new QDockWidget(tr("Video Camera Control"), this);
+ slugsCamControlWidget->setWidget(new SlugsVideoCamControl(this));
+
+=======
if (protocolWidget)
{
QStackedWidget *centerStack = dynamic_cast(centralWidget());
@@ -1363,96 +1896,148 @@ void MainWindow::loadMAVLinkView()
centerStack->setCurrentWidget(protocolWidget);
}
}
+>>>>>>> master
}
-void MainWindow::loadAllView()
+void MainWindow::connectWidgets()
{
- clearView();
-
- if (headDown1DockWidget)
+ if (linechartWidget)
{
- HDDisplay *hdd = dynamic_cast(headDown1DockWidget->widget());
- if (hdd)
- {
- addDockWidget(Qt::RightDockWidgetArea, headDown1DockWidget);
- headDown1DockWidget->show();
- hdd->start();
- }
-
+ connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)),
+ linechartWidget, SLOT(addSystem(UASInterface*)));
+ connect(UASManager::instance(), SIGNAL(activeUASSet(int)),
+ linechartWidget, SLOT(selectSystem(int)));
+ connect(linechartWidget, SIGNAL(logfileWritten(QString)),
+ this, SLOT(loadDataView(QString)));
}
- if (headDown2DockWidget)
+ if (infoDockWidget && infoDockWidget->widget())
{
- HDDisplay *hdd = dynamic_cast(headDown2DockWidget->widget());
- if (hdd)
- {
- addDockWidget(Qt::RightDockWidgetArea, headDown2DockWidget);
- headDown2DockWidget->show();
- hdd->start();
- }
+ connect(mavlink, SIGNAL(receiveLossChanged(int, float)),
+ infoDockWidget->widget(), SLOT(updateSendLoss(int, float)));
}
-
- // UAS CONTROL
- if (controlDockWidget)
+ if (mapWidget && waypointsDockWidget->widget())
{
- addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
- controlDockWidget->show();
- }
+ // clear path create on the map
+ connect(waypointsDockWidget->widget(), SIGNAL(clearPathclicked()), mapWidget, SLOT(clearPath()));
+ // add Waypoint widget in the WaypointList widget when mouse clicked
+ connect(mapWidget, SIGNAL(captureMapCoordinateClick(QPointF)), waypointsDockWidget->widget(), SLOT(addWaypointMouse(QPointF)));
+ // it notifies that a waypoint global goes to do create
+ //connect(mapWidget, SIGNAL(createGlobalWP(bool, QPointF)), waypointsDockWidget->widget(), SLOT(setIsWPGlobal(bool, QPointF)));
+ //connect(mapWidget, SIGNAL(sendGeometryEndDrag(QPointF,int)), waypointsDockWidget->widget(), SLOT(waypointGlobalChanged(QPointF,int)) );
- // UAS LIST
- if (listDockWidget)
- {
- addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
- listDockWidget->show();
- }
+ // it notifies that a waypoint global goes to do create and a map graphic too
+ connect(waypointsDockWidget->widget(), SIGNAL(createWaypointAtMap(QPointF)), mapWidget, SLOT(createWaypointGraphAtMap(QPointF)));
+ // it notifies that a waypoint global change it¥s position by spinBox on Widget WaypointView
+ //connect(waypointsDockWidget->widget(), SIGNAL(changePositionWPGlobalBySpinBox(int,float,float)), mapWidget, SLOT(changeGlobalWaypointPositionBySpinBox(int,float,float)));
+ // connect(waypointsDockWidget->widget(), SIGNAL(changePositionWPGlobalBySpinBox(int,float,float)), mapWidget, SLOT(changeGlobalWaypointPositionBySpinBox(int,float,float)));
- // UAS STATUS
- if (infoDockWidget)
- {
- addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
- infoDockWidget->show();
+ connect(slugsCamControlWidget->widget(),SIGNAL(viewCamBorderAtMap(bool)),mapWidget,SLOT(drawBorderCamAtMap(bool)));
+ connect(slugsCamControlWidget->widget(),SIGNAL(changeCamPosition(double,double,QString)),mapWidget,SLOT(updateCameraPosition(double,double, QString)));
}
- // WAYPOINT LIST
- if (waypointsDockWidget)
- {
- addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
- waypointsDockWidget->show();
+ if (slugsHilSimWidget && slugsHilSimWidget->widget()){
+ connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
+ slugsHilSimWidget->widget(), SLOT(activeUasSet(UASInterface*)));
}
- // DEBUG CONSOLE
- if (debugConsoleDockWidget)
- {
- addDockWidget(Qt::BottomDockWidgetArea, debugConsoleDockWidget);
- debugConsoleDockWidget->show();
+ if (slugsDataWidget && slugsDataWidget->widget()){
+ connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
+ slugsDataWidget->widget(), SLOT(setActiveUAS(UASInterface*)));
}
- // OBJECT DETECTION
- if (detectionDockWidget)
- {
- addDockWidget(Qt::RightDockWidgetArea, detectionDockWidget);
- detectionDockWidget->show();
- }
- // LINE CHART
- if (linechartWidget)
- {
- QStackedWidget *centerStack = dynamic_cast(centralWidget());
- if (centerStack)
- {
- linechartWidget->setActive(true);
- centerStack->setCurrentWidget(linechartWidget);
- }
- }
+}
+
+<<<<<<< HEAD
+void MainWindow::arrangeCommonCenterStack()
+{
+ QStackedWidget *centerStack = new QStackedWidget(this);
+ if (!centerStack) return;
+ if (linechartWidget) centerStack->addWidget(linechartWidget);
+ if (protocolWidget) centerStack->addWidget(protocolWidget);
+ if (mapWidget) centerStack->addWidget(mapWidget);
+#ifdef QGC_OSG_ENABLED
+ if (_3DWidget) centerStack->addWidget(_3DWidget);
+#endif
+#ifdef QGC_OSGEARTH_ENABLED
+ if (_3DMapWidget) centerStack->addWidget(_3DMapWidget);
+#endif
+#if (defined Q_OS_WIN) | (defined Q_OS_MAC)
+ if (gEarthWidget) centerStack->addWidget(gEarthWidget);
+#endif
+ if (hudWidget) centerStack->addWidget(hudWidget);
+ if (dataplotWidget) centerStack->addWidget(dataplotWidget);
+
+ setCentralWidget(centerStack);
+=======
// ONBOARD PARAMETERS
if (parametersDockWidget)
{
addDockWidget(Qt::RightDockWidgetArea, parametersDockWidget);
parametersDockWidget->show();
}
+>>>>>>> master
}
-void MainWindow::loadWidgets()
+void MainWindow::connectActions()
{
+<<<<<<< HEAD
+ // Connect actions from ui
+ connect(ui.actionAdd_Link, SIGNAL(triggered()), this, SLOT(addLink()));
+
+ // Connect internal actions
+ connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(UASCreated(UASInterface*)));
+
+ // Connect user interface controls
+ connect(ui.actionLiftoff, SIGNAL(triggered()), UASManager::instance(), SLOT(launchActiveUAS()));
+ connect(ui.actionLand, SIGNAL(triggered()), UASManager::instance(), SLOT(returnActiveUAS()));
+ connect(ui.actionEmergency_Land, SIGNAL(triggered()), UASManager::instance(), SLOT(stopActiveUAS()));
+ connect(ui.actionEmergency_Kill, SIGNAL(triggered()), UASManager::instance(), SLOT(killActiveUAS()));
+
+ connect(ui.actionConfiguration, SIGNAL(triggered()), UASManager::instance(), SLOT(configureActiveUAS()));
+
+ // User interface actions
+ connect(ui.actionPilotView, SIGNAL(triggered()), this, SLOT(loadPilotView()));
+ connect(ui.actionEngineerView, SIGNAL(triggered()), this, SLOT(loadEngineerView()));
+ connect(ui.actionOperatorView, SIGNAL(triggered()), this, SLOT(loadOperatorView()));
+#ifdef QGC_OSG_ENABLED
+ connect(ui.action3DView, SIGNAL(triggered()), this, SLOT(load3DView()));
+#else
+ ui.menuWindow->removeAction(ui.action3DView);
+#endif
+
+#ifdef QGC_OSGEARTH_ENABLED
+ connect(ui.action3DMapView, SIGNAL(triggered()), this, SLOT(load3DMapView()));
+#else
+ ui.menuWindow->removeAction(ui.action3DMapView);
+#endif
+ connect(ui.actionShow_full_view, SIGNAL(triggered()), this, SLOT(loadAllView()));
+ connect(ui.actionShow_MAVLink_view, SIGNAL(triggered()), this, SLOT(loadMAVLinkView()));
+ connect(ui.actionShow_data_analysis_view, SIGNAL(triggered()), this, SLOT(loadDataView()));
+ connect(ui.actionStyleConfig, SIGNAL(triggered()), this, SLOT(reloadStylesheet()));
+ connect(ui.actionGlobalOperatorView, SIGNAL(triggered()), this, SLOT(loadGlobalOperatorView()));
+ connect(ui.actionOnline_documentation, SIGNAL(triggered()), this, SLOT(showHelp()));
+ connect(ui.actionCredits_Developers, SIGNAL(triggered()), this, SLOT(showCredits()));
+ connect(ui.actionProject_Roadmap, SIGNAL(triggered()), this, SLOT(showRoadMap()));
+#if (defined Q_OS_WIN) | (defined Q_OS_MAC)
+ connect(ui.actionGoogleEarthView, SIGNAL(triggered()), this, SLOT(loadGoogleEarthView()));
+#else
+ ui.menuWindow->removeAction(ui.actionGoogleEarthView);
+#endif
+
+ // Joystick configuration
+ connect(ui.actionJoystickSettings, SIGNAL(triggered()), this, SLOT(configure()));
+
+ // Slugs View
+ connect(ui.actionShow_Slugs_View, SIGNAL(triggered()), this, SLOT(loadSlugsView()));
+
+ //GlobalOperatorView
+ // connect(ui.actionGlobalOperatorView,SIGNAL(triggered()),waypointsDockWidget->widget(),SLOT())
+
+=======
//loadEngineerView();
+>>>>>>> master
}
+
+*/
diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h
index 5430455..be8b318 100644
--- a/src/ui/MainWindow.h
+++ b/src/ui/MainWindow.h
@@ -87,8 +87,8 @@ public:
~MainWindow();
public slots:
- /** @brief Store the mainwindow settings */
- void storeSettings();
+// /** @brief Store the mainwindow settings */
+// void storeSettings();
/**
* @brief Shows a status message on the bottom status bar
@@ -122,22 +122,8 @@ public slots:
void loadEngineerView();
/** @brief Load view for operator */
void loadOperatorView();
- /** @brief Load 3D view */
- void load3DView();
- /** @brief Load 3D Google Earth view */
- void loadGoogleEarthView();
- /** @brief Load 3D map view */
- void load3DMapView();
- /** @brief Load view with all widgets */
- void loadAllView();
/** @brief Load MAVLink XML generator view */
void loadMAVLinkView();
- /** @brief Load data view, allowing to plot flight data */
- void loadDataView();
- /** @brief Load data view, allowing to plot flight data */
- void loadDataView(QString fileName);
- /** @brief Load view for global operator, allowing to flight on earth */
- void loadGlobalOperatorView();
/** @brief Show the online help for users */
void showHelp();
@@ -146,25 +132,200 @@ public slots:
/** @brief Show the project roadmap */
void showRoadMap();
- // Fixme find a nicer solution that scales to more AP types
- void loadSlugsView();
- void loadPixhawkView();
+ /** @brief Shows the widgets based on configuration and current view and autopilot */
+ void presentView();
/** @brief Reload the CSS style sheet */
void reloadStylesheet();
+
+ /*
+ ==========================================================
+ Potentially Deprecated
+ ==========================================================
+ */
+
+ void loadPixhawkEngineerView();
+
+ /** @brief Load view with all widgets */
+ void loadAllView();
+
+ void loadWidgets();
+
+ /** @brief Load data view, allowing to plot flight data */
+ void loadDataView();
+ /** @brief Load data view, allowing to plot flight data */
+ void loadDataView(QString fileName);
+
+ /** @brief Load 3D map view */
+ void load3DMapView();
+
+ /** @brief Load 3D Google Earth view */
+ void loadGoogleEarthView();
+
+ /** @brief Load 3D view */
+ void load3DView();
+
+ /**
+ * @brief Shows a Docked Widget based on the action sender
+ *
+ * This slot is written to be used in conjunction with the addToToolsMenu function
+ * It shows the QDockedWidget based on the action sender
+ *
+ */
+ void showToolWidget();
+
+ /**
+ * @brief Shows a Widget from the center stack based on the action sender
+ *
+ * This slot is written to be used in conjunction with the addToCentralWidgetsMenu function
+ * It shows the Widget based on the action sender
+ *
+ */
+ void showCentralWidget();
+
+ /** @brief Updates a QDockWidget's checked status based on its visibility */
+ void updateVisibilitySettings (bool vis);
+
+ /** @brief Updates a QDockWidget's location */
+ void updateLocationSettings (Qt::DockWidgetArea location);
+
protected:
+
+ // These defines are used to save the settings when selecting with
+ // which widgets populate the views
+ // FIXME: DO NOT PUT CUSTOM VALUES IN THIS ENUM since it is iterated over
+ // this will be fixed in a future release.
+ typedef enum _TOOLS_WIDGET_NAMES {
+ MENU_UAS_CONTROL,
+ MENU_UAS_INFO,
+ MENU_CAMERA,
+ MENU_UAS_LIST,
+ MENU_WAYPOINTS,
+ MENU_STATUS,
+ MENU_DETECTION,
+ MENU_DEBUG_CONSOLE,
+ MENU_PARAMETERS,
+ MENU_HDD_1,
+ MENU_HDD_2,
+ MENU_WATCHDOG,
+ MENU_HUD,
+ MENU_HSI,
+ MENU_RC_VIEW,
+ MENU_SLUGS_DATA,
+ MENU_SLUGS_PID,
+ MENU_SLUGS_HIL,
+ MENU_SLUGS_CAMERA,
+ CENTRAL_SEPARATOR= 255, // do not change
+ CENTRAL_LINECHART,
+ CENTRAL_PROTOCOL,
+ CENTRAL_MAP,
+ CENTRAL_3D_LOCAL,
+ CENTRAL_3D_MAP,
+ CENTRAL_OSGEARTH,
+ CENTRAL_GOOGLE_EARTH,
+ CENTRAL_HUD,
+ CENTRAL_DATA_PLOT,
+
+ }TOOLS_WIDGET_NAMES;
+
+ typedef enum _SETTINGS_SECTIONS {
+ SECTION_MENU,
+ SUB_SECTION_CHECKED,
+ SUB_SECTION_LOCATION,
+ } SETTINGS_SECTIONS;
+
+ typedef enum _VIEW_SECTIONS {
+ VIEW_ENGINEER,
+ VIEW_OPERATOR,
+ VIEW_PILOT,
+ VIEW_MAVLINK,
+ } VIEW_SECTIONS;
+
+
+ QHash toolsMenuActions; // Holds ptr to the Menu Actions
+ QHash dockWidgets; // Holds ptr to the Actual Dock widget
+ QHash dockWidgetLocations; // Holds the location
+
+ /**
+ * @brief Adds an already instantiated QDockedWidget to the Tools Menu
+ *
+ * This function does all the hosekeeping to have a QDockedWidget added to the
+ * tools menu and connects the QMenuAction to a slot that shows the widget and
+ * checks/unchecks the tools menu item
+ *
+ * @param widget The QDockedWidget being added
+ * @param title The entry that will appear in the Menu and in the QDockedWidget title bar
+ * @param slotName The slot to which the triggered() signal of the menu action will be connected.
+ * @param tool The ENUM defined in MainWindow.h that is associated to the widget
+ * @param location The default location for the QDockedWidget in case there is no previous key in the settings
+ */
+ void addToToolsMenu (QWidget* widget, const QString title, const char * slotName, TOOLS_WIDGET_NAMES tool, Qt::DockWidgetArea location);
+
+ /**
+ * @brief Determines if a QDockWidget needs to be show and if so, shows it
+ *
+ * Based on the the autopilot and the current view it queries the settings and shows the
+ * widget if necessary
+ *
+ * @param widget The QDockWidget requested to be shown
+ * @param view The view for which the QDockWidget is requested
+ */
+ void showTheWidget (TOOLS_WIDGET_NAMES widget, VIEW_SECTIONS view = VIEW_MAVLINK);
+
+ /**
+ * @brief Adds an already instantiated QWidget to the center stack
+ *
+ * This function does all the hosekeeping to have a QWidget added to the tools menu
+ * tools menu and connects the QMenuAction to a slot that shows the widget and
+ * checks/unchecks the tools menu item. This is used for all the central widgets (those in
+ * the center stack.
+ *
+ * @param widget The QWidget being added
+ * @param title The entry that will appear in the Menu
+ * @param slotName The slot to which the triggered() signal of the menu action will be connected.
+ * @param centralWidget The ENUM defined in MainWindow.h that is associated to the widget
+ */
+ void addToCentralWidgetsMenu ( QWidget* widget, const QString title,const char * slotName, TOOLS_WIDGET_NAMES centralWidget);
+
+ /**
+ * @brief Determines if a QWidget needs to be show and if so, shows it
+ *
+ * Based on the the autopilot and the current view it queries the settings and shows the
+ * widget if necessary
+ *
+ * @param centralWidget The QWidget requested to be shown
+ * @param view The view for which the QWidget is requested
+ */
+ void showTheCentralWidget (TOOLS_WIDGET_NAMES centralWidget, VIEW_SECTIONS view);
+
+
+ /** @brief Keeps track of the current view */
+ VIEW_SECTIONS currentView;
+
QStatusBar* statusBar;
QStatusBar* createStatusBar();
- void loadWidgets();
- void connectActions();
+
+
void clearView();
- void buildWidgets();
- void connectWidgets();
- void arrangeCenterStack();
- void configureWindowName();
- QMenu* createCenterWidgetMenu();
- QMenu* createDockWidgetMenu();
+ void buildCommonWidgets();
+ void buildPxWidgets();
+ void buildSlugsWidgets();
+
+ void connectCommonWidgets();
+ void connectPxWidgets();
+ void connectSlugsWidgets();
+
+ void arrangeCommonCenterStack();
+ void arrangePxCenterStack();
+ void arrangeSlugsCenterStack();
+
+ void connectCommonActions();
+ void connectPxActions();
+ void connectSlugsActions();
+
+
+ void configureWindowName();
// TODO Should be moved elsewhere, as the protocol does not belong to the UI
MAVLinkProtocol* mavlink;
@@ -174,13 +335,13 @@ protected:
LinkInterface* udpLink;
QSettings settings;
- // Widget lists
- QList > centerWidgets;
- QList > dockWidgets;
+ QStackedWidget *centerStack;
// Center widgets
QPointer linechartWidget;
+
QPointer hudWidget;
+
QPointer mapWidget;
QPointer protocolWidget;
QPointer dataplotWidget;
@@ -203,7 +364,9 @@ protected:
QPointer headDown1DockWidget;
QPointer headDown2DockWidget;
QPointer watchdogControlDockWidget;
+
QPointer headUpDockWidget;
+
QPointer hsiDockWidget;
QPointer rcViewDockWidget;
QPointer hudDockWidget;
@@ -227,6 +390,7 @@ protected:
QAction* killUASAct;
QAction* simulateUASAct;
+
LogCompressor* comp;
QString screenFileName;
QTimer* videoTimer;
@@ -234,6 +398,8 @@ protected:
private:
Ui::MainWindow ui;
+ QString buildMenuKey (SETTINGS_SECTIONS section , TOOLS_WIDGET_NAMES tool, VIEW_SECTIONS view);
+
};
#endif /* _MAINWINDOW_H_ */
diff --git a/src/ui/MainWindow.ui b/src/ui/MainWindow.ui
index 9a912e0..de35a73 100644
--- a/src/ui/MainWindow.ui
+++ b/src/ui/MainWindow.ui
@@ -38,19 +38,17 @@
0
0
1000
- 25
+ 22
-
-
-
-
- Recepcion
-
-
-
- -
Qt::Vertical
@@ -956,6 +949,13 @@
+ -
+
+
+ Recepcion
+
+
+
diff --git a/src/ui/SlugsPadCameraControl.cpp b/src/ui/SlugsPadCameraControl.cpp
index 40b40c0..3e198c6 100644
--- a/src/ui/SlugsPadCameraControl.cpp
+++ b/src/ui/SlugsPadCameraControl.cpp
@@ -13,6 +13,9 @@ SlugsPadCameraControl::SlugsPadCameraControl(QWidget *parent) :
ui->setupUi(this);
x1= 0;
y1 = 0;
+ bearingPad = 0;
+ distancePad = 0;
+ directionPad = "no";
}
@@ -23,13 +26,25 @@ SlugsPadCameraControl::~SlugsPadCameraControl()
void SlugsPadCameraControl::mouseMoveEvent(QMouseEvent *event)
{
- emit mouseMoveCoord(event->x(),event->y());
+ //emit mouseMoveCoord(event->x(),event->y());
+ if(dragging)
+ {
+ if(abs(x1-event->x())>20 || abs(y1-event->y())>20)
+ {
+
+ getDeltaPositionPad(event->x(), event->y());
+ x1 = event->x();
+ y1 = event->y();
+ }
+ }
+
}
void SlugsPadCameraControl::mousePressEvent(QMouseEvent *event)
{
- emit mousePressCoord(event->x(),event->y());
+ //emit mousePressCoord(event->x(),event->y());
+ dragging = true;
x1 = event->x();
y1 = event->y();
@@ -37,8 +52,13 @@ void SlugsPadCameraControl::mousePressEvent(QMouseEvent *event)
void SlugsPadCameraControl::mouseReleaseEvent(QMouseEvent *event)
{
- emit mouseReleaseCoord(event->x(),event->y());
- getDeltaPositionPad(event->x(), event->y());
+ dragging = false;
+ //emit mouseReleaseCoord(event->x(),event->y());
+ //getDeltaPositionPad(event->x(), event->y());
+
+ xFin = event->x();
+ yFin = event->y();
+
}
@@ -59,6 +79,13 @@ void SlugsPadCameraControl::paintEvent(QPaintEvent *pe)
painter.drawLine(QPoint(ui->frame->geometry().topLeft().x(),ui->frame->height()/2),
QPoint(ui->frame->geometry().bottomRight().x(),ui->frame->height()/2));
+ painter.setPen(Qt::white);
+
+ //QPointF coordTemp = getPointBy_BearingDistance(ui->frame->width()/2,ui->frame->height()/2,bearingPad,distancePad);
+
+ painter.drawLine(QPoint(ui->frame->width()/2,ui->frame->height()/2),
+ QPoint(xFin,yFin));
+
// painter.drawLine(QPoint());
//painter.drawLines(padLines);
@@ -92,7 +119,7 @@ void SlugsPadCameraControl::getDeltaPositionPad(int x2, int y2)
{
emit dirCursorText("right up");
//bearing = 315;
- dir = "riht up";
+ dir = "right up";
}
else
{
@@ -100,7 +127,7 @@ void SlugsPadCameraControl::getDeltaPositionPad(int x2, int y2)
{
emit dirCursorText("right");
//bearing = 315;
- dir = "riht";
+ dir = "right";
}
else
{
@@ -108,7 +135,7 @@ void SlugsPadCameraControl::getDeltaPositionPad(int x2, int y2)
{
emit dirCursorText("right down");
//bearing = 315;
- dir = "riht down";
+ dir = "right down";
}
else
{
@@ -158,8 +185,15 @@ void SlugsPadCameraControl::getDeltaPositionPad(int x2, int y2)
}
+ bearingPad = bearing;
+ distancePad = dist;
+ directionPad = dir;
emit changeCursorPosition(bearing, dist, dir);
+ update();
+
+
+
}
double SlugsPadCameraControl::getDistPixel(int x1, int y1, int x2, int y2)
@@ -229,3 +263,19 @@ QPointF SlugsPadCameraControl::ObtenerMarcacionDistanciaPixel(double lon1, doubl
return QPointF(marcacion,distancia);
}
+
+
+
+QPointF SlugsPadCameraControl::getPointBy_BearingDistance(double lat1, double lon1, double rumbo, double distancia)
+{
+ double lon2 = 0;
+ double lat2 = 0;
+ double rad= M_PI/180;
+
+ rumbo = rumbo*rad;
+ lon2=(lon1 + ((distancia/60) * (sin(rumbo))));
+ lat2=(lat1 + ((distancia/60) * (cos(rumbo))));
+
+ return QPointF(lon2,lat2);
+}
+
diff --git a/src/ui/SlugsPadCameraControl.h b/src/ui/SlugsPadCameraControl.h
index 06a9233..bb35976 100644
--- a/src/ui/SlugsPadCameraControl.h
+++ b/src/ui/SlugsPadCameraControl.h
@@ -21,6 +21,9 @@ public slots:
void getDeltaPositionPad(int x, int y);
double getDistPixel(int x1, int y1, int x2, int y2);
QPointF ObtenerMarcacionDistanciaPixel(double lon1, double lat1, double lon2, double lat2);
+ QPointF getPointBy_BearingDistance(double lat1, double lon1, double rumbo, double distancia);
+
+
signals:
void mouseMoveCoord(int x, int y);
@@ -36,11 +39,17 @@ protected:
void mouseMoveEvent(QMouseEvent* event);
void paintEvent(QPaintEvent *pe);
+
private:
Ui::SlugsPadCameraControl *ui;
bool dragging;
int x1;
int y1;
+ int xFin;
+ int yFin;
+ double bearingPad;
+ double distancePad;
+ QString directionPad;
};
diff --git a/src/ui/SlugsVideoCamControl.cpp b/src/ui/SlugsVideoCamControl.cpp
index 1eb0b52..a7c9c67 100644
--- a/src/ui/SlugsVideoCamControl.cpp
+++ b/src/ui/SlugsVideoCamControl.cpp
@@ -20,29 +20,12 @@
SlugsVideoCamControl::SlugsVideoCamControl(QWidget *parent) :
QWidget(parent),
ui(new Ui::SlugsVideoCamControl)
- //dragging(0)
-
{
ui->setupUi(this);
// x1= 0;
// y1 = 0;
- connect(ui->viewCamBordeatMap_checkBox,SIGNAL(clicked(bool)),this,SLOT(changeViewCamBorderAtMapStatus(bool)));
-// tL = ui->padCamContro_frame->frameGeometry().topLeft();
-// bR = ui->padCamContro_frame->frameGeometry().bottomRight();
- //ui->padCamContro_frame->setVisible(true);
-
-// // create a layout for camera pad
-// QGridLayout* padCameraLayout = new QGridLayout(this);
-// padCameraLayout->setSpacing(2);
-// padCameraLayout->setMargin(0);
-// padCameraLayout->setAlignment(Qt::AlignTop);
-
- //ui->padCamContro_frame->setLayout(padCameraLayout);
- // create a camera pad widget
- //test = new QPushButton(QIcon(":/images/actions/list-add.svg"), "", this);
- //test->setMaximumWidth(50);
- //ui->gridLayout->addWidget(test, 0,0);
+ connect(ui->viewCamBordeatMap_checkBox,SIGNAL(clicked(bool)),this,SLOT(changeViewCamBorderAtMapStatus(bool)));
padCamera = new SlugsPadCameraControl(this);
ui->gridLayout->addWidget(padCamera);
@@ -53,28 +36,6 @@ SlugsVideoCamControl::SlugsVideoCamControl(QWidget *parent) :
connect(padCamera,SIGNAL(changeCursorPosition(double,double,QString)),this,SLOT(getDeltaPositionPad(double,double,QString)));
-
- //padCamera->setVisible(true);
-
-
-
- // padCameraLayout->addWidget(padCamera);
-
-
-
-// QGraphicsScene *scene = new QGraphicsScene(ui->CamControlPanel_graphicsView);
-// scene->setItemIndexMethod(QGraphicsScene::NoIndex);
-// scene->setSceneRect(-200, -200, 400, 400);
-// setScene(scene);
-// setCacheMode(CacheBackground);
-// setViewportUpdateMode(BoundingRectViewportUpdate);
-// setRenderHint(QPainter::Antialiasing);
-// setTransformationAnchor(AnchorUnderMouse);
-// setResizeAnchor(AnchorViewCenter);
-
-// ui->CamControlPanel_graphicsView->installEventFilter(this);
-// ui->label_x->installEventFilter(this);
-
}
SlugsVideoCamControl::~SlugsVideoCamControl()
@@ -82,41 +43,41 @@ SlugsVideoCamControl::~SlugsVideoCamControl()
delete ui;
}
-void SlugsVideoCamControl::mouseMoveEvent(QMouseEvent *event)
-{
- Q_UNUSED(event);
+//void SlugsVideoCamControl::mouseMoveEvent(QMouseEvent *event)
+//{
+// Q_UNUSED(event);
-}
+//}
-void SlugsVideoCamControl::mousePressEvent(QMouseEvent *evnt)
-{
- Q_UNUSED(evnt);
+//void SlugsVideoCamControl::mousePressEvent(QMouseEvent *evnt)
+//{
+// Q_UNUSED(evnt);
-}
+//}
-void SlugsVideoCamControl::mouseReleaseEvent(QMouseEvent *evnt)
-{
- Q_UNUSED(evnt);
+//void SlugsVideoCamControl::mouseReleaseEvent(QMouseEvent *evnt)
+//{
+// Q_UNUSED(evnt);
-}
+//}
-void SlugsVideoCamControl::mousePadMoveEvent(int x, int y)
-{
+//void SlugsVideoCamControl::mousePadMoveEvent(int x, int y)
+//{
-}
+//}
-void SlugsVideoCamControl::mousePadPressEvent(int x, int y)
-{
+//void SlugsVideoCamControl::mousePadPressEvent(int x, int y)
+//{
-}
+//}
-void SlugsVideoCamControl::mousePadReleaseEvent(int x, int y)
-{
+//void SlugsVideoCamControl::mousePadReleaseEvent(int x, int y)
+//{
-}
+//}
void SlugsVideoCamControl::changeViewCamBorderAtMapStatus(bool status)
{
diff --git a/src/ui/SlugsVideoCamControl.h b/src/ui/SlugsVideoCamControl.h
index 2580033..0180fd5 100644
--- a/src/ui/SlugsVideoCamControl.h
+++ b/src/ui/SlugsVideoCamControl.h
@@ -27,22 +27,43 @@ public:
~SlugsVideoCamControl();
public slots:
+ /**
+ * @brief status = true: emit signal to draw a border cam over the map
+ */
void changeViewCamBorderAtMapStatus(bool status);
- void getDeltaPositionPad(double dir, double dist, QString dirText);
-
-
- void mousePadPressEvent(int x, int y);
- void mousePadReleaseEvent(int x, int y);
- void mousePadMoveEvent(int x, int y);
+ /**
+ * @brief show the values of mousepad on ui (labels) and emit a changeCamPosition(signal)
+ * with values:
+ * bearing and distance from mouse over the pad
+ * dirText: direction of mouse movement in text format (up, right,right up,right down,
+ * left, left up, left down, down)
+ */
+ void getDeltaPositionPad(double bearing, double distance, QString dirText);
+
+// /**
+// * @brief
+// */
+// void mousePadPressEvent(int x, int y);
+// void mousePadReleaseEvent(int x, int y);
+// void mousePadMoveEvent(int x, int y);
signals:
- void changeCamPosition(double dist, double dir, QString textDir);
+ /**
+ * @brief emit values from mousepad:
+ * bearing and distance from mouse over the pad
+ * dirText: direction of mouse movement in text format (up, right,right up,right down,
+ * left, left up, left down, down)
+ */
+ void changeCamPosition(double distance, double bearing, QString textDir);
+ /**
+ * @brief emit signal to draw a border cam over the map if status is true
+ */
void viewCamBorderAtMap(bool status);
protected:
- void mousePressEvent(QMouseEvent* event);
- void mouseReleaseEvent(QMouseEvent* event);
- void mouseMoveEvent(QMouseEvent* event);
+// void mousePressEvent(QMouseEvent* event);
+// void mouseReleaseEvent(QMouseEvent* event);
+// void mouseMoveEvent(QMouseEvent* event);
diff --git a/src/ui/WaypointList.cc b/src/ui/WaypointList.cc
index 3b5b967..d2d4aae 100644
--- a/src/ui/WaypointList.cc
+++ b/src/ui/WaypointList.cc
@@ -153,7 +153,7 @@ void WaypointList::loadWaypoints()
QString fileName = QFileDialog::getOpenFileName(this, tr("Load File"), ".", tr("Waypoint File (*.txt)"));
uas->getWaypointManager().loadWaypoints(fileName);
- }
+ }
}
void WaypointList::transmit()
@@ -474,14 +474,14 @@ void WaypointList::on_clearWPListButton_clicked()
if (uas)
{
- emit clearPathclicked();
+ emit clearPathclicked();
const QVector &waypoints = uas->getWaypointManager().getWaypointList();
while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[0]).value();
widget->remove();
- }
}
+ }
else
{
// if(isGlobalWP)
diff --git a/src/ui/WaypointView.cc b/src/ui/WaypointView.cc
index b291fc8..ca7f981 100644
--- a/src/ui/WaypointView.cc
+++ b/src/ui/WaypointView.cc
@@ -146,6 +146,7 @@ void WaypointView::changedAction(int index)
break;
case MAV_ACTION_NAVIGATE:
m_ui->autoContinue->show();
+ m_ui->orbitSpinBox->show();
break;
case MAV_ACTION_LOITER:
m_ui->orbitSpinBox->show();
diff --git a/src/ui/linechart/LinechartPlot.cc b/src/ui/linechart/LinechartPlot.cc
index 7d16138..3a7cb01 100644
--- a/src/ui/linechart/LinechartPlot.cc
+++ b/src/ui/linechart/LinechartPlot.cc
@@ -56,7 +56,7 @@ maxInterval(MAX_STORAGE_INTERVAL),
timeScaleStep(DEFAULT_SCALE_INTERVAL), // 10 seconds
automaticScrollActive(false),
m_active(true),
-m_groundTime(false),
+m_groundTime(true),
d_data(NULL),
d_curve(NULL)
{
diff --git a/src/ui/linechart/Linecharts.cc b/src/ui/linechart/Linecharts.cc
index 2cfaf83..b47ea71 100644
--- a/src/ui/linechart/Linecharts.cc
+++ b/src/ui/linechart/Linecharts.cc
@@ -1,4 +1,5 @@
#include "Linecharts.h"
+#include "UASManager.h"
Linecharts::Linecharts(QWidget *parent) :
QStackedWidget(parent),
@@ -6,6 +7,18 @@ Linecharts::Linecharts(QWidget *parent) :
active(true)
{
this->setVisible(false);
+ // Get current MAV list
+ QList systems = UASManager::instance()->getUASList();
+
+ // Add each of them
+ foreach (UASInterface* sys, systems)
+ {
+ addSystem(sys);
+ }
+ connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)),
+ this, SLOT(addSystem(UASInterface*)));
+ connect(UASManager::instance(), SIGNAL(activeUASSet(int)),
+ this, SLOT(selectSystem(int)));
}
diff --git a/src/ui/map3D/GCManipulator.cc b/src/ui/map3D/GCManipulator.cc
index 6f2fb0e..06a7527 100644
--- a/src/ui/map3D/GCManipulator.cc
+++ b/src/ui/map3D/GCManipulator.cc
@@ -30,6 +30,7 @@ This file is part of the QGROUNDCONTROL project
*/
#include "GCManipulator.h"
+#include
GCManipulator::GCManipulator()
{
@@ -254,7 +255,7 @@ GCManipulator::calcMovement(void)
if (buttonMask == GUIEventAdapter::LEFT_MOUSE_BUTTON)
{
// rotate camera
-#ifdef __APPLE__
+#if ((OPENSCENEGRAPH_MAJOR_VERSION == 2) & (OPENSCENEGRAPH_MINOR_VERSION > 8)) | (OPENSCENEGRAPH_MAJOR_VERSION > 2)
osg::Vec3d axis;
#else
osg::Vec3 axis;
diff --git a/src/ui/map3D/QMap3D.cc b/src/ui/map3D/QMap3D.cc
index ab4c98b..f5d7ffb 100644
--- a/src/ui/map3D/QMap3D.cc
+++ b/src/ui/map3D/QMap3D.cc
@@ -38,8 +38,13 @@ This file is part of the QGROUNDCONTROL project
QMap3D::QMap3D(QWidget * parent, const char * name, WindowFlags f) :
QWidget(parent,f)
{
+ Q_UNUSED(name);
setupUi(this);
+#if ((OPENSCENEGRAPH_MAJOR_VERSION == 2) & (OPENSCENEGRAPH_MINOR_VERSION > 8)) | (OPENSCENEGRAPH_MAJOR_VERSION > 2)
+ graphicsView->setCameraManipulator(new osgEarth::Util::EarthManipulator);
+#else
graphicsView->setCameraManipulator(new osgEarthUtil::EarthManipulator);
+#endif
graphicsView->setSceneData(new osg::Group);
graphicsView->updateCamera();
show();