Commit eb21fe21 authored by Matthias Krebs's avatar Matthias Krebs

Implementation of 6DOF 3DMouse input (Windows only)

Implementation of 6DOF 3DMouse input (Windows only). Not tested yet.
parent 9483a2d9
# ------------------------------------------------- # -------------------------------------------------
# QGroundControl - Micro Air Vehicle Groundstation # QGroundControl - Micro Air Vehicle Groundstation
# Please see our website at <http://qgroundcontrol.org> # Please see our website at <http://qgroundcontrol.org>
# Maintainer: # Maintainer:
# Lorenz Meier <lm@inf.ethz.ch> # Lorenz Meier <lm@inf.ethz.ch>
# (c) 2009-2011 QGroundControl Developers # (c) 2009-2011 QGroundControl Developers
# This file is part of the open groundstation project # This file is part of the open groundstation project
# QGroundControl is free software: you can redistribute it and/or modify # QGroundControl is free software: you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by # it under the terms of the GNU General Public License as published by
# the Free Software Foundation, either version 3 of the License, or # the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version. # (at your option) any later version.
# QGroundControl is distributed in the hope that it will be useful, # QGroundControl is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of # but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU General Public License for more details. # GNU General Public License for more details.
# You should have received a copy of the GNU General Public License # You should have received a copy of the GNU General Public License
# along with QGroundControl. If not, see <http://www.gnu.org/licenses/>. # along with QGroundControl. If not, see <http://www.gnu.org/licenses/>.
# ------------------------------------------------- # -------------------------------------------------
# Qt configuration # Qt configuration
CONFIG += qt \ CONFIG += qt \
thread thread
QT += network \ QT += network \
opengl \ opengl \
svg \ svg \
xml \ xml \
phonon \ phonon \
webkit \ webkit \
sql sql
TEMPLATE = app TEMPLATE = app
TARGET = qgroundcontrol TARGET = qgroundcontrol
BASEDIR = $${IN_PWD} BASEDIR = $${IN_PWD}
linux-g++|linux-g++-64{ linux-g++|linux-g++-64{
debug { debug {
TARGETDIR = $${OUT_PWD}/debug TARGETDIR = $${OUT_PWD}/debug
BUILDDIR = $${OUT_PWD}/build-debug BUILDDIR = $${OUT_PWD}/build-debug
} }
release { release {
TARGETDIR = $${OUT_PWD}/release TARGETDIR = $${OUT_PWD}/release
BUILDDIR = $${OUT_PWD}/build-release BUILDDIR = $${OUT_PWD}/build-release
} }
} else { } else {
TARGETDIR = $${OUT_PWD} TARGETDIR = $${OUT_PWD}
BUILDDIR = $${OUT_PWD}/build BUILDDIR = $${OUT_PWD}/build
} }
LANGUAGE = C++ LANGUAGE = C++
OBJECTS_DIR = $${BUILDDIR}/obj OBJECTS_DIR = $${BUILDDIR}/obj
MOC_DIR = $${BUILDDIR}/moc MOC_DIR = $${BUILDDIR}/moc
UI_DIR = $${BUILDDIR}/ui UI_DIR = $${BUILDDIR}/ui
RCC_DIR = $${BUILDDIR}/rcc RCC_DIR = $${BUILDDIR}/rcc
MAVLINK_CONF = "pixhawk" MAVLINK_CONF = "pixhawk"
MAVLINKPATH = $$BASEDIR/libs/mavlink/include/mavlink/v1.0 MAVLINKPATH = $$BASEDIR/libs/mavlink/include/mavlink/v1.0
DEFINES += MAVLINK_NO_DATA DEFINES += MAVLINK_NO_DATA
win32 { win32 {
QMAKE_INCDIR_QT = $$(QTDIR)/include QMAKE_INCDIR_QT = $$(QTDIR)/include
QMAKE_LIBDIR_QT = $$(QTDIR)/lib QMAKE_LIBDIR_QT = $$(QTDIR)/lib
QMAKE_UIC = "$$(QTDIR)/bin/uic.exe" QMAKE_UIC = "$$(QTDIR)/bin/uic.exe"
QMAKE_MOC = "$$(QTDIR)/bin/moc.exe" QMAKE_MOC = "$$(QTDIR)/bin/moc.exe"
QMAKE_RCC = "$$(QTDIR)/bin/rcc.exe" QMAKE_RCC = "$$(QTDIR)/bin/rcc.exe"
QMAKE_QMAKE = "$$(QTDIR)/bin/qmake.exe" QMAKE_QMAKE = "$$(QTDIR)/bin/qmake.exe"
# Build QAX for GoogleEarth API access # Build QAX for GoogleEarth API access
!exists( $(QTDIR)/src/activeqt/Makefile ) { !exists( $(QTDIR)/src/activeqt/Makefile ) {
message( Making QAx (ONE TIME) ) message( Making QAx (ONE TIME) )
system( cd $$(QTDIR)\\src\\activeqt && $$(QTDIR)\\bin\\qmake.exe ) system( cd $$(QTDIR)\\src\\activeqt && $$(QTDIR)\\bin\\qmake.exe )
system( cd $$(QTDIR)\\src\\activeqt\\container && $$(QTDIR)\\bin\\qmake.exe ) system( cd $$(QTDIR)\\src\\activeqt\\container && $$(QTDIR)\\bin\\qmake.exe )
system( cd $$(QTDIR)\\src\\activeqt\\control && $$(QTDIR)\\bin\\qmake.exe ) system( cd $$(QTDIR)\\src\\activeqt\\control && $$(QTDIR)\\bin\\qmake.exe )
} }
} }
################################################################# #################################################################
# EXTERNAL LIBRARY CONFIGURATION # EXTERNAL LIBRARY CONFIGURATION
# EIGEN matrix library (header-only) # EIGEN matrix library (header-only)
INCLUDEPATH += libs/eigen INCLUDEPATH += libs/eigen
# OPMapControl library (from OpenPilot) # OPMapControl library (from OpenPilot)
include(libs/utils/utils_external.pri) include(libs/utils/utils_external.pri)
include(libs/opmapcontrol/opmapcontrol_external.pri) include(libs/opmapcontrol/opmapcontrol_external.pri)
DEPENDPATH += \ DEPENDPATH += \
libs/utils \ libs/utils \
libs/utils/src \ libs/utils/src \
libs/opmapcontrol \ libs/opmapcontrol \
libs/opmapcontrol/src \ libs/opmapcontrol/src \
libs/opmapcontrol/src/mapwidget libs/opmapcontrol/src/mapwidget
INCLUDEPATH += \ INCLUDEPATH += \
libs/utils \ libs/utils \
libs \ libs \
libs/opmapcontrol libs/opmapcontrol
# If the user config file exists, it will be included. # If the user config file exists, it will be included.
# if the variable MAVLINK_CONF contains the name of an # if the variable MAVLINK_CONF contains the name of an
# additional project, QGroundControl includes the support # additional project, QGroundControl includes the support
# of custom MAVLink messages of this project. It will also # of custom MAVLink messages of this project. It will also
# create a QGC_USE_{AUTOPILOT_NAME}_MESSAGES macro for use # create a QGC_USE_{AUTOPILOT_NAME}_MESSAGES macro for use
# within the actual code. # within the actual code.
exists(user_config.pri) { exists(user_config.pri) {
include(user_config.pri) include(user_config.pri)
message("----- USING CUSTOM USER QGROUNDCONTROL CONFIG FROM user_config.pri -----") message("----- USING CUSTOM USER QGROUNDCONTROL CONFIG FROM user_config.pri -----")
message("Adding support for additional MAVLink messages for: " $$MAVLINK_CONF) message("Adding support for additional MAVLink messages for: " $$MAVLINK_CONF)
message("------------------------------------------------------------------------") message("------------------------------------------------------------------------")
} }
INCLUDEPATH += $$MAVLINKPATH INCLUDEPATH += $$MAVLINKPATH
isEmpty(MAVLINK_CONF) { isEmpty(MAVLINK_CONF) {
INCLUDEPATH += $$MAVLINKPATH/common INCLUDEPATH += $$MAVLINKPATH/common
} else { } else {
INCLUDEPATH += $$MAVLINKPATH/$$MAVLINK_CONF INCLUDEPATH += $$MAVLINKPATH/$$MAVLINK_CONF
#DEFINES += 'MAVLINK_CONF="$${MAVLINK_CONF}.h"' #DEFINES += 'MAVLINK_CONF="$${MAVLINK_CONF}.h"'
DEFINES += $$sprintf('QGC_USE_%1_MESSAGES', $$upper($$MAVLINK_CONF)) DEFINES += $$sprintf('QGC_USE_%1_MESSAGES', $$upper($$MAVLINK_CONF))
} }
# Include general settings for QGroundControl # Include general settings for QGroundControl
# necessary as last include to override any non-acceptable settings # necessary as last include to override any non-acceptable settings
# done by the plugins above # done by the plugins above
include(qgroundcontrol.pri) include(qgroundcontrol.pri)
# Include MAVLink generator # Include MAVLink generator
# has been deprecated # has been deprecated
DEPENDPATH += \ DEPENDPATH += \
src/apps/mavlinkgen src/apps/mavlinkgen
INCLUDEPATH += \ INCLUDEPATH += \
src/apps/mavlinkgen \ src/apps/mavlinkgen \
src/apps/mavlinkgen/ui \ src/apps/mavlinkgen/ui \
src/apps/mavlinkgen/generator src/apps/mavlinkgen/generator
include(src/apps/mavlinkgen/mavlinkgen.pri) include(src/apps/mavlinkgen/mavlinkgen.pri)
# Include QWT plotting library # Include QWT plotting library
include(libs/qwt/qwt.pri) include(libs/qwt/qwt.pri)
DEPENDPATH += . \ DEPENDPATH += . \
plugins \ plugins \
libs/thirdParty/qserialport/include \ libs/thirdParty/qserialport/include \
libs/thirdParty/qserialport/include/QtSerialPort \ libs/thirdParty/qserialport/include/QtSerialPort \
libs/thirdParty/qserialport \ libs/thirdParty/qserialport \
libs/qextserialport libs/qextserialport
INCLUDEPATH += . \ INCLUDEPATH += . \
libs/thirdParty/qserialport/include \ libs/thirdParty/qserialport/include \
libs/thirdParty/qserialport/include/QtSerialPort \ libs/thirdParty/qserialport/include/QtSerialPort \
libs/thirdParty/qserialport/src \ libs/thirdParty/qserialport/src \
libs/qextserialport libs/qextserialport
# Include serial port library (QSerial) # Include serial port library (QSerial)
include(qserialport.pri) include(qserialport.pri)
# Serial port detection (ripped-off from qextserialport library) # Serial port detection (ripped-off from qextserialport library)
macx|macx-g++|macx-g++42::SOURCES += libs/qextserialport/qextserialenumerator_osx.cpp macx|macx-g++|macx-g++42::SOURCES += libs/qextserialport/qextserialenumerator_osx.cpp
linux-g++::SOURCES += libs/qextserialport/qextserialenumerator_unix.cpp linux-g++::SOURCES += libs/qextserialport/qextserialenumerator_unix.cpp
linux-g++-64::SOURCES += libs/qextserialport/qextserialenumerator_unix.cpp linux-g++-64::SOURCES += libs/qextserialport/qextserialenumerator_unix.cpp
win32::SOURCES += libs/qextserialport/qextserialenumerator_win.cpp win32::SOURCES += libs/qextserialport/qextserialenumerator_win.cpp
win32-msvc2008|win32-msvc2010::SOURCES += libs/qextserialport/qextserialenumerator_win.cpp win32-msvc2008|win32-msvc2010::SOURCES += libs/qextserialport/qextserialenumerator_win.cpp
# Input # Input
FORMS += src/ui/MainWindow.ui \ FORMS += src/ui/MainWindow.ui \
src/ui/CommSettings.ui \ src/ui/CommSettings.ui \
src/ui/SerialSettings.ui \ src/ui/SerialSettings.ui \
src/ui/UASControl.ui \ src/ui/UASControl.ui \
src/ui/UASList.ui \ src/ui/UASList.ui \
src/ui/UASInfo.ui \ src/ui/UASInfo.ui \
src/ui/Linechart.ui \ src/ui/Linechart.ui \
src/ui/UASView.ui \ src/ui/UASView.ui \
src/ui/ParameterInterface.ui \ src/ui/ParameterInterface.ui \
src/ui/WaypointList.ui \ src/ui/WaypointList.ui \
src/ui/ObjectDetectionView.ui \ src/ui/ObjectDetectionView.ui \
src/ui/JoystickWidget.ui \ src/ui/JoystickWidget.ui \
src/ui/DebugConsole.ui \ src/ui/DebugConsole.ui \
src/ui/HDDisplay.ui \ src/ui/HDDisplay.ui \
src/ui/MAVLinkSettingsWidget.ui \ src/ui/MAVLinkSettingsWidget.ui \
src/ui/AudioOutputWidget.ui \ src/ui/AudioOutputWidget.ui \
src/ui/QGCSensorSettingsWidget.ui \ src/ui/QGCSensorSettingsWidget.ui \
src/ui/watchdog/WatchdogControl.ui \ src/ui/watchdog/WatchdogControl.ui \
src/ui/watchdog/WatchdogProcessView.ui \ src/ui/watchdog/WatchdogProcessView.ui \
src/ui/watchdog/WatchdogView.ui \ src/ui/watchdog/WatchdogView.ui \
src/ui/QGCFirmwareUpdate.ui \ src/ui/QGCFirmwareUpdate.ui \
src/ui/QGCPxImuFirmwareUpdate.ui \ src/ui/QGCPxImuFirmwareUpdate.ui \
src/ui/QGCDataPlot2D.ui \ src/ui/QGCDataPlot2D.ui \
src/ui/QGCRemoteControlView.ui \ src/ui/QGCRemoteControlView.ui \
src/ui/QMap3D.ui \ src/ui/QMap3D.ui \
src/ui/QGCWebView.ui \ src/ui/QGCWebView.ui \
src/ui/map3D/QGCGoogleEarthView.ui \ src/ui/map3D/QGCGoogleEarthView.ui \
src/ui/SlugsDataSensorView.ui \ src/ui/SlugsDataSensorView.ui \
src/ui/SlugsHilSim.ui \ src/ui/SlugsHilSim.ui \
src/ui/SlugsPadCameraControl.ui \ src/ui/SlugsPadCameraControl.ui \
src/ui/uas/QGCUnconnectedInfoWidget.ui \ src/ui/uas/QGCUnconnectedInfoWidget.ui \
src/ui/designer/QGCToolWidget.ui \ src/ui/designer/QGCToolWidget.ui \
src/ui/designer/QGCParamSlider.ui \ src/ui/designer/QGCParamSlider.ui \
src/ui/designer/QGCActionButton.ui \ src/ui/designer/QGCActionButton.ui \
src/ui/designer/QGCCommandButton.ui \ src/ui/designer/QGCCommandButton.ui \
src/ui/QGCMAVLinkLogPlayer.ui \ src/ui/QGCMAVLinkLogPlayer.ui \
src/ui/QGCWaypointListMulti.ui \ src/ui/QGCWaypointListMulti.ui \
src/ui/QGCUDPLinkConfiguration.ui \ src/ui/QGCUDPLinkConfiguration.ui \
src/ui/QGCSettingsWidget.ui \ src/ui/QGCSettingsWidget.ui \
src/ui/UASControlParameters.ui \ src/ui/UASControlParameters.ui \
src/ui/map/QGCMapTool.ui \ src/ui/map/QGCMapTool.ui \
src/ui/map/QGCMapToolBar.ui \ src/ui/map/QGCMapToolBar.ui \
src/ui/QGCMAVLinkInspector.ui \ src/ui/QGCMAVLinkInspector.ui \
src/ui/WaypointViewOnlyView.ui \ src/ui/WaypointViewOnlyView.ui \
src/ui/WaypointEditableView.ui \ src/ui/WaypointEditableView.ui \
src/ui/UnconnectedUASInfoWidget.ui \ src/ui/UnconnectedUASInfoWidget.ui \
src/ui/mavlink/QGCMAVLinkMessageSender.ui \ src/ui/mavlink/QGCMAVLinkMessageSender.ui \
src/ui/firmwareupdate/QGCFirmwareUpdateWidget.ui \ src/ui/firmwareupdate/QGCFirmwareUpdateWidget.ui \
src/ui/QGCPluginHost.ui \ src/ui/QGCPluginHost.ui \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.ui \ src/ui/firmwareupdate/QGCPX4FirmwareUpdate.ui \
src/ui/mission/QGCMissionOther.ui \ src/ui/mission/QGCMissionOther.ui \
src/ui/mission/QGCMissionNavWaypoint.ui \ src/ui/mission/QGCMissionNavWaypoint.ui \
src/ui/mission/QGCMissionDoJump.ui \ src/ui/mission/QGCMissionDoJump.ui \
src/ui/mission/QGCMissionConditionDelay.ui \ src/ui/mission/QGCMissionConditionDelay.ui \
src/ui/mission/QGCMissionNavLoiterUnlim.ui \ src/ui/mission/QGCMissionNavLoiterUnlim.ui \
src/ui/mission/QGCMissionNavLoiterTurns.ui \ src/ui/mission/QGCMissionNavLoiterTurns.ui \
src/ui/mission/QGCMissionNavLoiterTime.ui \ src/ui/mission/QGCMissionNavLoiterTime.ui \
src/ui/mission/QGCMissionNavReturnToLaunch.ui \ src/ui/mission/QGCMissionNavReturnToLaunch.ui \
src/ui/mission/QGCMissionNavLand.ui \ src/ui/mission/QGCMissionNavLand.ui \
src/ui/mission/QGCMissionNavTakeoff.ui \ src/ui/mission/QGCMissionNavTakeoff.ui \
src/ui/mission/QGCMissionNavSweep.ui \ src/ui/mission/QGCMissionNavSweep.ui \
src/ui/mission/QGCMissionDoStartSearch.ui \ src/ui/mission/QGCMissionDoStartSearch.ui \
src/ui/mission/QGCMissionDoFinishSearch.ui \ src/ui/mission/QGCMissionDoFinishSearch.ui \
src/ui/QGCVehicleConfig.ui \ src/ui/QGCVehicleConfig.ui \
src/ui/QGCHilConfiguration.ui \ src/ui/QGCHilConfiguration.ui \
src/ui/QGCHilFlightGearConfiguration.ui \ src/ui/QGCHilFlightGearConfiguration.ui \
src/ui/QGCHilXPlaneConfiguration.ui src/ui/QGCHilXPlaneConfiguration.ui
INCLUDEPATH += src \ INCLUDEPATH += src \
src/ui \ src/ui \
src/ui/linechart \ src/ui/linechart \
src/ui/uas \ src/ui/uas \
src/ui/map \ src/ui/map \
src/uas \ src/uas \
src/comm \ src/comm \
include/ui \ include/ui \
src/input \ src/input \
src/lib/qmapcontrol \ src/lib/qmapcontrol \
src/ui/mavlink \ src/ui/mavlink \
src/ui/param \ src/ui/param \
src/ui/watchdog \ src/ui/watchdog \
src/ui/map3D \ src/ui/map3D \
src/ui/mission \ src/ui/mission \
src/ui/designer src/ui/designer
HEADERS += src/MG.h \ HEADERS += src/MG.h \
src/QGCCore.h \ src/QGCCore.h \
src/uas/UASInterface.h \ src/uas/UASInterface.h \
src/uas/UAS.h \ src/uas/UAS.h \
src/uas/UASManager.h \ src/uas/UASManager.h \
src/comm/LinkManager.h \ src/comm/LinkManager.h \
src/comm/LinkInterface.h \ src/comm/LinkInterface.h \
src/comm/SerialLinkInterface.h \ src/comm/SerialLinkInterface.h \
src/comm/SerialLink.h \ src/comm/SerialLink.h \
src/comm/ProtocolInterface.h \ src/comm/ProtocolInterface.h \
src/comm/MAVLinkProtocol.h \ src/comm/MAVLinkProtocol.h \
src/comm/QGCFlightGearLink.h \ src/comm/QGCFlightGearLink.h \
src/comm/QGCXPlaneLink.h \ src/comm/QGCXPlaneLink.h \
src/ui/CommConfigurationWindow.h \ src/ui/CommConfigurationWindow.h \
src/ui/SerialConfigurationWindow.h \ src/ui/SerialConfigurationWindow.h \
src/ui/MainWindow.h \ src/ui/MainWindow.h \
src/ui/uas/UASControlWidget.h \ src/ui/uas/UASControlWidget.h \
src/ui/uas/UASListWidget.h \ src/ui/uas/UASListWidget.h \
src/ui/uas/UASInfoWidget.h \ src/ui/uas/UASInfoWidget.h \
src/ui/HUD.h \ src/ui/HUD.h \
src/ui/linechart/LinechartWidget.h \ src/ui/linechart/LinechartWidget.h \
src/ui/linechart/LinechartPlot.h \ src/ui/linechart/LinechartPlot.h \
src/ui/linechart/Scrollbar.h \ src/ui/linechart/Scrollbar.h \
src/ui/linechart/ScrollZoomer.h \ src/ui/linechart/ScrollZoomer.h \
src/configuration.h \ src/configuration.h \
src/ui/uas/UASView.h \ src/ui/uas/UASView.h \
src/ui/CameraView.h \ src/ui/CameraView.h \
src/comm/MAVLinkSimulationLink.h \ src/comm/MAVLinkSimulationLink.h \
src/comm/UDPLink.h \ src/comm/UDPLink.h \
src/ui/ParameterInterface.h \ src/ui/ParameterInterface.h \
src/ui/WaypointList.h \ src/ui/WaypointList.h \
src/Waypoint.h \ src/Waypoint.h \
src/ui/ObjectDetectionView.h \ src/ui/ObjectDetectionView.h \
src/input/JoystickInput.h \ src/input/JoystickInput.h \
src/ui/JoystickWidget.h \ src/ui/JoystickWidget.h \
src/ui/DebugConsole.h \ src/ui/DebugConsole.h \
src/ui/HDDisplay.h \ src/ui/HDDisplay.h \
src/ui/MAVLinkSettingsWidget.h \ src/ui/MAVLinkSettingsWidget.h \
src/ui/AudioOutputWidget.h \ src/ui/AudioOutputWidget.h \
src/GAudioOutput.h \ src/GAudioOutput.h \
src/LogCompressor.h \ src/LogCompressor.h \
src/ui/QGCParamWidget.h \ src/ui/QGCParamWidget.h \
src/ui/QGCSensorSettingsWidget.h \ src/ui/QGCSensorSettingsWidget.h \
src/ui/linechart/Linecharts.h \ src/ui/linechart/Linecharts.h \
src/uas/SlugsMAV.h \ src/uas/SlugsMAV.h \
src/uas/PxQuadMAV.h \ src/uas/PxQuadMAV.h \
src/uas/ArduPilotMegaMAV.h \ src/uas/ArduPilotMegaMAV.h \
src/uas/senseSoarMAV.h \ src/uas/senseSoarMAV.h \
src/ui/watchdog/WatchdogControl.h \ src/ui/watchdog/WatchdogControl.h \
src/ui/watchdog/WatchdogProcessView.h \ src/ui/watchdog/WatchdogProcessView.h \
src/ui/watchdog/WatchdogView.h \ src/ui/watchdog/WatchdogView.h \
src/uas/UASWaypointManager.h \ src/uas/UASWaypointManager.h \
src/ui/HSIDisplay.h \ src/ui/HSIDisplay.h \
src/QGC.h \ src/QGC.h \
src/ui/QGCFirmwareUpdate.h \ src/ui/QGCFirmwareUpdate.h \
src/ui/QGCPxImuFirmwareUpdate.h \ src/ui/QGCPxImuFirmwareUpdate.h \
src/ui/QGCDataPlot2D.h \ src/ui/QGCDataPlot2D.h \
src/ui/linechart/IncrementalPlot.h \ src/ui/linechart/IncrementalPlot.h \
src/ui/QGCRemoteControlView.h \ src/ui/QGCRemoteControlView.h \
src/ui/RadioCalibration/RadioCalibrationData.h \ src/ui/RadioCalibration/RadioCalibrationData.h \
src/ui/RadioCalibration/RadioCalibrationWindow.h \ src/ui/RadioCalibration/RadioCalibrationWindow.h \
src/ui/RadioCalibration/AirfoilServoCalibrator.h \ src/ui/RadioCalibration/AirfoilServoCalibrator.h \
src/ui/RadioCalibration/SwitchCalibrator.h \ src/ui/RadioCalibration/SwitchCalibrator.h \
src/ui/RadioCalibration/CurveCalibrator.h \ src/ui/RadioCalibration/CurveCalibrator.h \
src/ui/RadioCalibration/AbstractCalibrator.h \ src/ui/RadioCalibration/AbstractCalibrator.h \
src/comm/QGCMAVLink.h \ src/comm/QGCMAVLink.h \
src/ui/QGCWebView.h \ src/ui/QGCWebView.h \
src/ui/map3D/QGCWebPage.h \ src/ui/map3D/QGCWebPage.h \
src/ui/SlugsDataSensorView.h \ src/ui/SlugsDataSensorView.h \
src/ui/SlugsHilSim.h \ src/ui/SlugsHilSim.h \
src/ui/SlugsPadCameraControl.h \ src/ui/SlugsPadCameraControl.h \
src/ui/QGCMainWindowAPConfigurator.h \ src/ui/QGCMainWindowAPConfigurator.h \
src/comm/MAVLinkSwarmSimulationLink.h \ src/comm/MAVLinkSwarmSimulationLink.h \
src/ui/uas/QGCUnconnectedInfoWidget.h \ src/ui/uas/QGCUnconnectedInfoWidget.h \
src/ui/designer/QGCToolWidget.h \ src/ui/designer/QGCToolWidget.h \
src/ui/designer/QGCParamSlider.h \ src/ui/designer/QGCParamSlider.h \
src/ui/designer/QGCCommandButton.h \ src/ui/designer/QGCCommandButton.h \
src/ui/designer/QGCToolWidgetItem.h \ src/ui/designer/QGCToolWidgetItem.h \
src/ui/QGCMAVLinkLogPlayer.h \ src/ui/QGCMAVLinkLogPlayer.h \
src/comm/MAVLinkSimulationWaypointPlanner.h \ src/comm/MAVLinkSimulationWaypointPlanner.h \
src/comm/MAVLinkSimulationMAV.h \ src/comm/MAVLinkSimulationMAV.h \
src/uas/QGCMAVLinkUASFactory.h \ src/uas/QGCMAVLinkUASFactory.h \
src/ui/QGCWaypointListMulti.h \ src/ui/QGCWaypointListMulti.h \
src/ui/QGCUDPLinkConfiguration.h \ src/ui/QGCUDPLinkConfiguration.h \
src/ui/QGCSettingsWidget.h \ src/ui/QGCSettingsWidget.h \
src/ui/uas/UASControlParameters.h \ src/ui/uas/UASControlParameters.h \
src/uas/QGCUASParamManager.h \ src/uas/QGCUASParamManager.h \
src/ui/map/QGCMapWidget.h \ src/ui/map/QGCMapWidget.h \
src/ui/map/MAV2DIcon.h \ src/ui/map/MAV2DIcon.h \
src/ui/map/Waypoint2DIcon.h \ src/ui/map/Waypoint2DIcon.h \
src/ui/map/QGCMapTool.h \ src/ui/map/QGCMapTool.h \
src/ui/map/QGCMapToolBar.h \ src/ui/map/QGCMapToolBar.h \
libs/qextserialport/qextserialenumerator.h \ libs/qextserialport/qextserialenumerator.h \
src/QGCGeo.h \ src/QGCGeo.h \
src/ui/QGCToolBar.h \ src/ui/QGCToolBar.h \
src/ui/QGCMAVLinkInspector.h \ src/ui/QGCMAVLinkInspector.h \
src/ui/MAVLinkDecoder.h \ src/ui/MAVLinkDecoder.h \
src/ui/WaypointViewOnlyView.h \ src/ui/WaypointViewOnlyView.h \
src/ui/WaypointViewOnlyView.h \ src/ui/WaypointViewOnlyView.h \
src/ui/WaypointEditableView.h \ src/ui/WaypointEditableView.h \
src/ui/UnconnectedUASInfoWidget.h \ src/ui/UnconnectedUASInfoWidget.h \
src/ui/QGCRGBDView.h \ src/ui/QGCRGBDView.h \
src/ui/mavlink/QGCMAVLinkMessageSender.h \ src/ui/mavlink/QGCMAVLinkMessageSender.h \
src/ui/firmwareupdate/QGCFirmwareUpdateWidget.h \ src/ui/firmwareupdate/QGCFirmwareUpdateWidget.h \
src/ui/QGCPluginHost.h \ src/ui/QGCPluginHost.h \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.h \ src/ui/firmwareupdate/QGCPX4FirmwareUpdate.h \
src/ui/mission/QGCMissionOther.h \ src/ui/mission/QGCMissionOther.h \
src/ui/mission/QGCMissionNavWaypoint.h \ src/ui/mission/QGCMissionNavWaypoint.h \
src/ui/mission/QGCMissionDoJump.h \ src/ui/mission/QGCMissionDoJump.h \
src/ui/mission/QGCMissionConditionDelay.h \ src/ui/mission/QGCMissionConditionDelay.h \
src/ui/mission/QGCMissionNavLoiterUnlim.h \ src/ui/mission/QGCMissionNavLoiterUnlim.h \
src/ui/mission/QGCMissionNavLoiterTurns.h \ src/ui/mission/QGCMissionNavLoiterTurns.h \
src/ui/mission/QGCMissionNavLoiterTime.h \ src/ui/mission/QGCMissionNavLoiterTime.h \
src/ui/mission/QGCMissionNavReturnToLaunch.h \ src/ui/mission/QGCMissionNavReturnToLaunch.h \
src/ui/mission/QGCMissionNavLand.h \ src/ui/mission/QGCMissionNavLand.h \
src/ui/mission/QGCMissionNavTakeoff.h \ src/ui/mission/QGCMissionNavTakeoff.h \
src/ui/mission/QGCMissionNavSweep.h \ src/ui/mission/QGCMissionNavSweep.h \
src/ui/mission/QGCMissionDoStartSearch.h \ src/ui/mission/QGCMissionDoStartSearch.h \
src/ui/mission/QGCMissionDoFinishSearch.h \ src/ui/mission/QGCMissionDoFinishSearch.h \
src/ui/QGCVehicleConfig.h \ src/ui/QGCVehicleConfig.h \
src/comm/QGCHilLink.h \ src/comm/QGCHilLink.h \
src/ui/QGCHilConfiguration.h \ src/ui/QGCHilConfiguration.h \
src/ui/QGCHilFlightGearConfiguration.h \ src/ui/QGCHilFlightGearConfiguration.h \
src/ui/QGCHilXPlaneConfiguration.h src/ui/QGCHilXPlaneConfiguration.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler # Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::HEADERS += src/ui/map3D/QGCGoogleEarthView.h macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::HEADERS += src/ui/map3D/QGCGoogleEarthView.h
contains(DEPENDENCIES_PRESENT, osg) { contains(DEPENDENCIES_PRESENT, osg) {
message("Including headers for OpenSceneGraph") message("Including headers for OpenSceneGraph")
# Enable only if OpenSceneGraph is available # Enable only if OpenSceneGraph is available
HEADERS += src/ui/map3D/gpl.h \ HEADERS += src/ui/map3D/gpl.h \
src/ui/map3D/CameraParams.h \ src/ui/map3D/CameraParams.h \
src/ui/map3D/ViewParamWidget.h \ src/ui/map3D/ViewParamWidget.h \
src/ui/map3D/SystemContainer.h \ src/ui/map3D/SystemContainer.h \
src/ui/map3D/SystemViewParams.h \ src/ui/map3D/SystemViewParams.h \
src/ui/map3D/GlobalViewParams.h \ src/ui/map3D/GlobalViewParams.h \
src/ui/map3D/SystemGroupNode.h \ src/ui/map3D/SystemGroupNode.h \
src/ui/map3D/Q3DWidget.h \ src/ui/map3D/Q3DWidget.h \
src/ui/map3D/GCManipulator.h \ src/ui/map3D/GCManipulator.h \
src/ui/map3D/ImageWindowGeode.h \ src/ui/map3D/ImageWindowGeode.h \
src/ui/map3D/PixhawkCheetahNode.h \ src/ui/map3D/PixhawkCheetahNode.h \
src/ui/map3D/Pixhawk3DWidget.h \ src/ui/map3D/Pixhawk3DWidget.h \
src/ui/map3D/Q3DWidgetFactory.h \ src/ui/map3D/Q3DWidgetFactory.h \
src/ui/map3D/WebImageCache.h \ src/ui/map3D/WebImageCache.h \
src/ui/map3D/WebImage.h \ src/ui/map3D/WebImage.h \
src/ui/map3D/TextureCache.h \ src/ui/map3D/TextureCache.h \
src/ui/map3D/Texture.h \ src/ui/map3D/Texture.h \
src/ui/map3D/Imagery.h \ src/ui/map3D/Imagery.h \
src/ui/map3D/HUDScaleGeode.h \ src/ui/map3D/HUDScaleGeode.h \
src/ui/map3D/WaypointGroupNode.h \ src/ui/map3D/WaypointGroupNode.h \
src/ui/map3D/TerrainParamDialog.h \ src/ui/map3D/TerrainParamDialog.h \
src/ui/map3D/ImageryParamDialog.h src/ui/map3D/ImageryParamDialog.h
} }
contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) { contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) {
message("Including headers for Protocol Buffers") message("Including headers for Protocol Buffers")
# Enable only if protobuf is available # Enable only if protobuf is available
HEADERS += libs/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.pb.h \ HEADERS += libs/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.pb.h \
src/ui/map3D/ObstacleGroupNode.h \ src/ui/map3D/ObstacleGroupNode.h \
src/ui/map3D/GLOverlayGeode.h src/ui/map3D/GLOverlayGeode.h
} }
contains(DEPENDENCIES_PRESENT, libfreenect) { contains(DEPENDENCIES_PRESENT, libfreenect) {
message("Including headers for libfreenect") message("Including headers for libfreenect")
# Enable only if libfreenect is available # Enable only if libfreenect is available
HEADERS += src/input/Freenect.h HEADERS += src/input/Freenect.h
} }
SOURCES += src/main.cc \ SOURCES += src/main.cc \
src/QGCCore.cc \ src/QGCCore.cc \
src/uas/UASManager.cc \ src/uas/UASManager.cc \
src/uas/UAS.cc \ src/uas/UAS.cc \
src/comm/LinkManager.cc \ src/comm/LinkManager.cc \
src/comm/LinkInterface.cpp \ src/comm/LinkInterface.cpp \
src/comm/SerialLink.cc \ src/comm/SerialLink.cc \
src/comm/MAVLinkProtocol.cc \ src/comm/MAVLinkProtocol.cc \
src/comm/QGCFlightGearLink.cc \ src/comm/QGCFlightGearLink.cc \
src/comm/QGCXPlaneLink.cc \ src/comm/QGCXPlaneLink.cc \
src/ui/CommConfigurationWindow.cc \ src/ui/CommConfigurationWindow.cc \
src/ui/SerialConfigurationWindow.cc \ src/ui/SerialConfigurationWindow.cc \
src/ui/MainWindow.cc \ src/ui/MainWindow.cc \
src/ui/uas/UASControlWidget.cc \ src/ui/uas/UASControlWidget.cc \
src/ui/uas/UASListWidget.cc \ src/ui/uas/UASListWidget.cc \
src/ui/uas/UASInfoWidget.cc \ src/ui/uas/UASInfoWidget.cc \
src/ui/HUD.cc \ src/ui/HUD.cc \
src/ui/linechart/LinechartWidget.cc \ src/ui/linechart/LinechartWidget.cc \
src/ui/linechart/LinechartPlot.cc \ src/ui/linechart/LinechartPlot.cc \
src/ui/linechart/Scrollbar.cc \ src/ui/linechart/Scrollbar.cc \
src/ui/linechart/ScrollZoomer.cc \ src/ui/linechart/ScrollZoomer.cc \
src/ui/uas/UASView.cc \ src/ui/uas/UASView.cc \
src/ui/CameraView.cc \ src/ui/CameraView.cc \
src/comm/MAVLinkSimulationLink.cc \ src/comm/MAVLinkSimulationLink.cc \
src/comm/UDPLink.cc \ src/comm/UDPLink.cc \
src/ui/ParameterInterface.cc \ src/ui/ParameterInterface.cc \
src/ui/WaypointList.cc \ src/ui/WaypointList.cc \
src/Waypoint.cc \ src/Waypoint.cc \
src/ui/ObjectDetectionView.cc \ src/ui/ObjectDetectionView.cc \
src/input/JoystickInput.cc \ src/input/JoystickInput.cc \
src/ui/JoystickWidget.cc \ src/ui/JoystickWidget.cc \
src/ui/DebugConsole.cc \ src/ui/DebugConsole.cc \
src/ui/HDDisplay.cc \ src/ui/HDDisplay.cc \
src/ui/MAVLinkSettingsWidget.cc \ src/ui/MAVLinkSettingsWidget.cc \
src/ui/AudioOutputWidget.cc \ src/ui/AudioOutputWidget.cc \
src/GAudioOutput.cc \ src/GAudioOutput.cc \
src/LogCompressor.cc \ src/LogCompressor.cc \
src/ui/QGCParamWidget.cc \ src/ui/QGCParamWidget.cc \
src/ui/QGCSensorSettingsWidget.cc \ src/ui/QGCSensorSettingsWidget.cc \
src/ui/linechart/Linecharts.cc \ src/ui/linechart/Linecharts.cc \
src/uas/SlugsMAV.cc \ src/uas/SlugsMAV.cc \
src/uas/PxQuadMAV.cc \ src/uas/PxQuadMAV.cc \
src/uas/ArduPilotMegaMAV.cc \ src/uas/ArduPilotMegaMAV.cc \
src/uas/senseSoarMAV.cpp \ src/uas/senseSoarMAV.cpp \
src/ui/watchdog/WatchdogControl.cc \ src/ui/watchdog/WatchdogControl.cc \
src/ui/watchdog/WatchdogProcessView.cc \ src/ui/watchdog/WatchdogProcessView.cc \
src/ui/watchdog/WatchdogView.cc \ src/ui/watchdog/WatchdogView.cc \
src/uas/UASWaypointManager.cc \ src/uas/UASWaypointManager.cc \
src/ui/HSIDisplay.cc \ src/ui/HSIDisplay.cc \
src/QGC.cc \ src/QGC.cc \
src/ui/QGCFirmwareUpdate.cc \ src/ui/QGCFirmwareUpdate.cc \
src/ui/QGCPxImuFirmwareUpdate.cc \ src/ui/QGCPxImuFirmwareUpdate.cc \
src/ui/QGCDataPlot2D.cc \ src/ui/QGCDataPlot2D.cc \
src/ui/linechart/IncrementalPlot.cc \ src/ui/linechart/IncrementalPlot.cc \
src/ui/QGCRemoteControlView.cc \ src/ui/QGCRemoteControlView.cc \
src/ui/RadioCalibration/RadioCalibrationWindow.cc \ src/ui/RadioCalibration/RadioCalibrationWindow.cc \
src/ui/RadioCalibration/AirfoilServoCalibrator.cc \ src/ui/RadioCalibration/AirfoilServoCalibrator.cc \
src/ui/RadioCalibration/SwitchCalibrator.cc \ src/ui/RadioCalibration/SwitchCalibrator.cc \
src/ui/RadioCalibration/CurveCalibrator.cc \ src/ui/RadioCalibration/CurveCalibrator.cc \
src/ui/RadioCalibration/AbstractCalibrator.cc \ src/ui/RadioCalibration/AbstractCalibrator.cc \
src/ui/RadioCalibration/RadioCalibrationData.cc \ src/ui/RadioCalibration/RadioCalibrationData.cc \
src/ui/QGCWebView.cc \ src/ui/QGCWebView.cc \
src/ui/map3D/QGCWebPage.cc \ src/ui/map3D/QGCWebPage.cc \
src/ui/SlugsDataSensorView.cc \ src/ui/SlugsDataSensorView.cc \
src/ui/SlugsHilSim.cc \ src/ui/SlugsHilSim.cc \
src/ui/SlugsPadCameraControl.cpp \ src/ui/SlugsPadCameraControl.cpp \
src/ui/QGCMainWindowAPConfigurator.cc \ src/ui/QGCMainWindowAPConfigurator.cc \
src/comm/MAVLinkSwarmSimulationLink.cc \ src/comm/MAVLinkSwarmSimulationLink.cc \
src/ui/uas/QGCUnconnectedInfoWidget.cc \ src/ui/uas/QGCUnconnectedInfoWidget.cc \
src/ui/designer/QGCToolWidget.cc \ src/ui/designer/QGCToolWidget.cc \
src/ui/designer/QGCParamSlider.cc \ src/ui/designer/QGCParamSlider.cc \
src/ui/designer/QGCCommandButton.cc \ src/ui/designer/QGCCommandButton.cc \
src/ui/designer/QGCToolWidgetItem.cc \ src/ui/designer/QGCToolWidgetItem.cc \
src/ui/QGCMAVLinkLogPlayer.cc \ src/ui/QGCMAVLinkLogPlayer.cc \
src/comm/MAVLinkSimulationWaypointPlanner.cc \ src/comm/MAVLinkSimulationWaypointPlanner.cc \
src/comm/MAVLinkSimulationMAV.cc \ src/comm/MAVLinkSimulationMAV.cc \
src/uas/QGCMAVLinkUASFactory.cc \ src/uas/QGCMAVLinkUASFactory.cc \
src/ui/QGCWaypointListMulti.cc \ src/ui/QGCWaypointListMulti.cc \
src/ui/QGCUDPLinkConfiguration.cc \ src/ui/QGCUDPLinkConfiguration.cc \
src/ui/QGCSettingsWidget.cc \ src/ui/QGCSettingsWidget.cc \
src/ui/uas/UASControlParameters.cpp \ src/ui/uas/UASControlParameters.cpp \
src/uas/QGCUASParamManager.cc \ src/uas/QGCUASParamManager.cc \
src/ui/map/QGCMapWidget.cc \ src/ui/map/QGCMapWidget.cc \
src/ui/map/MAV2DIcon.cc \ src/ui/map/MAV2DIcon.cc \
src/ui/map/Waypoint2DIcon.cc \ src/ui/map/Waypoint2DIcon.cc \
src/ui/map/QGCMapTool.cc \ src/ui/map/QGCMapTool.cc \
src/ui/map/QGCMapToolBar.cc \ src/ui/map/QGCMapToolBar.cc \
src/ui/QGCToolBar.cc \ src/ui/QGCToolBar.cc \
src/ui/QGCMAVLinkInspector.cc \ src/ui/QGCMAVLinkInspector.cc \
src/ui/MAVLinkDecoder.cc \ src/ui/MAVLinkDecoder.cc \
src/ui/WaypointViewOnlyView.cc \ src/ui/WaypointViewOnlyView.cc \
src/ui/WaypointEditableView.cc \ src/ui/WaypointEditableView.cc \
src/ui/UnconnectedUASInfoWidget.cc \ src/ui/UnconnectedUASInfoWidget.cc \
src/ui/QGCRGBDView.cc \ src/ui/QGCRGBDView.cc \
src/ui/mavlink/QGCMAVLinkMessageSender.cc \ src/ui/mavlink/QGCMAVLinkMessageSender.cc \
src/ui/firmwareupdate/QGCFirmwareUpdateWidget.cc \ src/ui/firmwareupdate/QGCFirmwareUpdateWidget.cc \
src/ui/QGCPluginHost.cc \ src/ui/QGCPluginHost.cc \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.cc \ src/ui/firmwareupdate/QGCPX4FirmwareUpdate.cc \
src/ui/mission/QGCMissionOther.cc \ src/ui/mission/QGCMissionOther.cc \
src/ui/mission/QGCMissionNavWaypoint.cc \ src/ui/mission/QGCMissionNavWaypoint.cc \
src/ui/mission/QGCMissionDoJump.cc \ src/ui/mission/QGCMissionDoJump.cc \
src/ui/mission/QGCMissionConditionDelay.cc \ src/ui/mission/QGCMissionConditionDelay.cc \
src/ui/mission/QGCMissionNavLoiterUnlim.cc \ src/ui/mission/QGCMissionNavLoiterUnlim.cc \
src/ui/mission/QGCMissionNavLoiterTurns.cc \ src/ui/mission/QGCMissionNavLoiterTurns.cc \
src/ui/mission/QGCMissionNavLoiterTime.cc \ src/ui/mission/QGCMissionNavLoiterTime.cc \
src/ui/mission/QGCMissionNavReturnToLaunch.cc \ src/ui/mission/QGCMissionNavReturnToLaunch.cc \
src/ui/mission/QGCMissionNavLand.cc \ src/ui/mission/QGCMissionNavLand.cc \
src/ui/mission/QGCMissionNavTakeoff.cc \ src/ui/mission/QGCMissionNavTakeoff.cc \
src/ui/mission/QGCMissionNavSweep.cc \ src/ui/mission/QGCMissionNavSweep.cc \
src/ui/mission/QGCMissionDoStartSearch.cc \ src/ui/mission/QGCMissionDoStartSearch.cc \
src/ui/mission/QGCMissionDoFinishSearch.cc \ src/ui/mission/QGCMissionDoFinishSearch.cc \
src/ui/QGCVehicleConfig.cc \ src/ui/QGCVehicleConfig.cc \
src/ui/QGCHilConfiguration.cc \ src/ui/QGCHilConfiguration.cc \
src/ui/QGCHilFlightGearConfiguration.cc \ src/ui/QGCHilFlightGearConfiguration.cc \
src/ui/QGCHilXPlaneConfiguration.cc src/ui/QGCHilXPlaneConfiguration.cc
# Enable Google Earth only on Mac OS and Windows with Visual Studio compiler # Enable Google Earth only on Mac OS and Windows with Visual Studio compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
# Enable OSG only if it has been found # Enable OSG only if it has been found
contains(DEPENDENCIES_PRESENT, osg) { contains(DEPENDENCIES_PRESENT, osg) {
message("Including sources for OpenSceneGraph") message("Including sources for OpenSceneGraph")
# Enable only if OpenSceneGraph is available # Enable only if OpenSceneGraph is available
SOURCES += src/ui/map3D/gpl.cc \ SOURCES += src/ui/map3D/gpl.cc \
src/ui/map3D/CameraParams.cc \ src/ui/map3D/CameraParams.cc \
src/ui/map3D/ViewParamWidget.cc \ src/ui/map3D/ViewParamWidget.cc \
src/ui/map3D/SystemContainer.cc \ src/ui/map3D/SystemContainer.cc \
src/ui/map3D/SystemViewParams.cc \ src/ui/map3D/SystemViewParams.cc \
src/ui/map3D/GlobalViewParams.cc \ src/ui/map3D/GlobalViewParams.cc \
src/ui/map3D/SystemGroupNode.cc \ src/ui/map3D/SystemGroupNode.cc \
src/ui/map3D/Q3DWidget.cc \ src/ui/map3D/Q3DWidget.cc \
src/ui/map3D/ImageWindowGeode.cc \ src/ui/map3D/ImageWindowGeode.cc \
src/ui/map3D/GCManipulator.cc \ src/ui/map3D/GCManipulator.cc \
src/ui/map3D/PixhawkCheetahNode.cc \ src/ui/map3D/PixhawkCheetahNode.cc \
src/ui/map3D/Pixhawk3DWidget.cc \ src/ui/map3D/Pixhawk3DWidget.cc \
src/ui/map3D/Q3DWidgetFactory.cc \ src/ui/map3D/Q3DWidgetFactory.cc \
src/ui/map3D/WebImageCache.cc \ src/ui/map3D/WebImageCache.cc \
src/ui/map3D/WebImage.cc \ src/ui/map3D/WebImage.cc \
src/ui/map3D/TextureCache.cc \ src/ui/map3D/TextureCache.cc \
src/ui/map3D/Texture.cc \ src/ui/map3D/Texture.cc \
src/ui/map3D/Imagery.cc \ src/ui/map3D/Imagery.cc \
src/ui/map3D/HUDScaleGeode.cc \ src/ui/map3D/HUDScaleGeode.cc \
src/ui/map3D/WaypointGroupNode.cc \ src/ui/map3D/WaypointGroupNode.cc \
src/ui/map3D/TerrainParamDialog.cc \ src/ui/map3D/TerrainParamDialog.cc \
src/ui/map3D/ImageryParamDialog.cc src/ui/map3D/ImageryParamDialog.cc
contains(DEPENDENCIES_PRESENT, osgearth) { contains(DEPENDENCIES_PRESENT, osgearth) {
message("Including sources for osgEarth") message("Including sources for osgEarth")
# Enable only if OpenSceneGraph is available # Enable only if OpenSceneGraph is available
SOURCES += SOURCES +=
} }
} }
contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) { contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) {
message("Including sources for Protocol Buffers") message("Including sources for Protocol Buffers")
# Enable only if protobuf is available # Enable only if protobuf is available
SOURCES += libs/mavlink/share/mavlink/src/v1.0/pixhawk/pixhawk.pb.cc \ SOURCES += libs/mavlink/share/mavlink/src/v1.0/pixhawk/pixhawk.pb.cc \
src/ui/map3D/ObstacleGroupNode.cc \ src/ui/map3D/ObstacleGroupNode.cc \
src/ui/map3D/GLOverlayGeode.cc src/ui/map3D/GLOverlayGeode.cc
} }
contains(DEPENDENCIES_PRESENT, libfreenect) { contains(DEPENDENCIES_PRESENT, libfreenect) {
message("Including sources for libfreenect") message("Including sources for libfreenect")
# Enable only if libfreenect is available # Enable only if libfreenect is available
SOURCES += src/input/Freenect.cc SOURCES += src/input/Freenect.cc
} }
# Add icons and other resources # Add icons and other resources
RESOURCES += qgroundcontrol.qrc RESOURCES += qgroundcontrol.qrc
# Include RT-LAB Library # Include RT-LAB Library
win32:exists(src/lib/opalrt/OpalApi.h):exists(C:/OPAL-RT/RT-LAB7.2.4/Common/bin) { win32:exists(src/lib/opalrt/OpalApi.h):exists(C:/OPAL-RT/RT-LAB7.2.4/Common/bin) {
message("Building support for Opal-RT") message("Building support for Opal-RT")
LIBS += -LC:/OPAL-RT/RT-LAB7.2.4/Common/bin \ LIBS += -LC:/OPAL-RT/RT-LAB7.2.4/Common/bin \
-lOpalApi -lOpalApi
INCLUDEPATH += src/lib/opalrt INCLUDEPATH += src/lib/opalrt
HEADERS += src/comm/OpalRT.h \ HEADERS += src/comm/OpalRT.h \
src/comm/OpalLink.h \ src/comm/OpalLink.h \
src/comm/Parameter.h \ src/comm/Parameter.h \
src/comm/QGCParamID.h \ src/comm/QGCParamID.h \
src/comm/ParameterList.h \ src/comm/ParameterList.h \
src/ui/OpalLinkConfigurationWindow.h src/ui/OpalLinkConfigurationWindow.h
SOURCES += src/comm/OpalRT.cc \ SOURCES += src/comm/OpalRT.cc \
src/comm/OpalLink.cc \ src/comm/OpalLink.cc \
src/comm/Parameter.cc \ src/comm/Parameter.cc \
src/comm/QGCParamID.cc \ src/comm/QGCParamID.cc \
src/comm/ParameterList.cc \ src/comm/ParameterList.cc \
src/ui/OpalLinkConfigurationWindow.cc src/ui/OpalLinkConfigurationWindow.cc
FORMS += src/ui/OpalLinkSettings.ui FORMS += src/ui/OpalLinkSettings.ui
DEFINES += OPAL_RT DEFINES += OPAL_RT
} }
TRANSLATIONS += es-MX.ts \ TRANSLATIONS += es-MX.ts \
en-US.ts en-US.ts
# xbee support # xbee support
# libxbee only supported by linux and windows systems # libxbee only supported by linux and windows systems
win32-msvc2008|win32-msvc2010|linux { win32-msvc2008|win32-msvc2010|linux {
HEADERS += src/comm/XbeeLinkInterface.h \ HEADERS += src/comm/XbeeLinkInterface.h \
src/comm/XbeeLink.h \ src/comm/XbeeLink.h \
src/comm/HexSpinBox.h \ src/comm/HexSpinBox.h \
src/ui/XbeeConfigurationWindow.h \ src/ui/XbeeConfigurationWindow.h \
src/comm/CallConv.h src/comm/CallConv.h
SOURCES += src/comm/XbeeLink.cpp \ SOURCES += src/comm/XbeeLink.cpp \
src/comm/HexSpinBox.cpp \ src/comm/HexSpinBox.cpp \
src/ui/XbeeConfigurationWindow.cpp src/ui/XbeeConfigurationWindow.cpp
DEFINES += XBEELINK DEFINES += XBEELINK
INCLUDEPATH += libs/thirdParty/libxbee INCLUDEPATH += libs/thirdParty/libxbee
# TO DO: build library when it does not exist already # TO DO: build library when it does not exist already
LIBS += -Llibs/thirdParty/libxbee/lib \ LIBS += -Llibs/thirdParty/libxbee/lib \
-llibxbee -llibxbee
} }
#win32-msvc2008|win32-msvc2010 {
message("Including support for 3DxWare for Windows system.")
SOURCES += libs/thirdParty/3DMouse/win/MouseParameters.cpp \
libs/thirdParty/3DMouse/win/Mouse3DInput.cpp \
src/input/Mouse6dofInput.cpp
HEADERS += libs/thirdParty/3DMouse/win/I3dMouseParams.h \
libs/thirdParty/3DMouse/win/MouseParameters.h \
libs/thirdParty/3DMouse/win/Mouse3DInput.h \
src/input/Mouse6dofInput.h
INCLUDEPATH += libs/thirdParty/3DMouse/win
DEFINES += MOUSE_ENABLED_WIN
#}
/**
* @file
* @brief 3dConnexion 3dMouse interface for QGroundControl
*
* @author Matthias Krebs <makrebs@student.ethz.ch>
*
*/
#include "Mouse6dofInput.h"
#include "UAS.h"
#include "UASManager.h"
Mouse6dofInput::Mouse6dofInput(Mouse3DInput* mouseInput) :
mouse3DMax(0.01), // TODO: check maximum value fot plugged device
uas(NULL),
done(false),
xValue(0.0),
yValue(0.0),
zValue(0.0),
aValue(0.0),
bValue(0.0),
cValue(0.0)
{
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
// Connect 3DxWare SDK MotionEvent
connect(mouseInput, SIGNAL(Move3d(std::vector<float>&)), this, SLOT(motion3DMouse(std::vector<float>&)));
// TODO: Connect button mapping
//connect(mouseInput, SIGNAL(On3dmouseKeyDown(int)), this, SLOT);
//connect(mouseInput, SIGNAL(On3dmouseKeyUp(int)), this, SLOT);
}
Mouse6dofInput::~Mouse6dofInput()
{
done = true;
}
void Mouse6dofInput::setActiveUAS(UASInterface* uas)
{
// Only connect / disconnect is the UAS is of a controllable UAS class
UAS* tmp = 0;
if (this->uas)
{
tmp = dynamic_cast<UAS*>(this->uas);
if(tmp)
{
disconnect(this, SIGNAL(mouse6dofChanged(double,double,double,double,double,double)), tmp, SLOT(setManual6DOFControlCommands(double,double,double,double,double,double)));
// Todo: disconnect button mapping
}
}
this->uas = uas;
tmp = dynamic_cast<UAS*>(this->uas);
if(tmp) {
connect(this, SIGNAL(mouse6dofChanged(double,double,double,double,double,double)), tmp, SLOT(setManual6DOFControlCommands(double,double,double,double,double,double)));
// Todo: disconnect button mapping
}
if (!isRunning())
{
start();
}
}
void Mouse6dofInput::init()
{
// Make sure active UAS is set
setActiveUAS(UASManager::instance()->getActiveUAS());
}
void Mouse6dofInput::run()
{
init();
forever
{
if (done)
{
done = false;
exit();
}
// Bound x value
if (xValue > 1.0) xValue = 1.0;
if (xValue < -1.0) xValue = -1.0;
// Bound x value
if (yValue > 1.0) yValue = 1.0;
if (yValue < -1.0) yValue = -1.0;
// Bound x value
if (zValue > 1.0) zValue = 1.0;
if (zValue < -1.0) zValue = -1.0;
// Bound x value
if (aValue > 1.0) aValue = 1.0;
if (aValue < -1.0) aValue = -1.0;
// Bound x value
if (bValue > 1.0) bValue = 1.0;
if (bValue < -1.0) bValue = -1.0;
// Bound x value
if (cValue > 1.0) cValue = 1.0;
if (cValue < -1.0) cValue = -1.0;
emit mouse6dofChanged(xValue, yValue, zValue, aValue, bValue, cValue);
// Sleep, update rate of 3d mouse is approx. 50 Hz (1000 ms / 50 = 20 ms)
QGC::SLEEP::msleep(20);
}
}
void Mouse6dofInput::motion3DMouse(std::vector<float> &motionData)
{
if (motionData.size() < 6) return;
xValue = (double)1.0e2f*motionData[ 1 ] / mouse3DMax;
yValue = (double)1.0e2f*motionData[ 0 ] / mouse3DMax;
zValue = (double)1.0e2f*motionData[ 2 ] / mouse3DMax;
aValue = (double)1.0e2f*motionData[ 4 ] / mouse3DMax;
bValue = (double)1.0e2f*motionData[ 3 ] / mouse3DMax;
cValue = (double)1.0e2f*motionData[ 5 ] / mouse3DMax;
qDebug() << "NEW 3D MOUSE VALUES -- X" << xValue << " -- Y" << yValue << " -- Z" << zValue << " -- A" << aValue << " -- B" << bValue << " -- C" << cValue;
}
/**
* @file
* @brief Definition of 3dConnexion 3dMouse interface for QGroundControl
*
* @author Matthias Krebs <makrebs@student.ethz.ch>
*
*/
#ifndef MOUSE6DOFINPUT_H
#define MOUSE6DOFINPUT_H
#include <QThread>
#include "Mouse3DInput.h"
#include "UASInterface.h"
class Mouse6dofInput : public QThread
{
Q_OBJECT
public:
Mouse6dofInput(Mouse3DInput* mouseInput);
~Mouse6dofInput();
void run();
const double mouse3DMax;
protected:
void init();
Mouse3DInput* mouse3D;
UASInterface* uas;
bool done;
double xValue;
double yValue;
double zValue;
double aValue;
double bValue;
double cValue;
signals:
/**
* @brief Input of the 3d mouse has changed
*
* @param x Input x direction, range [-1, 1]
* @param y Input y direction, range [-1, 1]
* @param z Input z direction, range [-1, 1]
* @param a Input x rotation, range [-1, 1]
* @param b Input y rotation, range [-1, 1]
* @param c Input z rotation, range [-1, 1]
*/
void mouse6dofChanged(double x, double y, double z, double a, double b, double c);
public slots:
void setActiveUAS(UASInterface* uas);
void motion3DMouse(std::vector<float> &motionData);
};
#endif // MOUSE6DOFINPUT_H
This source diff could not be displayed because it is too large. You can view the blob instead.
/*===================================================================== /*=====================================================================
QGroundControl Open Source Ground Control Station QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> (c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or the Free Software Foundation, either version 3 of the License, or
(at your option) any later version. (at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful, QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details. GNU General Public License for more details.
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>. along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/ ======================================================================*/
/** /**
* @file * @file
* @brief Definition of Unmanned Aerial Vehicle object * @brief Definition of Unmanned Aerial Vehicle object
* *
* @author Lorenz Meier <mavteam@student.ethz.ch> * @author Lorenz Meier <mavteam@student.ethz.ch>
* *
*/ */
#ifndef _UAS_H_ #ifndef _UAS_H_
#define _UAS_H_ #define _UAS_H_
#include "UASInterface.h" #include "UASInterface.h"
#include <MAVLinkProtocol.h> #include <MAVLinkProtocol.h>
#include <QVector3D> #include <QVector3D>
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
#include "QGCHilLink.h" #include "QGCHilLink.h"
#include "QGCFlightGearLink.h" #include "QGCFlightGearLink.h"
#include "QGCXPlaneLink.h" #include "QGCXPlaneLink.h"
/** /**
* @brief A generic MAVLINK-connected MAV/UAV * @brief A generic MAVLINK-connected MAV/UAV
* *
* This class represents one vehicle. It can be used like the real vehicle, e.g. a call to halt() * This class represents one vehicle. It can be used like the real vehicle, e.g. a call to halt()
* will automatically send the appropriate messages to the vehicle. The vehicle state will also be * will automatically send the appropriate messages to the vehicle. The vehicle state will also be
* automatically updated by the comm architecture, so when writing code to e.g. control the vehicle * automatically updated by the comm architecture, so when writing code to e.g. control the vehicle
* no knowledge of the communication infrastructure is needed. * no knowledge of the communication infrastructure is needed.
*/ */
class UAS : public UASInterface class UAS : public UASInterface
{ {
Q_OBJECT Q_OBJECT
public: public:
UAS(MAVLinkProtocol* protocol, int id = 0); UAS(MAVLinkProtocol* protocol, int id = 0);
~UAS(); ~UAS();
enum BatteryType enum BatteryType
{ {
NICD = 0, NICD = 0,
NIMH = 1, NIMH = 1,
LIION = 2, LIION = 2,
LIPOLY = 3, LIPOLY = 3,
LIFE = 4, LIFE = 4,
AGZN = 5 AGZN = 5
}; ///< The type of battery used }; ///< The type of battery used
static const int lipoFull = 4.2f; ///< 100% charged voltage static const int lipoFull = 4.2f; ///< 100% charged voltage
static const int lipoEmpty = 3.5f; ///< Discharged voltage static const int lipoEmpty = 3.5f; ///< Discharged voltage
/* MANAGEMENT */ /* MANAGEMENT */
/** @brief The name of the robot */ /** @brief The name of the robot */
QString getUASName(void) const; QString getUASName(void) const;
/** @brief Get short state */ /** @brief Get short state */
const QString& getShortState() const; const QString& getShortState() const;
/** @brief Get short mode */ /** @brief Get short mode */
const QString& getShortMode() const; const QString& getShortMode() const;
/** @brief Translate from mode id to text */ /** @brief Translate from mode id to text */
static QString getShortModeTextFor(int id); static QString getShortModeTextFor(int id);
/** @brief Translate from mode id to audio text */ /** @brief Translate from mode id to audio text */
static QString getAudioModeTextFor(int id); static QString getAudioModeTextFor(int id);
/** @brief Get the unique system id */ /** @brief Get the unique system id */
int getUASID() const; int getUASID() const;
/** @brief Get the airframe */ /** @brief Get the airframe */
int getAirframe() const int getAirframe() const
{ {
return airframe; return airframe;
} }
/** @brief Get the components */ /** @brief Get the components */
QMap<int, QString> getComponents(); QMap<int, QString> getComponents();
/** @brief The time interval the robot is switched on */ /** @brief The time interval the robot is switched on */
quint64 getUptime() const; quint64 getUptime() const;
/** @brief Get the status flag for the communication */ /** @brief Get the status flag for the communication */
int getCommunicationStatus() const; int getCommunicationStatus() const;
/** @brief Add one measurement and get low-passed voltage */ /** @brief Add one measurement and get low-passed voltage */
float filterVoltage(float value) const; float filterVoltage(float value) const;
/** @brief Get the links associated with this robot */ /** @brief Get the links associated with this robot */
QList<LinkInterface*>* getLinks(); QList<LinkInterface*>* getLinks();
double getLocalX() const double getLocalX() const
{ {
return localX; return localX;
} }
double getLocalY() const double getLocalY() const
{ {
return localY; return localY;
} }
double getLocalZ() const double getLocalZ() const
{ {
return localZ; return localZ;
} }
double getLatitude() const double getLatitude() const
{ {
return latitude; return latitude;
} }
double getLongitude() const double getLongitude() const
{ {
return longitude; return longitude;
} }
double getAltitude() const double getAltitude() const
{ {
return altitude; return altitude;
} }
virtual bool localPositionKnown() const virtual bool localPositionKnown() const
{ {
return isLocalPositionKnown; return isLocalPositionKnown;
} }
virtual bool globalPositionKnown() const virtual bool globalPositionKnown() const
{ {
return isGlobalPositionKnown; return isGlobalPositionKnown;
} }
double getRoll() const double getRoll() const
{ {
return roll; return roll;
} }
double getPitch() const double getPitch() const
{ {
return pitch; return pitch;
} }
double getYaw() const double getYaw() const
{ {
return yaw; return yaw;
} }
bool getSelected() const; bool getSelected() const;
QVector3D getNedPosGlobalOffset() const QVector3D getNedPosGlobalOffset() const
{ {
return nedPosGlobalOffset; return nedPosGlobalOffset;
} }
QVector3D getNedAttGlobalOffset() const QVector3D getNedAttGlobalOffset() const
{ {
return nedAttGlobalOffset; return nedAttGlobalOffset;
} }
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) #if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
px::GLOverlay getOverlay() px::GLOverlay getOverlay()
{ {
QMutexLocker locker(&overlayMutex); QMutexLocker locker(&overlayMutex);
return overlay; return overlay;
} }
px::GLOverlay getOverlay(qreal& receivedTimestamp) px::GLOverlay getOverlay(qreal& receivedTimestamp)
{ {
receivedTimestamp = receivedOverlayTimestamp; receivedTimestamp = receivedOverlayTimestamp;
QMutexLocker locker(&overlayMutex); QMutexLocker locker(&overlayMutex);
return overlay; return overlay;
} }
px::ObstacleList getObstacleList() { px::ObstacleList getObstacleList() {
QMutexLocker locker(&obstacleListMutex); QMutexLocker locker(&obstacleListMutex);
return obstacleList; return obstacleList;
} }
px::ObstacleList getObstacleList(qreal& receivedTimestamp) { px::ObstacleList getObstacleList(qreal& receivedTimestamp) {
receivedTimestamp = receivedObstacleListTimestamp; receivedTimestamp = receivedObstacleListTimestamp;
QMutexLocker locker(&obstacleListMutex); QMutexLocker locker(&obstacleListMutex);
return obstacleList; return obstacleList;
} }
px::Path getPath() { px::Path getPath() {
QMutexLocker locker(&pathMutex); QMutexLocker locker(&pathMutex);
return path; return path;
} }
px::Path getPath(qreal& receivedTimestamp) { px::Path getPath(qreal& receivedTimestamp) {
receivedTimestamp = receivedPathTimestamp; receivedTimestamp = receivedPathTimestamp;
QMutexLocker locker(&pathMutex); QMutexLocker locker(&pathMutex);
return path; return path;
} }
px::PointCloudXYZRGB getPointCloud() { px::PointCloudXYZRGB getPointCloud() {
QMutexLocker locker(&pointCloudMutex); QMutexLocker locker(&pointCloudMutex);
return pointCloud; return pointCloud;
} }
px::PointCloudXYZRGB getPointCloud(qreal& receivedTimestamp) { px::PointCloudXYZRGB getPointCloud(qreal& receivedTimestamp) {
receivedTimestamp = receivedPointCloudTimestamp; receivedTimestamp = receivedPointCloudTimestamp;
QMutexLocker locker(&pointCloudMutex); QMutexLocker locker(&pointCloudMutex);
return pointCloud; return pointCloud;
} }
px::RGBDImage getRGBDImage() { px::RGBDImage getRGBDImage() {
QMutexLocker locker(&rgbdImageMutex); QMutexLocker locker(&rgbdImageMutex);
return rgbdImage; return rgbdImage;
} }
px::RGBDImage getRGBDImage(qreal& receivedTimestamp) { px::RGBDImage getRGBDImage(qreal& receivedTimestamp) {
receivedTimestamp = receivedRGBDImageTimestamp; receivedTimestamp = receivedRGBDImageTimestamp;
QMutexLocker locker(&rgbdImageMutex); QMutexLocker locker(&rgbdImageMutex);
return rgbdImage; return rgbdImage;
} }
#endif #endif
friend class UASWaypointManager; friend class UASWaypointManager;
protected: //COMMENTS FOR TEST UNIT protected: //COMMENTS FOR TEST UNIT
int uasId; ///< Unique system ID int uasId; ///< Unique system ID
unsigned char type; ///< UAS type (from type enum) unsigned char type; ///< UAS type (from type enum)
quint64 startTime; ///< The time the UAS was switched on quint64 startTime; ///< The time the UAS was switched on
CommStatus commStatus; ///< Communication status CommStatus commStatus; ///< Communication status
QString name; ///< Human-friendly name of the vehicle, e.g. bravo 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 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<LinkInterface*>* links; ///< List of links this UAS can be reached by QList<LinkInterface*>* links; ///< List of links this UAS can be reached by
QList<int> unknownPackets; ///< Packet IDs which are unknown and have been received QList<int> unknownPackets; ///< Packet IDs which are unknown and have been received
MAVLinkProtocol* mavlink; ///< Reference to the MAVLink instance MAVLinkProtocol* mavlink; ///< Reference to the MAVLink instance
BatteryType batteryType; ///< The battery type BatteryType batteryType; ///< The battery type
int cells; ///< Number of cells int cells; ///< Number of cells
UASWaypointManager waypointManager; UASWaypointManager waypointManager;
QList<double> actuatorValues; QList<double> actuatorValues;
QList<QString> actuatorNames; QList<QString> actuatorNames;
QList<double> motorValues; QList<double> motorValues;
QList<QString> motorNames; QList<QString> motorNames;
QMap<int, QString> components; ///< IDs and names of all detected onboard components QMap<int, QString> components; ///< IDs and names of all detected onboard components
double thrustSum; ///< Sum of forward/up thrust of all thrust actuators, in Newtons double thrustSum; ///< Sum of forward/up thrust of all thrust actuators, in Newtons
double thrustMax; ///< Maximum forward/up thrust of this vehicle, in Newtons double thrustMax; ///< Maximum forward/up thrust of this vehicle, in Newtons
// Battery stats // Battery stats
float fullVoltage; ///< Voltage of the fully charged battery (100%) float fullVoltage; ///< Voltage of the fully charged battery (100%)
float emptyVoltage; ///< Voltage of the empty battery (0%) float emptyVoltage; ///< Voltage of the empty battery (0%)
float startVoltage; ///< Voltage at system start float startVoltage; ///< Voltage at system start
float tickVoltage; ///< Voltage where 0.1 V ticks are told float tickVoltage; ///< Voltage where 0.1 V ticks are told
float lastTickVoltageValue; ///< The last voltage where a tick was announced float lastTickVoltageValue; ///< The last voltage where a tick was announced
float tickLowpassVoltage; ///< Lowpass-filtered voltage for the tick announcement float tickLowpassVoltage; ///< Lowpass-filtered voltage for the tick announcement
float warnVoltage; ///< Voltage where QGC will start to warn about low battery float warnVoltage; ///< Voltage where QGC will start to warn about low battery
float warnLevelPercent; ///< Warning level, in percent float warnLevelPercent; ///< Warning level, in percent
double currentVoltage; ///< Voltage currently measured double currentVoltage; ///< Voltage currently measured
float lpVoltage; ///< Low-pass filtered voltage float lpVoltage; ///< Low-pass filtered voltage
bool batteryRemainingEstimateEnabled; ///< If the estimate is enabled, QGC will try to estimate the remaining battery life bool batteryRemainingEstimateEnabled; ///< If the estimate is enabled, QGC will try to estimate the remaining battery life
float chargeLevel; ///< Charge level of battery, in percent float chargeLevel; ///< Charge level of battery, in percent
int timeRemaining; ///< Remaining time calculated based on previous and current int timeRemaining; ///< Remaining time calculated based on previous and current
uint8_t mode; ///< The current mode of the MAV uint8_t mode; ///< The current mode of the MAV
uint32_t custom_mode; ///< The current mode of the MAV uint32_t custom_mode; ///< The current mode of the MAV
int status; ///< The current status of the MAV int status; ///< The current status of the MAV
uint32_t navMode; ///< The current navigation mode of the MAV uint32_t navMode; ///< The current navigation mode of the MAV
quint64 onboardTimeOffset; quint64 onboardTimeOffset;
bool controlRollManual; ///< status flag, true if roll is controlled manually bool controlRollManual; ///< status flag, true if roll is controlled manually
bool controlPitchManual; ///< status flag, true if pitch is controlled manually bool controlPitchManual; ///< status flag, true if pitch is controlled manually
bool controlYawManual; ///< status flag, true if yaw is controlled manually bool controlYawManual; ///< status flag, true if yaw is controlled manually
bool controlThrustManual; ///< status flag, true if thrust is controlled manually bool controlThrustManual; ///< status flag, true if thrust is controlled manually
double manualRollAngle; ///< Roll angle set by human pilot (radians) double manualRollAngle; ///< Roll angle set by human pilot (radians)
double manualPitchAngle; ///< Pitch angle set by human pilot (radians) double manualPitchAngle; ///< Pitch angle set by human pilot (radians)
double manualYawAngle; ///< Yaw angle set by human pilot (radians) double manualYawAngle; ///< Yaw angle set by human pilot (radians)
double manualThrust; ///< Thrust set by human pilot (radians) double manualThrust; ///< Thrust set by human pilot (radians)
float receiveDropRate; ///< Percentage of packets that were dropped on the MAV's receiving link (from GCS and other MAVs) float receiveDropRate; ///< Percentage of packets that were dropped on the MAV's receiving link (from GCS and other MAVs)
float sendDropRate; ///< Percentage of packets that were not received from the MAV by the GCS float sendDropRate; ///< Percentage of packets that were not received from the MAV by the GCS
bool lowBattAlarm; ///< Switch if battery is low bool lowBattAlarm; ///< Switch if battery is low
bool positionLock; ///< Status if position information is available or not bool positionLock; ///< Status if position information is available or not
double localX; double localX;
double localY; double localY;
double localZ; double localZ;
double latitude; double latitude;
double longitude; double longitude;
double altitude; double altitude;
double speedX; ///< True speed in X axis double speedX; ///< True speed in X axis
double speedY; ///< True speed in Y axis double speedY; ///< True speed in Y axis
double speedZ; ///< True speed in Z axis double speedZ; ///< True speed in Z axis
double roll; double roll;
double pitch; double pitch;
double yaw; double yaw;
quint64 lastHeartbeat; ///< Time of the last heartbeat message quint64 lastHeartbeat; ///< Time of the last heartbeat message
QTimer* statusTimeout; ///< Timer for various status timeouts QTimer* statusTimeout; ///< Timer for various status timeouts
int imageSize; ///< Image size being transmitted (bytes) int imageSize; ///< Image size being transmitted (bytes)
int imagePackets; ///< Number of data packets being sent for this image int imagePackets; ///< Number of data packets being sent for this image
int imagePacketsArrived; ///< Number of data packets recieved int imagePacketsArrived; ///< Number of data packets recieved
int imagePayload; ///< Payload size per transmitted packet (bytes). Standard is 254, and decreases when image resolution increases. int imagePayload; ///< Payload size per transmitted packet (bytes). Standard is 254, and decreases when image resolution increases.
int imageQuality; ///< Quality of the transmitted image (percentage) int imageQuality; ///< Quality of the transmitted image (percentage)
int imageType; ///< Type of the transmitted image (BMP, PNG, JPEG, RAW 8 bit, RAW 32 bit) int imageType; ///< Type of the transmitted image (BMP, PNG, JPEG, RAW 8 bit, RAW 32 bit)
int imageWidth; ///< Width of the image stream int imageWidth; ///< Width of the image stream
int imageHeight; ///< Width of the image stream int imageHeight; ///< Width of the image stream
QByteArray imageRecBuffer; ///< Buffer for the incoming bytestream QByteArray imageRecBuffer; ///< Buffer for the incoming bytestream
QImage image; ///< Image data of last completely transmitted image QImage image; ///< Image data of last completely transmitted image
quint64 imageStart; quint64 imageStart;
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) #if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
px::GLOverlay overlay; px::GLOverlay overlay;
QMutex overlayMutex; QMutex overlayMutex;
qreal receivedOverlayTimestamp; qreal receivedOverlayTimestamp;
px::ObstacleList obstacleList; px::ObstacleList obstacleList;
QMutex obstacleListMutex; QMutex obstacleListMutex;
qreal receivedObstacleListTimestamp; qreal receivedObstacleListTimestamp;
px::Path path; px::Path path;
QMutex pathMutex; QMutex pathMutex;
qreal receivedPathTimestamp; qreal receivedPathTimestamp;
px::PointCloudXYZRGB pointCloud; px::PointCloudXYZRGB pointCloud;
QMutex pointCloudMutex; QMutex pointCloudMutex;
qreal receivedPointCloudTimestamp; qreal receivedPointCloudTimestamp;
px::RGBDImage rgbdImage; px::RGBDImage rgbdImage;
QMutex rgbdImageMutex; QMutex rgbdImageMutex;
qreal receivedRGBDImageTimestamp; qreal receivedRGBDImageTimestamp;
#endif #endif
QMap<int, QMap<QString, QVariant>* > parameters; ///< All parameters QMap<int, QMap<QString, QVariant>* > parameters; ///< All parameters
bool paramsOnceRequested; ///< If the parameter list has been read at least once bool paramsOnceRequested; ///< If the parameter list has been read at least once
int airframe; ///< The airframe type int airframe; ///< The airframe type
bool attitudeKnown; ///< True if attitude was received, false else bool attitudeKnown; ///< True if attitude was received, false else
QGCUASParamManager* paramManager; ///< Parameter manager class QGCUASParamManager* paramManager; ///< Parameter manager class
QString shortStateText; ///< Short textual state description QString shortStateText; ///< Short textual state description
QString shortModeText; ///< Short textual mode description QString shortModeText; ///< Short textual mode description
bool attitudeStamped; ///< Should arriving data be timestamped with the last attitude? This helps with broken system time clocks on the MAV bool attitudeStamped; ///< Should arriving data be timestamped with the last attitude? This helps with broken system time clocks on the MAV
quint64 lastAttitude; ///< Timestamp of last attitude measurement quint64 lastAttitude; ///< Timestamp of last attitude measurement
QGCHilLink* simulation; ///< Hardware in the loop simulation link QGCHilLink* simulation; ///< Hardware in the loop simulation link
bool isLocalPositionKnown; ///< If the local position has been received for this MAV bool isLocalPositionKnown; ///< If the local position has been received for this MAV
bool isGlobalPositionKnown; ///< If the global position has been received for this MAV bool isGlobalPositionKnown; ///< If the global position has been received for this MAV
bool systemIsArmed; ///< If the system is armed bool systemIsArmed; ///< If the system is armed
QVector3D nedPosGlobalOffset; ///< Offset between the system's NED position measurements and the swarm / global 0/0/0 origin QVector3D nedPosGlobalOffset; ///< Offset between the system's NED position measurements and the swarm / global 0/0/0 origin
QVector3D nedAttGlobalOffset; ///< Offset between the system's NED position measurements and the swarm / global 0/0/0 origin QVector3D nedAttGlobalOffset; ///< Offset between the system's NED position measurements and the swarm / global 0/0/0 origin
public: public:
/** @brief Set the current battery type */ /** @brief Set the current battery type */
void setBattery(BatteryType type, int cells); void setBattery(BatteryType type, int cells);
/** @brief Estimate how much flight time is remaining */ /** @brief Estimate how much flight time is remaining */
int calculateTimeRemaining(); int calculateTimeRemaining();
/** @brief Get the current charge level */ /** @brief Get the current charge level */
float getChargeLevel(); float getChargeLevel();
/** @brief Get the human-readable status message for this code */ /** @brief Get the human-readable status message for this code */
void getStatusForCode(int statusCode, QString& uasState, QString& stateDescription); void getStatusForCode(int statusCode, QString& uasState, QString& stateDescription);
/** @brief Get the human-readable navigation mode translation for this mode */ /** @brief Get the human-readable navigation mode translation for this mode */
QString getNavModeText(int mode); QString getNavModeText(int mode);
/** @brief Check if vehicle is in autonomous mode */ /** @brief Check if vehicle is in autonomous mode */
bool isAuto(); bool isAuto();
/** @brief Check if vehicle is armed */ /** @brief Check if vehicle is armed */
bool isArmed() const { return systemIsArmed; } bool isArmed() const { return systemIsArmed; }
UASWaypointManager* getWaypointManager() { UASWaypointManager* getWaypointManager() {
return &waypointManager; return &waypointManager;
} }
/** @brief Get reference to the param manager **/ /** @brief Get reference to the param manager **/
QGCUASParamManager* getParamManager() const { QGCUASParamManager* getParamManager() const {
return paramManager; return paramManager;
} }
/** @brief Get the HIL simulation */ /** @brief Get the HIL simulation */
QGCHilLink* getHILSimulation() const { QGCHilLink* getHILSimulation() const {
return simulation; return simulation;
} }
// TODO Will be removed // TODO Will be removed
/** @brief Set reference to the param manager **/ /** @brief Set reference to the param manager **/
void setParamManager(QGCUASParamManager* manager) { void setParamManager(QGCUASParamManager* manager) {
paramManager = manager; paramManager = manager;
} }
int getSystemType(); int getSystemType();
QString getSystemTypeName() QString getSystemTypeName()
{ {
switch(type) switch(type)
{ {
case MAV_TYPE_GENERIC: case MAV_TYPE_GENERIC:
return "GENERIC"; return "GENERIC";
break; break;
case MAV_TYPE_FIXED_WING: case MAV_TYPE_FIXED_WING:
return "FIXED_WING"; return "FIXED_WING";
break; break;
case MAV_TYPE_QUADROTOR: case MAV_TYPE_QUADROTOR:
return "QUADROTOR"; return "QUADROTOR";
break; break;
case MAV_TYPE_COAXIAL: case MAV_TYPE_COAXIAL:
return "COAXIAL"; return "COAXIAL";
break; break;
case MAV_TYPE_HELICOPTER: case MAV_TYPE_HELICOPTER:
return "HELICOPTER"; return "HELICOPTER";
break; break;
case MAV_TYPE_ANTENNA_TRACKER: case MAV_TYPE_ANTENNA_TRACKER:
return "ANTENNA_TRACKER"; return "ANTENNA_TRACKER";
break; break;
case MAV_TYPE_GCS: case MAV_TYPE_GCS:
return "GCS"; return "GCS";
break; break;
case MAV_TYPE_AIRSHIP: case MAV_TYPE_AIRSHIP:
return "AIRSHIP"; return "AIRSHIP";
break; break;
case MAV_TYPE_FREE_BALLOON: case MAV_TYPE_FREE_BALLOON:
return "FREE_BALLOON"; return "FREE_BALLOON";
break; break;
case MAV_TYPE_ROCKET: case MAV_TYPE_ROCKET:
return "ROCKET"; return "ROCKET";
break; break;
case MAV_TYPE_GROUND_ROVER: case MAV_TYPE_GROUND_ROVER:
return "GROUND_ROVER"; return "GROUND_ROVER";
break; break;
case MAV_TYPE_SURFACE_BOAT: case MAV_TYPE_SURFACE_BOAT:
return "BOAT"; return "BOAT";
break; break;
case MAV_TYPE_SUBMARINE: case MAV_TYPE_SUBMARINE:
return "SUBMARINE"; return "SUBMARINE";
break; break;
case MAV_TYPE_HEXAROTOR: case MAV_TYPE_HEXAROTOR:
return "HEXAROTOR"; return "HEXAROTOR";
break; break;
case MAV_TYPE_OCTOROTOR: case MAV_TYPE_OCTOROTOR:
return "OCTOROTOR"; return "OCTOROTOR";
break; break;
case MAV_TYPE_TRICOPTER: case MAV_TYPE_TRICOPTER:
return "TRICOPTER"; return "TRICOPTER";
break; break;
case MAV_TYPE_FLAPPING_WING: case MAV_TYPE_FLAPPING_WING:
return "FLAPPING_WING"; return "FLAPPING_WING";
break; break;
default: default:
return ""; return "";
break; break;
} }
} }
QImage getImage(); QImage getImage();
void requestImage(); void requestImage();
int getAutopilotType(){ int getAutopilotType(){
return autopilot; return autopilot;
} }
QString getAutopilotTypeName() QString getAutopilotTypeName()
{ {
switch (autopilot) switch (autopilot)
{ {
case MAV_AUTOPILOT_GENERIC: case MAV_AUTOPILOT_GENERIC:
return "GENERIC"; return "GENERIC";
break; break;
case MAV_AUTOPILOT_PIXHAWK: case MAV_AUTOPILOT_PIXHAWK:
return "PIXHAWK"; return "PIXHAWK";
break; break;
case MAV_AUTOPILOT_SLUGS: case MAV_AUTOPILOT_SLUGS:
return "SLUGS"; return "SLUGS";
break; break;
case MAV_AUTOPILOT_ARDUPILOTMEGA: case MAV_AUTOPILOT_ARDUPILOTMEGA:
return "ARDUPILOTMEGA"; return "ARDUPILOTMEGA";
break; break;
case MAV_AUTOPILOT_OPENPILOT: case MAV_AUTOPILOT_OPENPILOT:
return "OPENPILOT"; return "OPENPILOT";
break; break;
case MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY: case MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY:
return "GENERIC_WAYPOINTS_ONLY"; return "GENERIC_WAYPOINTS_ONLY";
break; break;
case MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY: case MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY:
return "GENERIC_MISSION_NAVIGATION_ONLY"; return "GENERIC_MISSION_NAVIGATION_ONLY";
break; break;
case MAV_AUTOPILOT_GENERIC_MISSION_FULL: case MAV_AUTOPILOT_GENERIC_MISSION_FULL:
return "GENERIC_MISSION_FULL"; return "GENERIC_MISSION_FULL";
break; break;
case MAV_AUTOPILOT_INVALID: case MAV_AUTOPILOT_INVALID:
return "NO AP"; return "NO AP";
break; break;
case MAV_AUTOPILOT_PPZ: case MAV_AUTOPILOT_PPZ:
return "PPZ"; return "PPZ";
break; break;
case MAV_AUTOPILOT_UDB: case MAV_AUTOPILOT_UDB:
return "UDB"; return "UDB";
break; break;
case MAV_AUTOPILOT_FP: case MAV_AUTOPILOT_FP:
return "FP"; return "FP";
break; break;
case MAV_AUTOPILOT_PX4: case MAV_AUTOPILOT_PX4:
return "PX4"; return "PX4";
break; break;
default: default:
return ""; return "";
break; break;
} }
} }
public slots: public slots:
/** @brief Set the autopilot type */ /** @brief Set the autopilot type */
void setAutopilotType(int apType) void setAutopilotType(int apType)
{ {
autopilot = apType; autopilot = apType;
emit systemSpecsChanged(uasId); emit systemSpecsChanged(uasId);
} }
/** @brief Set the type of airframe */ /** @brief Set the type of airframe */
void setSystemType(int systemType); void setSystemType(int systemType);
/** @brief Set the specific airframe type */ /** @brief Set the specific airframe type */
void setAirframe(int airframe) void setAirframe(int airframe)
{ {
if((airframe >= QGC_AIRFRAME_GENERIC) && (airframe < QGC_AIRFRAME_END_OF_ENUM)) if((airframe >= QGC_AIRFRAME_GENERIC) && (airframe < QGC_AIRFRAME_END_OF_ENUM))
{ {
this->airframe = airframe; this->airframe = airframe;
emit systemSpecsChanged(uasId); emit systemSpecsChanged(uasId);
} }
} }
/** @brief Set a new name **/ /** @brief Set a new name **/
void setUASName(const QString& name); void setUASName(const QString& name);
/** @brief Executes a command **/ /** @brief Executes a command **/
void executeCommand(MAV_CMD command); void executeCommand(MAV_CMD command);
/** @brief Executes a command with 7 params */ /** @brief Executes a command with 7 params */
void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component); void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component);
/** @brief Set the current battery type and voltages */ /** @brief Set the current battery type and voltages */
void setBatterySpecs(const QString& specs); void setBatterySpecs(const QString& specs);
/** @brief Get the current battery type and specs */ /** @brief Get the current battery type and specs */
QString getBatterySpecs(); QString getBatterySpecs();
/** @brief Launches the system **/ /** @brief Launches the system **/
void launch(); void launch();
/** @brief Write this waypoint to the list of waypoints */ /** @brief Write this waypoint to the list of waypoints */
//void setWaypoint(Waypoint* wp); FIXME tbd //void setWaypoint(Waypoint* wp); FIXME tbd
/** @brief Set currently active waypoint */ /** @brief Set currently active waypoint */
//void setWaypointActive(int id); FIXME tbd //void setWaypointActive(int id); FIXME tbd
/** @brief Order the robot to return home **/ /** @brief Order the robot to return home **/
void home(); void home();
/** @brief Order the robot to land **/ /** @brief Order the robot to land **/
void land(); void land();
void halt(); void halt();
void go(); void go();
/** @brief Enable / disable HIL */ /** @brief Enable / disable HIL */
void enableHilFlightGear(bool enable, QString options); void enableHilFlightGear(bool enable, QString options);
void enableHilXPlane(bool enable); void enableHilXPlane(bool enable);
/** @brief Send the full HIL state to the MAV */ /** @brief Send the full HIL state to the MAV */
void sendHilState( uint64_t time_us, float roll, float pitch, float yaw, float rollspeed, void sendHilState( uint64_t time_us, float roll, float pitch, float yaw, float rollspeed,
float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt,
int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc); int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc);
/** @brief Places the UAV in Hardware-in-the-Loop simulation status **/ /** @brief Places the UAV in Hardware-in-the-Loop simulation status **/
void startHil(); void startHil();
/** @brief Stops the UAV's Hardware-in-the-Loop simulation status **/ /** @brief Stops the UAV's Hardware-in-the-Loop simulation status **/
void stopHil(); void stopHil();
/** @brief Stops the robot system. If it is an MAV, the robot starts the emergency landing procedure **/ /** @brief Stops the robot system. If it is an MAV, the robot starts the emergency landing procedure **/
void emergencySTOP(); void emergencySTOP();
/** @brief Kills the robot. All systems are immediately shut down (e.g. the main power line is cut). This might lead to a crash **/ /** @brief Kills the robot. All systems are immediately shut down (e.g. the main power line is cut). This might lead to a crash **/
bool emergencyKILL(); bool emergencyKILL();
/** @brief Shut the system cleanly down. Will shut down any onboard computers **/ /** @brief Shut the system cleanly down. Will shut down any onboard computers **/
void shutdown(); void shutdown();
/** @brief Set the target position for the robot to navigate to. */ /** @brief Set the target position for the robot to navigate to. */
void setTargetPosition(float x, float y, float z, float yaw); void setTargetPosition(float x, float y, float z, float yaw);
void startLowBattAlarm(); void startLowBattAlarm();
void stopLowBattAlarm(); void stopLowBattAlarm();
/** @brief Arm system */ /** @brief Arm system */
void armSystem(); void armSystem();
/** @brief Disable the motors */ /** @brief Disable the motors */
void disarmSystem(); void disarmSystem();
/** @brief Set the values for the manual control of the vehicle */ /** @brief Set the values for the manual control of the vehicle */
void setManualControlCommands(double roll, double pitch, double yaw, double thrust, int xHat, int yHat, int buttons); void setManualControlCommands(double roll, double pitch, double yaw, double thrust, int xHat, int yHat, int buttons);
/** @brief Receive a button pressed event from an input device, e.g. joystick */ /** @brief Receive a button pressed event from an input device, e.g. joystick */
void receiveButton(int buttonIndex); void receiveButton(int buttonIndex);
/** @brief Add a link associated with this robot */ /** @brief Set the values for the 6dof manual control of the vehicle */
void addLink(LinkInterface* link); void setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw);
/** @brief Remove a link associated with this robot */
void removeLink(QObject* object); /** @brief Add a link associated with this robot */
void addLink(LinkInterface* link);
/** @brief Receive a message from one of the communication links. */ /** @brief Remove a link associated with this robot */
virtual void receiveMessage(LinkInterface* link, mavlink_message_t message); void removeLink(QObject* object);
#ifdef QGC_PROTOBUF_ENABLED /** @brief Receive a message from one of the communication links. */
/** @brief Receive a message from one of the communication links. */ virtual void receiveMessage(LinkInterface* link, mavlink_message_t message);
virtual void receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<google::protobuf::Message> message);
#endif #ifdef QGC_PROTOBUF_ENABLED
/** @brief Receive a message from one of the communication links. */
/** @brief Send a message over this link (to this or to all UAS on this link) */ virtual void receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<google::protobuf::Message> message);
void sendMessage(LinkInterface* link, mavlink_message_t message); #endif
/** @brief Send a message over all links this UAS can be reached with (!= all links) */
void sendMessage(mavlink_message_t message); /** @brief Send a message over this link (to this or to all UAS on this link) */
void sendMessage(LinkInterface* link, 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 */ /** @brief Send a message over all links this UAS can be reached with (!= all links) */
void forwardMessage(mavlink_message_t message); void sendMessage(mavlink_message_t message);
/** @brief Set this UAS as the system currently in focus, e.g. in the main display widgets */ /** @brief Temporary Hack for sending packets to patch Antenna. Send a message over all serial links except for this UAS's */
void setSelected(); void forwardMessage(mavlink_message_t message);
/** @brief Set current mode of operation, e.g. auto or manual */ /** @brief Set this UAS as the system currently in focus, e.g. in the main display widgets */
void setMode(int mode); void setSelected();
/** @brief Request all parameters */ /** @brief Set current mode of operation, e.g. auto or manual */
void requestParameters(); void setMode(int mode);
/** @brief Request a single parameter by name */ /** @brief Request all parameters */
void requestParameter(int component, const QString& parameter); void requestParameters();
/** @brief Request a single parameter by index */
void requestParameter(int component, int id); /** @brief Request a single parameter by name */
void requestParameter(int component, const QString& parameter);
/** @brief Set a system parameter */ /** @brief Request a single parameter by index */
void setParameter(const int component, const QString& id, const QVariant& value); void requestParameter(int component, int id);
/** @brief Write parameters to permanent storage */ /** @brief Set a system parameter */
void writeParametersToStorage(); void setParameter(const int component, const QString& id, const QVariant& value);
/** @brief Read parameters from permanent storage */
void readParametersFromStorage(); /** @brief Write parameters to permanent storage */
void writeParametersToStorage();
/** @brief Get the names of all parameters */ /** @brief Read parameters from permanent storage */
QList<QString> getParameterNames(int component); void readParametersFromStorage();
/** @brief Get the ids of all components */ /** @brief Get the names of all parameters */
QList<int> getComponentIds(); QList<QString> getParameterNames(int component);
void enableAllDataTransmission(int rate); /** @brief Get the ids of all components */
void enableRawSensorDataTransmission(int rate); QList<int> getComponentIds();
void enableExtendedSystemStatusTransmission(int rate);
void enableRCChannelDataTransmission(int rate); void enableAllDataTransmission(int rate);
void enableRawControllerDataTransmission(int rate); void enableRawSensorDataTransmission(int rate);
//void enableRawSensorFusionTransmission(int rate); void enableExtendedSystemStatusTransmission(int rate);
void enablePositionTransmission(int rate); void enableRCChannelDataTransmission(int rate);
void enableExtra1Transmission(int rate); void enableRawControllerDataTransmission(int rate);
void enableExtra2Transmission(int rate); //void enableRawSensorFusionTransmission(int rate);
void enableExtra3Transmission(int rate); void enablePositionTransmission(int rate);
void enableExtra1Transmission(int rate);
/** @brief Update the system state */ void enableExtra2Transmission(int rate);
void updateState(); void enableExtra3Transmission(int rate);
/** @brief Set world frame origin at current GPS position */ /** @brief Update the system state */
void setLocalOriginAtCurrentGPSPosition(); void updateState();
/** @brief Set world frame origin / home position at this GPS position */
void setHomePosition(double lat, double lon, double alt); /** @brief Set world frame origin at current GPS position */
/** @brief Set local position setpoint */ void setLocalOriginAtCurrentGPSPosition();
void setLocalPositionSetpoint(float x, float y, float z, float yaw); /** @brief Set world frame origin / home position at this GPS position */
/** @brief Add an offset in body frame to the setpoint */ void setHomePosition(double lat, double lon, double alt);
void setLocalPositionOffset(float x, float y, float z, float yaw); /** @brief Set local position setpoint */
void setLocalPositionSetpoint(float x, float y, float z, float yaw);
void startRadioControlCalibration(); /** @brief Add an offset in body frame to the setpoint */
void startMagnetometerCalibration(); void setLocalPositionOffset(float x, float y, float z, float yaw);
void startGyroscopeCalibration();
void startPressureCalibration(); void startRadioControlCalibration();
void startMagnetometerCalibration();
void startDataRecording(); void startGyroscopeCalibration();
void stopDataRecording(); void startPressureCalibration();
void deleteSettings();
signals: void startDataRecording();
/** @brief The main/battery voltage has changed/was updated */ void stopDataRecording();
//void voltageChanged(int uasId, double voltage); // Defined in UASInterface already void deleteSettings();
/** @brief An actuator value has changed */ signals:
//void actuatorChanged(UASInterface*, int actId, double value); // Defined in UASInterface already /** @brief The main/battery voltage has changed/was updated */
/** @brief An actuator value has changed */ //void voltageChanged(int uasId, double voltage); // Defined in UASInterface already
void actuatorChanged(UASInterface* uas, QString actuatorName, double min, double max, double value); /** @brief An actuator value has changed */
void motorChanged(UASInterface* uas, QString motorName, double min, double max, double value); //void actuatorChanged(UASInterface*, int actId, double value); // Defined in UASInterface already
/** @brief The system load (MCU/CPU usage) changed */ /** @brief An actuator value has changed */
void loadChanged(UASInterface* uas, double load); void actuatorChanged(UASInterface* uas, QString actuatorName, double min, double max, double value);
/** @brief Propagate a heartbeat received from the system */ void motorChanged(UASInterface* uas, QString motorName, double min, double max, double value);
//void heartbeat(UASInterface* uas); // Defined in UASInterface already /** @brief The system load (MCU/CPU usage) changed */
void imageStarted(quint64 timestamp); void loadChanged(UASInterface* uas, double load);
/** @brief A new camera image has arrived */ /** @brief Propagate a heartbeat received from the system */
void imageReady(UASInterface* uas); //void heartbeat(UASInterface* uas); // Defined in UASInterface already
/** @brief HIL controls have changed */ void imageStarted(quint64 timestamp);
void hilControlsChanged(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode); /** @brief A new camera image has arrived */
/** @brief HIL actuator outputs have changed */ void imageReady(UASInterface* uas);
void hilActuatorsChanged(uint64_t time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8); /** @brief HIL controls have changed */
void hilControlsChanged(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode);
protected: /** @brief HIL actuator outputs have changed */
/** @brief Get the UNIX timestamp in milliseconds, enter microseconds */ void hilActuatorsChanged(uint64_t time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8);
quint64 getUnixTime(quint64 time=0);
/** @brief Get the UNIX timestamp in milliseconds, enter milliseconds */ protected:
quint64 getUnixTimeFromMs(quint64 time); /** @brief Get the UNIX timestamp in milliseconds, enter microseconds */
/** @brief Get the UNIX timestamp in milliseconds, ignore attitudeStamped mode */ quint64 getUnixTime(quint64 time=0);
quint64 getUnixReferenceTime(quint64 time); /** @brief Get the UNIX timestamp in milliseconds, enter milliseconds */
int componentID[256]; quint64 getUnixTimeFromMs(quint64 time);
bool componentMulti[256]; /** @brief Get the UNIX timestamp in milliseconds, ignore attitudeStamped mode */
bool connectionLost; ///< Flag indicates a timed out connection quint64 getUnixReferenceTime(quint64 time);
quint64 connectionLossTime; ///< Time the connection was interrupted int componentID[256];
quint64 lastVoltageWarning; ///< Time at which the last voltage warning occured bool componentMulti[256];
quint64 lastNonNullTime; ///< The last timestamp from the MAV that was not null bool connectionLost; ///< Flag indicates a timed out connection
unsigned int onboardTimeOffsetInvalidCount; ///< Count when the offboard time offset estimation seemed wrong quint64 connectionLossTime; ///< Time the connection was interrupted
bool hilEnabled; ///< Set to true if HIL mode is enabled from GCS (UAS might be in HIL even if this flag is not set, this defines the GCS HIL setting) quint64 lastVoltageWarning; ///< Time at which the last voltage warning occured
quint64 lastNonNullTime; ///< The last timestamp from the MAV that was not null
protected slots: unsigned int onboardTimeOffsetInvalidCount; ///< Count when the offboard time offset estimation seemed wrong
/** @brief Write settings to disk */ bool hilEnabled; ///< Set to true if HIL mode is enabled from GCS (UAS might be in HIL even if this flag is not set, this defines the GCS HIL setting)
void writeSettings();
/** @brief Read settings from disk */ protected slots:
void readSettings(); /** @brief Write settings to disk */
void writeSettings();
// // MESSAGE RECEPTION /** @brief Read settings from disk */
// /** @brief Receive a named value message */ void readSettings();
// void receiveMessageNamedValue(const mavlink_message_t& message);
// // MESSAGE RECEPTION
private: // /** @brief Receive a named value message */
// unsigned int mode; ///< The current mode of the MAV // void receiveMessageNamedValue(const mavlink_message_t& message);
};
private:
// unsigned int mode; ///< The current mode of the MAV
#endif // _UAS_H_ };
#endif // _UAS_H_
This source diff could not be displayed because it is too large. You can view the blob instead.
/*===================================================================== /*=====================================================================
QGroundControl Open Source Ground Control Station QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> (c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or the Free Software Foundation, either version 3 of the License, or
(at your option) any later version. (at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful, QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details. GNU General Public License for more details.
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>. along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/ ======================================================================*/
/** /**
* @file * @file
* @brief Definition of class MainWindow * @brief Definition of class MainWindow
* @author Lorenz Meier <mavteam@student.ethz.ch> * @author Lorenz Meier <mavteam@student.ethz.ch>
* *
*/ */
#ifndef _MAINWINDOW_H_ #ifndef _MAINWINDOW_H_
#define _MAINWINDOW_H_ #define _MAINWINDOW_H_
#include <QtGui/QMainWindow> #include <QtGui/QMainWindow>
#include <QStatusBar> #include <QStatusBar>
#include <QStackedWidget> #include <QStackedWidget>
#include <QSettings> #include <QSettings>
#include <qlist.h> #include <qlist.h>
#include "ui_MainWindow.h" #include "ui_MainWindow.h"
#include "LinkManager.h" #include "LinkManager.h"
#include "LinkInterface.h" #include "LinkInterface.h"
#include "UASInterface.h" #include "UASInterface.h"
#include "UASManager.h" #include "UASManager.h"
#include "UASControlWidget.h" #include "UASControlWidget.h"
#include "Linecharts.h" #include "Linecharts.h"
#include "UASInfoWidget.h" #include "UASInfoWidget.h"
#include "WaypointList.h" #include "WaypointList.h"
#include "CameraView.h" #include "CameraView.h"
#include "UASListWidget.h" #include "UASListWidget.h"
#include "MAVLinkProtocol.h" #include "MAVLinkProtocol.h"
#include "MAVLinkSimulationLink.h" #include "MAVLinkSimulationLink.h"
#include "ObjectDetectionView.h" #include "ObjectDetectionView.h"
#include "HUD.h" #include "HUD.h"
#include "JoystickWidget.h" #include "JoystickWidget.h"
#include "input/JoystickInput.h" #include "input/JoystickInput.h"
#include "DebugConsole.h" #include "input/Mouse6dofInput.h"
#include "ParameterInterface.h" #include "DebugConsole.h"
#include "XMLCommProtocolWidget.h" #include "ParameterInterface.h"
#include "HDDisplay.h" #include "XMLCommProtocolWidget.h"
#include "WatchdogControl.h" #include "HDDisplay.h"
#include "HSIDisplay.h" #include "WatchdogControl.h"
#include "QGCDataPlot2D.h" #include "HSIDisplay.h"
#include "QGCRemoteControlView.h" #include "QGCDataPlot2D.h"
#include "opmapcontrol.h" #include "QGCRemoteControlView.h"
#if (defined Q_OS_MAC) | (defined _MSC_VER) #include "opmapcontrol.h"
#include "QGCGoogleEarthView.h" #if (defined Q_OS_MAC) | (defined _MSC_VER)
#endif #include "QGCGoogleEarthView.h"
#include "QGCToolBar.h" #endif
#include "SlugsDataSensorView.h" #include "QGCToolBar.h"
#include "LogCompressor.h" #include "SlugsDataSensorView.h"
#include "LogCompressor.h"
#include "SlugsHilSim.h"
#include "SlugsHilSim.h"
#include "SlugsPadCameraControl.h"
#include "UASControlParameters.h" #include "SlugsPadCameraControl.h"
#include "QGCMAVLinkInspector.h" #include "UASControlParameters.h"
#include "QGCMAVLinkLogPlayer.h" #include "QGCMAVLinkInspector.h"
#include "QGCVehicleConfig.h" #include "QGCMAVLinkLogPlayer.h"
#include "MAVLinkDecoder.h" #include "QGCVehicleConfig.h"
#include "MAVLinkDecoder.h"
class QGCMapTool;
class QGCMAVLinkMessageSender; class QGCMapTool;
class QGCFirmwareUpdate; class QGCMAVLinkMessageSender;
class QSplashScreen; class QGCFirmwareUpdate;
class QSplashScreen;
/**
* @brief Main Application Window /**
* * @brief Main Application Window
**/ *
class MainWindow : public QMainWindow **/
{ class MainWindow : public QMainWindow
Q_OBJECT {
Q_OBJECT
public:
static MainWindow* instance(QSplashScreen* screen = 0); public:
~MainWindow(); static MainWindow* instance(QSplashScreen* screen = 0);
~MainWindow();
enum QGC_MAINWINDOW_STYLE
{ enum QGC_MAINWINDOW_STYLE
QGC_MAINWINDOW_STYLE_NATIVE, {
QGC_MAINWINDOW_STYLE_INDOOR, QGC_MAINWINDOW_STYLE_NATIVE,
QGC_MAINWINDOW_STYLE_OUTDOOR QGC_MAINWINDOW_STYLE_INDOOR,
}; QGC_MAINWINDOW_STYLE_OUTDOOR
};
/** @brief Get current visual style */
int getStyle() /** @brief Get current visual style */
{ int getStyle()
return currentStyle; {
} return currentStyle;
/** @brief Get auto link reconnect setting */ }
bool autoReconnectEnabled() /** @brief Get auto link reconnect setting */
{ bool autoReconnectEnabled()
return autoReconnect; {
} return autoReconnect;
}
/** @brief Get low power mode setting */
bool lowPowerModeEnabled() /** @brief Get low power mode setting */
{ bool lowPowerModeEnabled()
return lowPowerMode; {
} return lowPowerMode;
}
QList<QAction*> listLinkMenuActions(void);
QList<QAction*> listLinkMenuActions(void);
public slots:
public slots:
/** @brief Shows a status message on the bottom status bar */
void showStatusMessage(const QString& status, int timeout); /** @brief Shows a status message on the bottom status bar */
/** @brief Shows a status message on the bottom status bar */ void showStatusMessage(const QString& status, int timeout);
void showStatusMessage(const QString& status); /** @brief Shows a status message on the bottom status bar */
/** @brief Shows a critical message as popup or as widget */ void showStatusMessage(const QString& status);
void showCriticalMessage(const QString& title, const QString& message); /** @brief Shows a critical message as popup or as widget */
/** @brief Shows an info message as popup or as widget */ void showCriticalMessage(const QString& title, const QString& message);
void showInfoMessage(const QString& title, const QString& message); /** @brief Shows an info message as popup or as widget */
void showInfoMessage(const QString& title, const QString& message);
/** @brief Show the application settings */
void showSettings(); /** @brief Show the application settings */
/** @brief Add a communication link */ void showSettings();
void addLink(); /** @brief Add a communication link */
void addLink(LinkInterface* link); void addLink();
void configure(); void addLink(LinkInterface* link);
/** @brief Set the currently controlled UAS */ void configure();
void setActiveUAS(UASInterface* uas); /** @brief Set the currently controlled UAS */
void setActiveUAS(UASInterface* uas);
/** @brief Add a new UAS */
void UASCreated(UASInterface* uas); /** @brief Add a new UAS */
/** Delete an UAS */ void UASCreated(UASInterface* uas);
void UASDeleted(UASInterface* uas); /** Delete an UAS */
/** @brief Update system specs of a UAS */ void UASDeleted(UASInterface* uas);
void UASSpecsChanged(int uas); /** @brief Update system specs of a UAS */
void startVideoCapture(); void UASSpecsChanged(int uas);
void stopVideoCapture(); void startVideoCapture();
void saveScreen(); void stopVideoCapture();
void saveScreen();
/** @brief Load default view when no MAV is connected */
void loadUnconnectedView(); /** @brief Load default view when no MAV is connected */
/** @brief Load view for pilot */ void loadUnconnectedView();
void loadPilotView(); /** @brief Load view for pilot */
/** @brief Load view for engineer */ void loadPilotView();
void loadEngineerView(); /** @brief Load view for engineer */
/** @brief Load view for operator */ void loadEngineerView();
void loadOperatorView(); /** @brief Load view for operator */
/** @brief Load MAVLink XML generator view */ void loadOperatorView();
void loadMAVLinkView(); /** @brief Load MAVLink XML generator view */
/** @brief Load firmware update view */ void loadMAVLinkView();
void loadFirmwareUpdateView(); /** @brief Load firmware update view */
void loadFirmwareUpdateView();
/** @brief Show the online help for users */
void showHelp(); /** @brief Show the online help for users */
/** @brief Show the authors / credits */ void showHelp();
void showCredits(); /** @brief Show the authors / credits */
/** @brief Show the project roadmap */ void showCredits();
void showRoadMap(); /** @brief Show the project roadmap */
void showRoadMap();
/** @brief Reload the CSS style sheet */
void reloadStylesheet(); /** @brief Reload the CSS style sheet */
/** @brief Let the user select the CSS style sheet */ void reloadStylesheet();
void selectStylesheet(); /** @brief Let the user select the CSS style sheet */
/** @brief Automatically reconnect last link */ void selectStylesheet();
void enableAutoReconnect(bool enabled); /** @brief Automatically reconnect last link */
/** @brief Save power by reducing update rates */ void enableAutoReconnect(bool enabled);
void enableLowPowerMode(bool enabled) { lowPowerMode = enabled; } /** @brief Save power by reducing update rates */
/** @brief Switch to native application style */ void enableLowPowerMode(bool enabled) { lowPowerMode = enabled; }
void loadNativeStyle(); /** @brief Switch to native application style */
/** @brief Switch to indoor mission style */ void loadNativeStyle();
void loadIndoorStyle(); /** @brief Switch to indoor mission style */
/** @brief Switch to outdoor mission style */ void loadIndoorStyle();
void loadOutdoorStyle(); /** @brief Switch to outdoor mission style */
/** @brief Load a specific style */ void loadOutdoorStyle();
void loadStyle(QGC_MAINWINDOW_STYLE style); /** @brief Load a specific style */
void loadStyle(QGC_MAINWINDOW_STYLE style);
/** @brief Add a custom tool widget */
void createCustomWidget(); /** @brief Add a custom tool widget */
void createCustomWidget();
/** @brief Load a custom tool widget from a file chosen by user (QFileDialog) */
void loadCustomWidget(); /** @brief Load a custom tool widget from a file chosen by user (QFileDialog) */
void loadCustomWidget();
/** @brief Load a custom tool widget from a file */
void loadCustomWidget(const QString& fileName, bool singleinstance=false); /** @brief Load a custom tool widget from a file */
void loadCustomWidget(const QString& fileName, bool singleinstance=false);
/** @brief Load custom widgets from default file */
void loadCustomWidgetsFromDefaults(const QString& systemType, const QString& autopilotType); /** @brief Load custom widgets from default file */
void loadCustomWidgetsFromDefaults(const QString& systemType, const QString& autopilotType);
/** @brief Loads and shows the HIL Configuration Widget for the given UAS*/
void showHILConfigurationWidget(UASInterface *uas); /** @brief Loads and shows the HIL Configuration Widget for the given UAS*/
void showHILConfigurationWidget(UASInterface *uas);
void closeEvent(QCloseEvent* event);
void closeEvent(QCloseEvent* event);
/** @brief Load data view, allowing to plot flight data */
void loadDataView(QString fileName); /** @brief Load data view, allowing to plot flight data */
void loadDataView(QString fileName);
/**
* @brief Shows a Docked Widget based on the action sender /**
* * @brief Shows a Docked Widget based on the action sender
* This slot is written to be used in conjunction with the addTool() function *
* It shows the QDockedWidget based on the action sender * This slot is written to be used in conjunction with the addTool() function
* * It shows the QDockedWidget based on the action sender
*/ *
void showTool(bool visible); */
void showTool(bool visible);
/**
* @brief Shows a Widget from the center stack based on the action sender /**
* * @brief Shows a Widget from the center stack based on the action sender
* This slot is written to be used in conjunction with the addCentralWidget() function *
* It shows the Widget based on the action sender * This slot is written to be used in conjunction with the addCentralWidget() function
* * It shows the Widget based on the action sender
*/ *
void showCentralWidget(); */
void showCentralWidget();
/** @brief Update the window name */
void configureWindowName(); /** @brief Update the window name */
void configureWindowName();
signals:
void initStatusChanged(const QString& message); signals:
void initStatusChanged(const QString& message);
public:
QGCMAVLinkLogPlayer* getLogPlayer() public:
{ QGCMAVLinkLogPlayer* getLogPlayer()
return logPlayer; {
} return logPlayer;
}
MAVLinkProtocol* getMAVLink()
{ MAVLinkProtocol* getMAVLink()
return mavlink; {
} return mavlink;
}
protected:
protected:
MainWindow(QWidget *parent = 0);
MainWindow(QWidget *parent = 0);
typedef enum _VIEW_SECTIONS
{ typedef enum _VIEW_SECTIONS
VIEW_ENGINEER, {
VIEW_OPERATOR, VIEW_ENGINEER,
VIEW_PILOT, VIEW_OPERATOR,
VIEW_MAVLINK, VIEW_PILOT,
VIEW_FIRMWAREUPDATE, VIEW_MAVLINK,
VIEW_UNCONNECTED, ///< View in unconnected mode, when no UAS is available VIEW_FIRMWAREUPDATE,
VIEW_FULL ///< All widgets shown at once VIEW_UNCONNECTED, ///< View in unconnected mode, when no UAS is available
} VIEW_SECTIONS; VIEW_FULL ///< All widgets shown at once
} VIEW_SECTIONS;
/**
* @brief Adds an already instantiated QDockedWidget to the Tools Menu /**
* * @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 * This function does all the hosekeeping to have a QDockedWidget added to the
* checks/unchecks the tools menu item * tools menu and connects the QMenuAction to a slot that shows the widget and
* * checks/unchecks the tools menu item
* @param widget The QDockWidget being added *
* @param title The entry that will appear in the Menu and in the QDockedWidget title bar * @param widget The QDockWidget being added
* @param location The default location for the QDockedWidget in case there is no previous key in the settings * @param title The entry that will appear in the Menu and in the QDockedWidget title bar
*/ * @param location The default location for the QDockedWidget in case there is no previous key in the settings
void addTool(QDockWidget* widget, const QString& title, Qt::DockWidgetArea location=Qt::RightDockWidgetArea); */
void addTool(QDockWidget* widget, const QString& title, Qt::DockWidgetArea location=Qt::RightDockWidgetArea);
/**
* @brief Adds an already instantiated QWidget to the center stack /**
* * @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 * This function does all the hosekeeping to have a QWidget added to the tools menu
* checks/unchecks the tools menu item. This is used for all the central widgets (those in * tools menu and connects the QMenuAction to a slot that shows the widget and
* the center stack. * 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 widget The QWidget being added
*/ * @param title The entry that will appear in the Menu
void addCentralWidget(QWidget* widget, const QString& title); */
void addCentralWidget(QWidget* widget, const QString& title);
/** @brief Catch window resize events */
void resizeEvent(QResizeEvent * event); /** @brief Catch window resize events */
void resizeEvent(QResizeEvent * event);
/** @brief Keeps track of the current view */
VIEW_SECTIONS currentView; /** @brief Keeps track of the current view */
QGC_MAINWINDOW_STYLE currentStyle; VIEW_SECTIONS currentView;
bool aboutToCloseFlag; QGC_MAINWINDOW_STYLE currentStyle;
bool changingViewsFlag; bool aboutToCloseFlag;
bool changingViewsFlag;
void storeViewState();
void loadViewState(); void storeViewState();
void loadViewState();
void buildCustomWidget();
void buildCommonWidgets(); void buildCustomWidget();
void connectCommonWidgets(); void buildCommonWidgets();
void connectCommonActions(); void connectCommonWidgets();
void connectSenseSoarActions(); void connectCommonActions();
void connectSenseSoarActions();
void loadSettings();
void storeSettings(); void loadSettings();
void storeSettings();
// TODO Should be moved elsewhere, as the protocol does not belong to the UI
MAVLinkProtocol* mavlink; // TODO Should be moved elsewhere, as the protocol does not belong to the UI
MAVLinkProtocol* mavlink;
MAVLinkSimulationLink* simulationLink;
LinkInterface* udpLink; MAVLinkSimulationLink* simulationLink;
LinkInterface* udpLink;
QSettings settings;
QStackedWidget *centerStack; QSettings settings;
QActionGroup* centerStackActionGroup; QStackedWidget *centerStack;
QActionGroup* centerStackActionGroup;
// Center widgets
QPointer<Linecharts> linechartWidget; // Center widgets
QPointer<HUD> hudWidget; QPointer<Linecharts> linechartWidget;
QPointer<QGCVehicleConfig> configWidget; QPointer<HUD> hudWidget;
QPointer<QGCMapTool> mapWidget; QPointer<QGCVehicleConfig> configWidget;
QPointer<XMLCommProtocolWidget> protocolWidget; QPointer<QGCMapTool> mapWidget;
QPointer<QGCDataPlot2D> dataplotWidget; QPointer<XMLCommProtocolWidget> protocolWidget;
#ifdef QGC_OSG_ENABLED QPointer<QGCDataPlot2D> dataplotWidget;
QPointer<QWidget> _3DWidget; #ifdef QGC_OSG_ENABLED
#endif QPointer<QWidget> _3DWidget;
#if (defined _MSC_VER) || (defined Q_OS_MAC) #endif
QPointer<QGCGoogleEarthView> gEarthWidget; #if (defined _MSC_VER) || (defined Q_OS_MAC)
#endif QPointer<QGCGoogleEarthView> gEarthWidget;
QPointer<QGCFirmwareUpdate> firmwareUpdateWidget; #endif
QPointer<QGCFirmwareUpdate> firmwareUpdateWidget;
// Dock widgets
QPointer<QDockWidget> controlDockWidget; // Dock widgets
QPointer<QDockWidget> controlParameterWidget; QPointer<QDockWidget> controlDockWidget;
QPointer<QDockWidget> infoDockWidget; QPointer<QDockWidget> controlParameterWidget;
QPointer<QDockWidget> cameraDockWidget; QPointer<QDockWidget> infoDockWidget;
QPointer<QDockWidget> listDockWidget; QPointer<QDockWidget> cameraDockWidget;
QPointer<QDockWidget> waypointsDockWidget; QPointer<QDockWidget> listDockWidget;
QPointer<QDockWidget> detectionDockWidget; QPointer<QDockWidget> waypointsDockWidget;
QPointer<QDockWidget> debugConsoleDockWidget; QPointer<QDockWidget> detectionDockWidget;
QPointer<QDockWidget> parametersDockWidget; QPointer<QDockWidget> debugConsoleDockWidget;
QPointer<QDockWidget> headDown1DockWidget; QPointer<QDockWidget> parametersDockWidget;
QPointer<QDockWidget> headDown2DockWidget; QPointer<QDockWidget> headDown1DockWidget;
QPointer<QDockWidget> watchdogControlDockWidget; QPointer<QDockWidget> headDown2DockWidget;
QPointer<QDockWidget> watchdogControlDockWidget;
QPointer<QDockWidget> headUpDockWidget;
QPointer<QDockWidget> video1DockWidget; QPointer<QDockWidget> headUpDockWidget;
QPointer<QDockWidget> video2DockWidget; QPointer<QDockWidget> video1DockWidget;
QPointer<QDockWidget> rgbd1DockWidget; QPointer<QDockWidget> video2DockWidget;
QPointer<QDockWidget> rgbd2DockWidget; QPointer<QDockWidget> rgbd1DockWidget;
QPointer<QDockWidget> logPlayerDockWidget; QPointer<QDockWidget> rgbd2DockWidget;
QPointer<QDockWidget> logPlayerDockWidget;
QPointer<QDockWidget> hsiDockWidget;
QPointer<QDockWidget> rcViewDockWidget; QPointer<QDockWidget> hsiDockWidget;
QPointer<QDockWidget> hudDockWidget; QPointer<QDockWidget> rcViewDockWidget;
QPointer<QDockWidget> slugsDataWidget; QPointer<QDockWidget> hudDockWidget;
QPointer<QDockWidget> slugsHilSimWidget; QPointer<QDockWidget> slugsDataWidget;
QPointer<QDockWidget> slugsCamControlWidget; QPointer<QDockWidget> slugsHilSimWidget;
QPointer<QDockWidget> slugsCamControlWidget;
QPointer<QGCToolBar> toolBar;
QPointer<QGCToolBar> toolBar;
QPointer<QDockWidget> mavlinkInspectorWidget;
QPointer<MAVLinkDecoder> mavlinkDecoder; QPointer<QDockWidget> mavlinkInspectorWidget;
QPointer<QDockWidget> mavlinkSenderWidget; QPointer<MAVLinkDecoder> mavlinkDecoder;
QGCMAVLinkLogPlayer* logPlayer; QPointer<QDockWidget> mavlinkSenderWidget;
QGCMAVLinkLogPlayer* logPlayer;
// Popup widgets
JoystickWidget* joystickWidget; // Popup widgets
JoystickWidget* joystickWidget;
JoystickInput* joystick;
JoystickInput* joystick;
/** User interface actions **/
QAction* connectUASAct; #ifdef MOUSE_ENABLED_WIN
QAction* disconnectUASAct; /** 3d Mouse support (WIN only) **/
QAction* startUASAct; Mouse3DInput* mouseInput; ///< 3dConnexion 3dMouse SDK
QAction* returnUASAct; Mouse6dofInput* mouse; ///< Implementation for 3dMouse input
QAction* stopUASAct; #endif // MOUSE_ENABLED_WIN
QAction* killUASAct;
QAction* simulateUASAct; /** User interface actions **/
QAction* connectUASAct;
QAction* disconnectUASAct;
LogCompressor* comp; QAction* startUASAct;
QString screenFileName; QAction* returnUASAct;
QTimer* videoTimer; QAction* stopUASAct;
QString styleFileName; QAction* killUASAct;
bool autoReconnect; QAction* simulateUASAct;
Qt::WindowStates windowStateVal;
bool lowPowerMode; ///< If enabled, QGC reduces the update rates of all widgets
QGCFlightGearLink* fgLink; LogCompressor* comp;
QTimer windowNameUpdateTimer; QString screenFileName;
QTimer* videoTimer;
private: QString styleFileName;
Ui::MainWindow ui; bool autoReconnect;
Qt::WindowStates windowStateVal;
QString getWindowStateKey(); bool lowPowerMode; ///< If enabled, QGC reduces the update rates of all widgets
QString getWindowGeometryKey(); QGCFlightGearLink* fgLink;
QTimer windowNameUpdateTimer;
};
private:
#endif /* _MAINWINDOW_H_ */ Ui::MainWindow ui;
QString getWindowStateKey();
QString getWindowGeometryKey();
};
#endif /* _MAINWINDOW_H_ */
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment