Commit dffc01d6 authored by Alejandro's avatar Alejandro

Working in SLUGS widgets for debug

parent 3b928588
# -------------------------------------------------
# QGroundControl - Micro Air Vehicle Groundstation
# Please see our website at <http://qgroundcontrol.org>
# Author:
# Lorenz Meier <mavteam@student.ethz.ch>
# (c) 2009-2010 PIXHAWK Team
# This file is part of the mav groundstation project
# QGroundControl is free software: you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
# QGroundControl is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU General Public License for more details.
# You should have received a copy of the GNU General Public License
# along with QGroundControl. If not, see <http://www.gnu.org/licenses/>.
# -------------------------------------------------
# Include QMapControl map library
# prefer version from external directory /
# from http://github.com/pixhawk/qmapcontrol/
# over bundled version in lib directory
# Version from GIT repository is preferred
# include ( "../qmapcontrol/QMapControl/QMapControl.pri" ) #{
# Include bundled version if necessary
include(lib/QMapControl/QMapControl.pri)
include(lib/nmea/nmea.pri)
# message("Including bundled QMapControl version as FALLBACK. This is fine on Linux and MacOS, but not the best choice in Windows")
QT += network \
opengl \
svg \
xml \
phonon \
webkit
TEMPLATE = app
TARGET = qgroundcontrol
BASEDIR = $$IN_PWD
TARGETDIR = $$OUT_PWD
BUILDDIR = $$TARGETDIR/build
LANGUAGE = C++
OBJECTS_DIR = $$BUILDDIR/obj
MOC_DIR = $$BUILDDIR/moc
UI_HEADERS_DIR = src/ui/generated
MAVLINK_CONF = ""
# If the user config file exists, it will be included.
# if the variable MAVLINK_CONF contains the name of an
# additional project, QGroundControl includes the support
# of custom MAVLink messages of this project
exists(user_config.pri) {
include(user_config.pri)
message("----- USING CUSTOM USER QGROUNDCONTROL CONFIG FROM user_config.pri -----")
message("Adding support for additional MAVLink messages for: " $$MAVLINK_CONF)
message("------------------------------------------------------------------------")
}
INCLUDEPATH += $$BASEDIR/../mavlink/include/common
contains(MAVLINK_CONF, pixhawk) {
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
# PIXHAWK SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/pixhawk
DEFINES += QGC_USE_PIXHAWK_MESSAGES
}
contains(MAVLINK_CONF, slugs) {
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
# SLUGS SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/slugs
DEFINES += QGC_USE_SLUGS_MESSAGES
}
contains(MAVLINK_CONF, ualberta) {
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
# UALBERTA SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/ualberta
DEFINES += QGC_USE_UALBERTA_MESSAGES
}
contains(MAVLINK_CONF, ardupilotmega) {
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
# UALBERTA SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/ardupilotmega
DEFINES += QGC_USE_ARDUPILOTMEGA_MESSAGES
}
# }
# Include general settings for MAVGround
# necessary as last include to override any non-acceptable settings
# done by the plugins above
include(qgroundcontrol.pri)
# QWT plot and QExtSerial depend on paths set by qgroundcontrol.pri
# Include serial port library
include(src/lib/qextserialport/qextserialport.pri)
# Include QWT plotting library
include(src/lib/qwt/qwt.pri)
DEPENDPATH += . \
lib/QMapControl \
lib/QMapControl/src \
plugins
INCLUDEPATH += . \
lib/QMapControl \
$$BASEDIR/../mavlink/include
# ../mavlink/include \
# MAVLink/include \
# mavlink/include
# Input
FORMS += src/ui/MainWindow.ui \
src/ui/CommSettings.ui \
src/ui/SerialSettings.ui \
src/ui/UASControl.ui \
src/ui/UASList.ui \
src/ui/UASInfo.ui \
src/ui/Linechart.ui \
src/ui/UASView.ui \
src/ui/ParameterInterface.ui \
src/ui/WaypointList.ui \
src/ui/WaypointView.ui \
src/ui/ObjectDetectionView.ui \
src/ui/JoystickWidget.ui \
src/ui/DebugConsole.ui \
src/ui/MapWidget.ui \
src/ui/XMLCommProtocolWidget.ui \
src/ui/HDDisplay.ui \
src/ui/MAVLinkSettingsWidget.ui \
src/ui/AudioOutputWidget.ui \
src/ui/QGCSensorSettingsWidget.ui \
src/ui/watchdog/WatchdogControl.ui \
src/ui/watchdog/WatchdogProcessView.ui \
src/ui/watchdog/WatchdogView.ui \
src/ui/QGCFirmwareUpdate.ui \
src/ui/QGCPxImuFirmwareUpdate.ui \
src/ui/QGCDataPlot2D.ui \
src/ui/QGCRemoteControlView.ui \
src/ui/QMap3D.ui \
src/ui/QGCWebView.ui \
src/ui/map3D/QGCGoogleEarthView.ui \
src/ui/map3D/QGCGoogleEarthViewWin.ui \
src/ui/SlugsDataSensorView.ui \
src/ui/SlugsHilSim.ui \
src/ui/SlugsPIDControl.ui \
src/ui/SlugsVideoCamControl.ui \
src/ui/SlugsPadCameraControl.ui \
src/ui/uas/QGCUnconnectedInfoWidget.ui \
src/ui/designer/QGCToolWidget.ui \
src/ui/designer/QGCParamSlider.ui \
src/ui/designer/QGCActionButton.ui \
src/ui/QGCMAVLinkLogPlayer.ui \
src/ui/QGCWaypointListMulti.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
src/ui/uas \
src/ui/map \
src/uas \
src/comm \
include/ui \
src/input \
src/lib/qmapcontrol \
src/ui/mavlink \
src/ui/param \
src/ui/watchdog \
src/ui/map3D \
src/ui/designer
HEADERS += src/MG.h \
src/Core.h \
src/uas/UASInterface.h \
src/uas/UAS.h \
src/uas/UASManager.h \
src/comm/LinkManager.h \
src/comm/LinkInterface.h \
src/comm/SerialLinkInterface.h \
src/comm/SerialLink.h \
src/comm/SerialSimulationLink.h \
src/comm/ProtocolInterface.h \
src/comm/MAVLinkProtocol.h \
src/comm/AS4Protocol.h \
src/ui/CommConfigurationWindow.h \
src/ui/SerialConfigurationWindow.h \
src/ui/MainWindow.h \
src/ui/uas/UASControlWidget.h \
src/ui/uas/UASListWidget.h \
src/ui/uas/UASInfoWidget.h \
src/ui/HUD.h \
src/ui/linechart/LinechartWidget.h \
src/ui/linechart/LinechartPlot.h \
src/ui/linechart/Scrollbar.h \
src/ui/linechart/ScrollZoomer.h \
src/configuration.h \
src/ui/uas/UASView.h \
src/ui/CameraView.h \
src/comm/MAVLinkSimulationLink.h \
src/comm/UDPLink.h \
src/ui/ParameterInterface.h \
src/ui/WaypointList.h \
src/Waypoint.h \
src/ui/WaypointView.h \
src/ui/ObjectDetectionView.h \
src/input/JoystickInput.h \
src/ui/JoystickWidget.h \
src/ui/DebugConsole.h \
src/ui/MapWidget.h \
src/ui/XMLCommProtocolWidget.h \
src/ui/mavlink/DomItem.h \
src/ui/mavlink/DomModel.h \
src/comm/MAVLinkXMLParser.h \
src/ui/HDDisplay.h \
src/ui/MAVLinkSettingsWidget.h \
src/ui/AudioOutputWidget.h \
src/GAudioOutput.h \
src/LogCompressor.h \
src/ui/QGCParamWidget.h \
src/ui/QGCSensorSettingsWidget.h \
src/ui/linechart/Linecharts.h \
src/uas/SlugsMAV.h \
src/uas/PxQuadMAV.h \
src/uas/ArduPilotMegaMAV.h \
src/comm/MAVLinkSyntaxHighlighter.h \
src/ui/watchdog/WatchdogControl.h \
src/ui/watchdog/WatchdogProcessView.h \
src/ui/watchdog/WatchdogView.h \
src/uas/UASWaypointManager.h \
src/ui/HSIDisplay.h \
src/QGC.h \
src/ui/QGCFirmwareUpdate.h \
src/ui/QGCPxImuFirmwareUpdate.h \
src/ui/QGCDataPlot2D.h \
src/ui/linechart/IncrementalPlot.h \
src/ui/map/Waypoint2DIcon.h \
src/ui/map/MAV2DIcon.h \
src/ui/QGCRemoteControlView.h \
src/ui/RadioCalibration/RadioCalibrationData.h \
src/ui/RadioCalibration/RadioCalibrationWindow.h \
src/ui/RadioCalibration/AirfoilServoCalibrator.h \
src/ui/RadioCalibration/SwitchCalibrator.h \
src/ui/RadioCalibration/CurveCalibrator.h \
src/ui/RadioCalibration/AbstractCalibrator.h \
src/comm/QGCMAVLink.h \
src/ui/QGCWebView.h \
src/ui/map3D/QGCWebPage.h \
src/ui/SlugsDataSensorView.h \
src/ui/SlugsHilSim.h \
src/ui/SlugsPIDControl.h \
src/ui/SlugsVideoCamControl.h \
src/ui/SlugsPadCameraControl.h \
src/ui/QGCMainWindowAPConfigurator.h \
src/comm/MAVLinkSwarmSimulationLink.h \
src/ui/uas/QGCUnconnectedInfoWidget.h \
src/ui/designer/QGCToolWidget.h \
src/ui/designer/QGCParamSlider.h \
src/ui/designer/QGCActionButton.h \
src/ui/designer/QGCToolWidgetItem.h \
src/ui/QGCMAVLinkLogPlayer.h \
src/comm/MAVLinkSimulationWaypointPlanner.h \
src/comm/MAVLinkSimulationMAV.h \
src/uas/QGCMAVLinkUASFactory.h \
src/ui/QGCWaypointListMulti.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|win32-msvc2008: {
HEADERS += src/ui/map3D/QGCGoogleEarthView.h
}
contains(DEPENDENCIES_PRESENT, osg) {
message("Including headers for OpenSceneGraph")
# Enable only if OpenSceneGraph is available
HEADERS += src/ui/map3D/Q3DWidget.h \
src/ui/map3D/GCManipulator.h \
src/ui/map3D/ImageWindowGeode.h \
src/ui/map3D/QOSGWidget.h \
src/ui/map3D/PixhawkCheetahGeode.h \
src/ui/map3D/Pixhawk3DWidget.h \
src/ui/map3D/Q3DWidgetFactory.h \
src/ui/map3D/WebImageCache.h \
src/ui/map3D/WebImage.h \
src/ui/map3D/TextureCache.h \
src/ui/map3D/Texture.h \
src/ui/map3D/Imagery.h \
src/ui/map3D/HUDScaleGeode.h \
src/ui/map3D/WaypointGroupNode.h
contains(DEPENDENCIES_PRESENT, osgearth) {
message("Including headers for OSGEARTH")
# Enable only if OpenSceneGraph is available
HEADERS += src/ui/map3D/QMap3D.h
}
}
contains(DEPENDENCIES_PRESENT, libfreenect) {
message("Including headers for libfreenect")
# Enable only if libfreenect is available
HEADERS += src/input/Freenect.h
}
SOURCES += src/main.cc \
src/Core.cc \
src/uas/UASManager.cc \
src/uas/UAS.cc \
src/comm/LinkManager.cc \
src/comm/SerialLink.cc \
src/comm/SerialSimulationLink.cc \
src/comm/MAVLinkProtocol.cc \
src/comm/AS4Protocol.cc \
src/ui/CommConfigurationWindow.cc \
src/ui/SerialConfigurationWindow.cc \
src/ui/MainWindow.cc \
src/ui/uas/UASControlWidget.cc \
src/ui/uas/UASListWidget.cc \
src/ui/uas/UASInfoWidget.cc \
src/ui/HUD.cc \
src/ui/linechart/LinechartWidget.cc \
src/ui/linechart/LinechartPlot.cc \
src/ui/linechart/Scrollbar.cc \
src/ui/linechart/ScrollZoomer.cc \
src/ui/uas/UASView.cc \
src/ui/CameraView.cc \
src/comm/MAVLinkSimulationLink.cc \
src/comm/UDPLink.cc \
src/ui/ParameterInterface.cc \
src/ui/WaypointList.cc \
src/Waypoint.cc \
src/ui/WaypointView.cc \
src/ui/ObjectDetectionView.cc \
src/input/JoystickInput.cc \
src/ui/JoystickWidget.cc \
src/ui/DebugConsole.cc \
src/ui/MapWidget.cc \
src/ui/XMLCommProtocolWidget.cc \
src/ui/mavlink/DomItem.cc \
src/ui/mavlink/DomModel.cc \
src/comm/MAVLinkXMLParser.cc \
src/ui/HDDisplay.cc \
src/ui/MAVLinkSettingsWidget.cc \
src/ui/AudioOutputWidget.cc \
src/GAudioOutput.cc \
src/LogCompressor.cc \
src/ui/QGCParamWidget.cc \
src/ui/QGCSensorSettingsWidget.cc \
src/ui/linechart/Linecharts.cc \
src/uas/SlugsMAV.cc \
src/uas/PxQuadMAV.cc \
src/uas/ArduPilotMegaMAV.cc \
src/comm/MAVLinkSyntaxHighlighter.cc \
src/ui/watchdog/WatchdogControl.cc \
src/ui/watchdog/WatchdogProcessView.cc \
src/ui/watchdog/WatchdogView.cc \
src/uas/UASWaypointManager.cc \
src/ui/HSIDisplay.cc \
src/QGC.cc \
src/ui/QGCFirmwareUpdate.cc \
src/ui/QGCPxImuFirmwareUpdate.cc \
src/ui/QGCDataPlot2D.cc \
src/ui/linechart/IncrementalPlot.cc \
src/ui/map/Waypoint2DIcon.cc \
src/ui/map/MAV2DIcon.cc \
src/ui/QGCRemoteControlView.cc \
src/ui/RadioCalibration/RadioCalibrationWindow.cc \
src/ui/RadioCalibration/AirfoilServoCalibrator.cc \
src/ui/RadioCalibration/SwitchCalibrator.cc \
src/ui/RadioCalibration/CurveCalibrator.cc \
src/ui/RadioCalibration/AbstractCalibrator.cc \
src/ui/RadioCalibration/RadioCalibrationData.cc \
src/ui/QGCWebView.cc \
src/ui/map3D/QGCWebPage.cc \
src/ui/SlugsDataSensorView.cc \
src/ui/SlugsHilSim.cc \
src/ui/SlugsPIDControl.cpp \
src/ui/SlugsVideoCamControl.cpp \
src/ui/SlugsPadCameraControl.cpp \
src/ui/QGCMainWindowAPConfigurator.cc \
src/comm/MAVLinkSwarmSimulationLink.cc \
src/ui/uas/QGCUnconnectedInfoWidget.cc \
src/ui/designer/QGCToolWidget.cc \
src/ui/designer/QGCParamSlider.cc \
src/ui/designer/QGCActionButton.cc \
src/ui/designer/QGCToolWidgetItem.cc \
src/ui/QGCMAVLinkLogPlayer.cc \
src/comm/MAVLinkSimulationWaypointPlanner.cc \
src/comm/MAVLinkSimulationMAV.cc \
src/uas/QGCMAVLinkUASFactory.cc \
src/ui/QGCWaypointListMulti.cc
macx|win32-msvc2008: {
SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
}
contains(DEPENDENCIES_PRESENT, osg) {
message("Including sources for OpenSceneGraph")
# Enable only if OpenSceneGraph is available
SOURCES += src/ui/map3D/Q3DWidget.cc \
src/ui/map3D/ImageWindowGeode.cc \
src/ui/map3D/GCManipulator.cc \
src/ui/map3D/QOSGWidget.cc \
src/ui/map3D/PixhawkCheetahGeode.cc \
src/ui/map3D/Pixhawk3DWidget.cc \
src/ui/map3D/Q3DWidgetFactory.cc \
src/ui/map3D/WebImageCache.cc \
src/ui/map3D/WebImage.cc \
src/ui/map3D/TextureCache.cc \
src/ui/map3D/Texture.cc \
src/ui/map3D/Imagery.cc \
src/ui/map3D/HUDScaleGeode.cc \
src/ui/map3D/WaypointGroupNode.cc \
contains(DEPENDENCIES_PRESENT, osgearth) {
message("Including sources for osgEarth")
# Enable only if OpenSceneGraph is available
SOURCES += src/ui/map3D/QMap3D.cc
}
}
contains(DEPENDENCIES_PRESENT, libfreenect) {
message("Including sources for libfreenect")
# Enable only if libfreenect is available
SOURCES += src/input/Freenect.cc
}
RESOURCES += mavground.qrc
# Include RT-LAB Library
win32:exists(src/lib/opalrt/OpalApi.h):exists(C:/OPAL-RT/RT-LAB7.2.4/Common/bin) {
message("Building support for Opal-RT")
LIBS += -LC:/OPAL-RT/RT-LAB7.2.4/Common/bin \
-lOpalApi
INCLUDEPATH += src/lib/opalrt
HEADERS += src/comm/OpalRT.h \
src/comm/OpalLink.h \
src/comm/Parameter.h \
src/comm/QGCParamID.h \
src/comm/ParameterList.h \
src/ui/OpalLinkConfigurationWindow.h
SOURCES += src/comm/OpalRT.cc \
src/comm/OpalLink.cc \
src/comm/Parameter.cc \
src/comm/QGCParamID.cc \
src/comm/ParameterList.cc \
src/ui/OpalLinkConfigurationWindow.cc
FORMS += src/ui/OpalLinkSettings.ui
DEFINES += OPAL_RT
}
# -------------------------------------------------
# QGroundControl - Micro Air Vehicle Groundstation
# Please see our website at <http://qgroundcontrol.org>
# Author:
# Lorenz Meier <mavteam@student.ethz.ch>
# (c) 2009-2010 PIXHAWK Team
# This file is part of the mav groundstation project
# QGroundControl is free software: you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
# QGroundControl is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU General Public License for more details.
# You should have received a copy of the GNU General Public License
# along with QGroundControl. If not, see <http://www.gnu.org/licenses/>.
# -------------------------------------------------
# Include QMapControl map library
# prefer version from external directory /
# from http://github.com/pixhawk/qmapcontrol/
# over bundled version in lib directory
# Version from GIT repository is preferred
# include ( "../qmapcontrol/QMapControl/QMapControl.pri" ) #{
# Include bundled version if necessary
include(lib/QMapControl/QMapControl.pri)
include(lib/nmea/nmea.pri)
# message("Including bundled QMapControl version as FALLBACK. This is fine on Linux and MacOS, but not the best choice in Windows")
QT += network \
opengl \
svg \
xml \
phonon \
webkit
TEMPLATE = app
TARGET = qgroundcontrol
BASEDIR = $$IN_PWD
TARGETDIR = $$OUT_PWD
BUILDDIR = $$TARGETDIR/build
LANGUAGE = C++
OBJECTS_DIR = $$BUILDDIR/obj
MOC_DIR = $$BUILDDIR/moc
UI_HEADERS_DIR = src/ui/generated
MAVLINK_CONF = ""
# If the user config file exists, it will be included.
# if the variable MAVLINK_CONF contains the name of an
# additional project, QGroundControl includes the support
# of custom MAVLink messages of this project
exists(user_config.pri) {
include(user_config.pri)
message("----- USING CUSTOM USER QGROUNDCONTROL CONFIG FROM user_config.pri -----")
message("Adding support for additional MAVLink messages for: " $$MAVLINK_CONF)
message("------------------------------------------------------------------------")
}
INCLUDEPATH += $$BASEDIR/../mavlink/include/common
contains(MAVLINK_CONF, pixhawk) {
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
# PIXHAWK SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/pixhawk
DEFINES += QGC_USE_PIXHAWK_MESSAGES
}
contains(MAVLINK_CONF, slugs) {
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
# SLUGS SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/slugs
DEFINES += QGC_USE_SLUGS_MESSAGES
}
contains(MAVLINK_CONF, ualberta) {
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
# UALBERTA SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/ualberta
DEFINES += QGC_USE_UALBERTA_MESSAGES
}
contains(MAVLINK_CONF, ardupilotmega) {
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
# UALBERTA SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/ardupilotmega
DEFINES += QGC_USE_ARDUPILOTMEGA_MESSAGES
}
# }
# Include general settings for MAVGround
# necessary as last include to override any non-acceptable settings
# done by the plugins above
include(qgroundcontrol.pri)
# QWT plot and QExtSerial depend on paths set by qgroundcontrol.pri
# Include serial port library
include(src/lib/qextserialport/qextserialport.pri)
# Include QWT plotting library
include(src/lib/qwt/qwt.pri)
DEPENDPATH += . \
lib/QMapControl \
lib/QMapControl/src \
plugins
INCLUDEPATH += . \
lib/QMapControl \
$$BASEDIR/../mavlink/include
# ../mavlink/include \
# MAVLink/include \
# mavlink/include
# Input
FORMS += src/ui/MainWindow.ui \
src/ui/CommSettings.ui \
src/ui/SerialSettings.ui \
src/ui/UASControl.ui \
src/ui/UASList.ui \
src/ui/UASInfo.ui \
src/ui/Linechart.ui \
src/ui/UASView.ui \
src/ui/ParameterInterface.ui \
src/ui/WaypointList.ui \
src/ui/WaypointView.ui \
src/ui/ObjectDetectionView.ui \
src/ui/JoystickWidget.ui \
src/ui/DebugConsole.ui \
src/ui/MapWidget.ui \
src/ui/XMLCommProtocolWidget.ui \
src/ui/HDDisplay.ui \
src/ui/MAVLinkSettingsWidget.ui \
src/ui/AudioOutputWidget.ui \
src/ui/QGCSensorSettingsWidget.ui \
src/ui/watchdog/WatchdogControl.ui \
src/ui/watchdog/WatchdogProcessView.ui \
src/ui/watchdog/WatchdogView.ui \
src/ui/QGCFirmwareUpdate.ui \
src/ui/QGCPxImuFirmwareUpdate.ui \
src/ui/QGCDataPlot2D.ui \
src/ui/QGCRemoteControlView.ui \
src/ui/QMap3D.ui \
src/ui/QGCWebView.ui \
src/ui/map3D/QGCGoogleEarthView.ui \
src/ui/map3D/QGCGoogleEarthViewWin.ui \
src/ui/SlugsDataSensorView.ui \
src/ui/SlugsHilSim.ui \
src/ui/SlugsPIDControl.ui \
src/ui/SlugsVideoCamControl.ui \
src/ui/SlugsPadCameraControl.ui \
src/ui/uas/QGCUnconnectedInfoWidget.ui \
src/ui/designer/QGCToolWidget.ui \
src/ui/designer/QGCParamSlider.ui \
src/ui/designer/QGCActionButton.ui \
src/ui/QGCMAVLinkLogPlayer.ui \
src/ui/QGCWaypointListMulti.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
src/ui/uas \
src/ui/map \
src/uas \
src/comm \
include/ui \
src/input \
src/lib/qmapcontrol \
src/ui/mavlink \
src/ui/param \
src/ui/watchdog \
src/ui/map3D \
src/ui/designer
HEADERS += src/MG.h \
src/Core.h \
src/uas/UASInterface.h \
src/uas/UAS.h \
src/uas/UASManager.h \
src/comm/LinkManager.h \
src/comm/LinkInterface.h \
src/comm/SerialLinkInterface.h \
src/comm/SerialLink.h \
src/comm/SerialSimulationLink.h \
src/comm/ProtocolInterface.h \
src/comm/MAVLinkProtocol.h \
src/comm/AS4Protocol.h \
src/ui/CommConfigurationWindow.h \
src/ui/SerialConfigurationWindow.h \
src/ui/MainWindow.h \
src/ui/uas/UASControlWidget.h \
src/ui/uas/UASListWidget.h \
src/ui/uas/UASInfoWidget.h \
src/ui/HUD.h \
src/ui/linechart/LinechartWidget.h \
src/ui/linechart/LinechartPlot.h \
src/ui/linechart/Scrollbar.h \
src/ui/linechart/ScrollZoomer.h \
src/configuration.h \
src/ui/uas/UASView.h \
src/ui/CameraView.h \
src/comm/MAVLinkSimulationLink.h \
src/comm/UDPLink.h \
src/ui/ParameterInterface.h \
src/ui/WaypointList.h \
src/Waypoint.h \
src/ui/WaypointView.h \
src/ui/ObjectDetectionView.h \
src/input/JoystickInput.h \
src/ui/JoystickWidget.h \
src/ui/DebugConsole.h \
src/ui/MapWidget.h \
src/ui/XMLCommProtocolWidget.h \
src/ui/mavlink/DomItem.h \
src/ui/mavlink/DomModel.h \
src/comm/MAVLinkXMLParser.h \
src/ui/HDDisplay.h \
src/ui/MAVLinkSettingsWidget.h \
src/ui/AudioOutputWidget.h \
src/GAudioOutput.h \
src/LogCompressor.h \
src/ui/QGCParamWidget.h \
src/ui/QGCSensorSettingsWidget.h \
src/ui/linechart/Linecharts.h \
src/uas/SlugsMAV.h \
src/uas/PxQuadMAV.h \
src/uas/ArduPilotMegaMAV.h \
src/comm/MAVLinkSyntaxHighlighter.h \
src/ui/watchdog/WatchdogControl.h \
src/ui/watchdog/WatchdogProcessView.h \
src/ui/watchdog/WatchdogView.h \
src/uas/UASWaypointManager.h \
src/ui/HSIDisplay.h \
src/QGC.h \
src/ui/QGCFirmwareUpdate.h \
src/ui/QGCPxImuFirmwareUpdate.h \
src/ui/QGCDataPlot2D.h \
src/ui/linechart/IncrementalPlot.h \
src/ui/map/Waypoint2DIcon.h \
src/ui/map/MAV2DIcon.h \
src/ui/QGCRemoteControlView.h \
src/ui/RadioCalibration/RadioCalibrationData.h \
src/ui/RadioCalibration/RadioCalibrationWindow.h \
src/ui/RadioCalibration/AirfoilServoCalibrator.h \
src/ui/RadioCalibration/SwitchCalibrator.h \
src/ui/RadioCalibration/CurveCalibrator.h \
src/ui/RadioCalibration/AbstractCalibrator.h \
src/comm/QGCMAVLink.h \
src/ui/QGCWebView.h \
src/ui/map3D/QGCWebPage.h \
src/ui/SlugsDataSensorView.h \
src/ui/SlugsHilSim.h \
src/ui/SlugsPIDControl.h \
src/ui/SlugsVideoCamControl.h \
src/ui/SlugsPadCameraControl.h \
src/ui/QGCMainWindowAPConfigurator.h \
src/comm/MAVLinkSwarmSimulationLink.h \
src/ui/uas/QGCUnconnectedInfoWidget.h \
src/ui/designer/QGCToolWidget.h \
src/ui/designer/QGCParamSlider.h \
src/ui/designer/QGCActionButton.h \
src/ui/designer/QGCToolWidgetItem.h \
src/ui/QGCMAVLinkLogPlayer.h \
src/comm/MAVLinkSimulationWaypointPlanner.h \
src/comm/MAVLinkSimulationMAV.h \
src/uas/QGCMAVLinkUASFactory.h \
src/ui/QGCWaypointListMulti.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|win32-msvc2008: {
HEADERS += src/ui/map3D/QGCGoogleEarthView.h
}
contains(DEPENDENCIES_PRESENT, osg) {
message("Including headers for OpenSceneGraph")
# Enable only if OpenSceneGraph is available
HEADERS += src/ui/map3D/Q3DWidget.h \
src/ui/map3D/GCManipulator.h \
src/ui/map3D/ImageWindowGeode.h \
src/ui/map3D/QOSGWidget.h \
src/ui/map3D/PixhawkCheetahGeode.h \
src/ui/map3D/Pixhawk3DWidget.h \
src/ui/map3D/Q3DWidgetFactory.h \
src/ui/map3D/WebImageCache.h \
src/ui/map3D/WebImage.h \
src/ui/map3D/TextureCache.h \
src/ui/map3D/Texture.h \
src/ui/map3D/Imagery.h \
src/ui/map3D/HUDScaleGeode.h \
src/ui/map3D/WaypointGroupNode.h
contains(DEPENDENCIES_PRESENT, osgearth) {
message("Including headers for OSGEARTH")
# Enable only if OpenSceneGraph is available
HEADERS += src/ui/map3D/QMap3D.h
}
}
contains(DEPENDENCIES_PRESENT, libfreenect) {
message("Including headers for libfreenect")
# Enable only if libfreenect is available
HEADERS += src/input/Freenect.h
}
SOURCES += src/main.cc \
src/Core.cc \
src/uas/UASManager.cc \
src/uas/UAS.cc \
src/comm/LinkManager.cc \
src/comm/SerialLink.cc \
src/comm/SerialSimulationLink.cc \
src/comm/MAVLinkProtocol.cc \
src/comm/AS4Protocol.cc \
src/ui/CommConfigurationWindow.cc \
src/ui/SerialConfigurationWindow.cc \
src/ui/MainWindow.cc \
src/ui/uas/UASControlWidget.cc \
src/ui/uas/UASListWidget.cc \
src/ui/uas/UASInfoWidget.cc \
src/ui/HUD.cc \
src/ui/linechart/LinechartWidget.cc \
src/ui/linechart/LinechartPlot.cc \
src/ui/linechart/Scrollbar.cc \
src/ui/linechart/ScrollZoomer.cc \
src/ui/uas/UASView.cc \
src/ui/CameraView.cc \
src/comm/MAVLinkSimulationLink.cc \
src/comm/UDPLink.cc \
src/ui/ParameterInterface.cc \
src/ui/WaypointList.cc \
src/Waypoint.cc \
src/ui/WaypointView.cc \
src/ui/ObjectDetectionView.cc \
src/input/JoystickInput.cc \
src/ui/JoystickWidget.cc \
src/ui/DebugConsole.cc \
src/ui/MapWidget.cc \
src/ui/XMLCommProtocolWidget.cc \
src/ui/mavlink/DomItem.cc \
src/ui/mavlink/DomModel.cc \
src/comm/MAVLinkXMLParser.cc \
src/ui/HDDisplay.cc \
src/ui/MAVLinkSettingsWidget.cc \
src/ui/AudioOutputWidget.cc \
src/GAudioOutput.cc \
src/LogCompressor.cc \
src/ui/QGCParamWidget.cc \
src/ui/QGCSensorSettingsWidget.cc \
src/ui/linechart/Linecharts.cc \
src/uas/SlugsMAV.cc \
src/uas/PxQuadMAV.cc \
src/uas/ArduPilotMegaMAV.cc \
src/comm/MAVLinkSyntaxHighlighter.cc \
src/ui/watchdog/WatchdogControl.cc \
src/ui/watchdog/WatchdogProcessView.cc \
src/ui/watchdog/WatchdogView.cc \
src/uas/UASWaypointManager.cc \
src/ui/HSIDisplay.cc \
src/QGC.cc \
src/ui/QGCFirmwareUpdate.cc \
src/ui/QGCPxImuFirmwareUpdate.cc \
src/ui/QGCDataPlot2D.cc \
src/ui/linechart/IncrementalPlot.cc \
src/ui/map/Waypoint2DIcon.cc \
src/ui/map/MAV2DIcon.cc \
src/ui/QGCRemoteControlView.cc \
src/ui/RadioCalibration/RadioCalibrationWindow.cc \
src/ui/RadioCalibration/AirfoilServoCalibrator.cc \
src/ui/RadioCalibration/SwitchCalibrator.cc \
src/ui/RadioCalibration/CurveCalibrator.cc \
src/ui/RadioCalibration/AbstractCalibrator.cc \
src/ui/RadioCalibration/RadioCalibrationData.cc \
src/ui/QGCWebView.cc \
src/ui/map3D/QGCWebPage.cc \
src/ui/SlugsDataSensorView.cc \
src/ui/SlugsHilSim.cc \
src/ui/SlugsPIDControl.cpp \
src/ui/SlugsVideoCamControl.cpp \
src/ui/SlugsPadCameraControl.cpp \
src/ui/QGCMainWindowAPConfigurator.cc \
src/comm/MAVLinkSwarmSimulationLink.cc \
src/ui/uas/QGCUnconnectedInfoWidget.cc \
src/ui/designer/QGCToolWidget.cc \
src/ui/designer/QGCParamSlider.cc \
src/ui/designer/QGCActionButton.cc \
src/ui/designer/QGCToolWidgetItem.cc \
src/ui/QGCMAVLinkLogPlayer.cc \
src/comm/MAVLinkSimulationWaypointPlanner.cc \
src/comm/MAVLinkSimulationMAV.cc \
src/uas/QGCMAVLinkUASFactory.cc \
src/ui/QGCWaypointListMulti.cc
macx|win32-msvc2008: {
SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
}
contains(DEPENDENCIES_PRESENT, osg) {
message("Including sources for OpenSceneGraph")
# Enable only if OpenSceneGraph is available
SOURCES += src/ui/map3D/Q3DWidget.cc \
src/ui/map3D/ImageWindowGeode.cc \
src/ui/map3D/GCManipulator.cc \
src/ui/map3D/QOSGWidget.cc \
src/ui/map3D/PixhawkCheetahGeode.cc \
src/ui/map3D/Pixhawk3DWidget.cc \
src/ui/map3D/Q3DWidgetFactory.cc \
src/ui/map3D/WebImageCache.cc \
src/ui/map3D/WebImage.cc \
src/ui/map3D/TextureCache.cc \
src/ui/map3D/Texture.cc \
src/ui/map3D/Imagery.cc \
src/ui/map3D/HUDScaleGeode.cc \
src/ui/map3D/WaypointGroupNode.cc \
contains(DEPENDENCIES_PRESENT, osgearth) {
message("Including sources for osgEarth")
# Enable only if OpenSceneGraph is available
SOURCES += src/ui/map3D/QMap3D.cc
}
}
contains(DEPENDENCIES_PRESENT, libfreenect) {
message("Including sources for libfreenect")
# Enable only if libfreenect is available
SOURCES += src/input/Freenect.cc
}
RESOURCES += mavground.qrc
# Include RT-LAB Library
win32:exists(src/lib/opalrt/OpalApi.h):exists(C:/OPAL-RT/RT-LAB7.2.4/Common/bin) {
message("Building support for Opal-RT")
LIBS += -LC:/OPAL-RT/RT-LAB7.2.4/Common/bin \
-lOpalApi
INCLUDEPATH += src/lib/opalrt
HEADERS += src/comm/OpalRT.h \
src/comm/OpalLink.h \
src/comm/Parameter.h \
src/comm/QGCParamID.h \
src/comm/ParameterList.h \
src/ui/OpalLinkConfigurationWindow.h
SOURCES += src/comm/OpalRT.cc \
src/comm/OpalLink.cc \
src/comm/Parameter.cc \
src/comm/QGCParamID.cc \
src/comm/ParameterList.cc \
src/ui/OpalLinkConfigurationWindow.cc
FORMS += src/ui/OpalLinkSettings.ui
DEFINES += OPAL_RT
}
TRANSLATIONS += es-MX.ts \
en-US.ts
#include "SlugsMAV.h"
#include <QDebug>
SlugsMAV::SlugsMAV(MAVLinkProtocol* mavlink, int id) :
UAS(mavlink, id)//,
// Place other initializers here
{
widgetTimer = new QTimer (this);
widgetTimer->setInterval(SLUGS_UPDATE_RATE);
connect (widgetTimer, SIGNAL(timeout()),
this, SLOT(emitSignals()));
widgetTimer->start();
// clear all the state structures
memset(&mlRawImuData ,0, sizeof(mavlink_raw_imu_t));
#ifdef MAVLINK_ENABLED_SLUGS
memset(&mlGpsData, 0, sizeof(mavlink_gps_raw_t));
memset(&mlCpuLoadData, 0, sizeof(mavlink_cpu_load_t));
memset(&mlAirData, 0, sizeof(mavlink_air_data_t));
memset(&mlSensorBiasData, 0, sizeof(mavlink_sensor_bias_t));
memset(&mlDiagnosticData, 0, sizeof(mavlink_diagnostic_t));
memset(&mlPilotConsoleData, 0, sizeof(mavlink_pilot_console_t));
memset(&mlFilteredData ,0, sizeof(mavlink_filtered_data_t));
memset(&mlBoot ,0, sizeof(mavlink_boot_t));
memset(&mlGpsDateTime ,0, sizeof(mavlink_gps_date_time_t));
memset(&mlApMode ,0, sizeof(mavlink_set_mode_t));
memset(&mlPwmCommands ,0, sizeof(mavlink_pwm_commands_t));
memset(&mlPidValues ,0, sizeof(mavlink_pid_values_t));
memset(&mlSinglePid ,0, sizeof(mavlink_pid_t));
memset(&mlNavigation ,0, sizeof(mavlink_slugs_navigation_t));
memset(&mlDataLog ,0, sizeof(mavlink_data_log_t));
memset(&mlPassthrough ,0, sizeof(mavlink_ctrl_srfc_pt_t));
memset(&mlActionAck,0, sizeof(mavlink_action_ack_t));
memset(&mlAction ,0, sizeof(mavlink_slugs_action_t));
updateRoundRobin = 0;
uasId = id;
#endif
}
/**
* This function is called by MAVLink once a complete, uncorrupted (CRC check valid)
* mavlink packet is received.
*
* @param link Hardware link the message came from (e.g. /dev/ttyUSB0 or UDP port).
* messages can be sent back to the system via this link
* @param message MAVLink message, as received from the MAVLink protocol stack
*/
void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
// Let UAS handle the default message set
UAS::receiveMessage(link, message);
if (message.sysid == uasId)
{
// Handle your special messages mavlink_message_t* msg = &message;
switch (message.msgid)
{
#ifdef MAVLINK_ENABLED_SLUGS
case MAVLINK_MSG_ID_RAW_IMU:
mavlink_msg_raw_imu_decode(&message, &mlRawImuData);
break;
case MAVLINK_MSG_ID_BOOT:
mavlink_msg_boot_decode(&message,&mlBoot);
emit slugsBootMsg(uasId, mlBoot);
break;
case MAVLINK_MSG_ID_ATTITUDE:
mavlink_msg_attitude_decode(&message, &mlAttitude);
break;
case MAVLINK_MSG_ID_GPS_RAW:
mavlink_msg_gps_raw_decode(&message, &mlGpsData);
break;
case MAVLINK_MSG_ID_ACTION_ACK: // 62
mavlink_msg_action_ack_decode(&message,&mlActionAck);
break;
case MAVLINK_MSG_ID_CPU_LOAD: //170
mavlink_msg_cpu_load_decode(&message,&mlCpuLoadData);
break;
case MAVLINK_MSG_ID_AIR_DATA: //171
mavlink_msg_air_data_decode(&message,&mlAirData);
break;
case MAVLINK_MSG_ID_SENSOR_BIAS: //172
mavlink_msg_sensor_bias_decode(&message,&mlSensorBiasData);
break;
case MAVLINK_MSG_ID_DIAGNOSTIC: //173
mavlink_msg_diagnostic_decode(&message,&mlDiagnosticData);
break;
case MAVLINK_MSG_ID_PILOT_CONSOLE: //174
mavlink_msg_pilot_console_decode(&message,&mlPilotConsoleData);
break;
case MAVLINK_MSG_ID_PWM_COMMANDS: //175
mavlink_msg_pwm_commands_decode(&message,&mlPwmCommands);
break;
case MAVLINK_MSG_ID_SLUGS_NAVIGATION://176
mavlink_msg_slugs_navigation_decode(&message,&mlNavigation);
break;
case MAVLINK_MSG_ID_DATA_LOG: //177
mavlink_msg_data_log_decode(&message,&mlDataLog);
break;
case MAVLINK_MSG_ID_FILTERED_DATA: //178
mavlink_msg_filtered_data_decode(&message,&mlFilteredData);
break;
case MAVLINK_MSG_ID_GPS_DATE_TIME: //179
mavlink_msg_gps_date_time_decode(&message,&mlGpsDateTime);
break;
case MAVLINK_MSG_ID_MID_LVL_CMDS: //180
break;
case MAVLINK_MSG_ID_CTRL_SRFC_PT: //181
break;
case MAVLINK_MSG_ID_PID: //182
memset(&mlSinglePid,0,sizeof(mavlink_pid_t));
mavlink_msg_pid_decode(&message, &mlSinglePid);
// qDebug() << "\nSLUGS RECEIVED PID Message = "<<mlSinglePid.idx;
emit slugsPidValues(uasId, mlSinglePid);
break;
case MAVLINK_MSG_ID_SLUGS_ACTION: //183
break;
#endif
default:
// qDebug() << "\nSLUGS RECEIVED MESSAGE WITH ID" << message.msgid;
break;
}
}
}
void SlugsMAV::emitSignals (void){
#ifdef MAVLINK_ENABLED_SLUGS
switch(updateRoundRobin){
case 1:
emit slugsCPULoad(uasId, mlCpuLoadData);
emit slugsSensorBias(uasId,mlSensorBiasData);
break;
case 2:
emit slugsAirData(uasId, mlAirData);
emit slugsDiagnostic(uasId,mlDiagnosticData);
break;
case 3:
emit remoteControlChannelScaledChanged(0,(mlPilotConsoleData.de- 1000.0f)/1000.0f);
emit remoteControlChannelScaledChanged(1,(mlPilotConsoleData.dla- 1000.0f)/1000.0f);
emit remoteControlChannelScaledChanged(2,(mlPilotConsoleData.dr- 1000.0f)/1000.0f);
emit remoteControlChannelScaledChanged(3,(mlPilotConsoleData.dra- 1000.0f)/1000.0f);
emit slugsPWM(uasId, mlPwmCommands);
break;
case 4:
emit slugsNavegation(uasId, mlNavigation);
emit slugsDataLog(uasId, mlDataLog);
break;
case 5:
emit slugsFilteredData(uasId,mlFilteredData);
emit slugsGPSDateTime(uasId, mlGpsDateTime);
break;
case 6:
emit slugsActionAck(uasId,mlActionAck);
emit emitGpsSignals();
break;
}
emit slugsAttitude(uasId, mlAttitude);
emit attitudeChanged(this,
mlAttitude.roll,
mlAttitude.pitch,
mlAttitude.yaw,
0.0);
#endif
emit slugsRawImu(uasId, mlRawImuData);
// wrap around
updateRoundRobin = updateRoundRobin > 10? 1: updateRoundRobin + 1;
}
#ifdef MAVLINK_ENABLED_SLUGS
void SlugsMAV::emitGpsSignals (void){
// qDebug()<<"After Emit GPS Signal"<<mlGpsData.fix_type;
//ToDo Uncomment if. it was comment only to test
// if (mlGpsData.fix_type > 0){
emit globalPositionChanged(this,
mlGpsData.lon,
mlGpsData.lat,
mlGpsData.alt,
0.0);
emit slugsGPSCogSog(uasId,mlGpsData.hdg, mlGpsData.v);
// // Smaller than threshold and not NaN
// if (mlGpsData.v < 1000000 && mlGpsData.v == mlGpsData.v){
// // emit speedChanged(this, (double)mlGpsData.v, 0.0, 0.0, 0.0);
// }
// else {
// emit textMessageReceived(uasId, uasId, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(mlGpsData.v));
// }
//}
}
void SlugsMAV::emitPidSignal()
{
// qDebug() << "\nSLUGS RECEIVED PID Message";
emit slugsPidValues(uasId, mlSinglePid);
}
mavlink_pwm_commands_t* SlugsMAV::getPwmCommands()
{
return &mlPwmCommands;
}
#endif // MAVLINK_ENABLED_SLUGS
#include "SlugsMAV.h"
#include <QDebug>
SlugsMAV::SlugsMAV(MAVLinkProtocol* mavlink, int id) :
UAS(mavlink, id)//,
// Place other initializers here
{
widgetTimer = new QTimer (this);
widgetTimer->setInterval(200);//SLUGS_UPDATE_RATE);
qDebug() << "SLUGS_UPDATE_RATE: " << SLUGS_UPDATE_RATE;
connect (widgetTimer, SIGNAL(timeout()),
this, SLOT(emitSignals()));
widgetTimer->start();
// clear all the state structures
memset(&mlRawImuData ,0, sizeof(mavlink_raw_imu_t));
#ifdef MAVLINK_ENABLED_SLUGS
memset(&mlGpsData, 0, sizeof(mavlink_gps_raw_t));
memset(&mlCpuLoadData, 0, sizeof(mavlink_cpu_load_t));
memset(&mlAirData, 0, sizeof(mavlink_air_data_t));
memset(&mlSensorBiasData, 0, sizeof(mavlink_sensor_bias_t));
memset(&mlDiagnosticData, 0, sizeof(mavlink_diagnostic_t));
memset(&mlPilotConsoleData, 0, sizeof(mavlink_pilot_console_t));
memset(&mlFilteredData ,0, sizeof(mavlink_filtered_data_t));
memset(&mlBoot ,0, sizeof(mavlink_boot_t));
memset(&mlGpsDateTime ,0, sizeof(mavlink_gps_date_time_t));
memset(&mlApMode ,0, sizeof(mavlink_set_mode_t));
memset(&mlPwmCommands ,0, sizeof(mavlink_pwm_commands_t));
memset(&mlPidValues ,0, sizeof(mavlink_pid_values_t));
memset(&mlSinglePid ,0, sizeof(mavlink_pid_t));
memset(&mlNavigation ,0, sizeof(mavlink_slugs_navigation_t));
memset(&mlDataLog ,0, sizeof(mavlink_data_log_t));
memset(&mlPassthrough ,0, sizeof(mavlink_ctrl_srfc_pt_t));
memset(&mlActionAck,0, sizeof(mavlink_action_ack_t));
memset(&mlAction ,0, sizeof(mavlink_slugs_action_t));
updateRoundRobin = 0;
uasId = id;
#endif
}
/**
* This function is called by MAVLink once a complete, uncorrupted (CRC check valid)
* mavlink packet is received.
*
* @param link Hardware link the message came from (e.g. /dev/ttyUSB0 or UDP port).
* messages can be sent back to the system via this link
* @param message MAVLink message, as received from the MAVLink protocol stack
*/
void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
// Let UAS handle the default message set
UAS::receiveMessage(link, message);
if (message.sysid == uasId)
{
// Handle your special messages mavlink_message_t* msg = &message;
switch (message.msgid)
{
#ifdef MAVLINK_ENABLED_SLUGS
case MAVLINK_MSG_ID_RAW_IMU:
//mavlink_raw_imu_t t;
mavlink_msg_raw_imu_decode(&message, &mlRawImuData);
break;
case MAVLINK_MSG_ID_BOOT:
mavlink_msg_boot_decode(&message,&mlBoot);
emit slugsBootMsg(uasId, mlBoot);
break;
case MAVLINK_MSG_ID_ATTITUDE:
mavlink_msg_attitude_decode(&message, &mlAttitude);
break;
case MAVLINK_MSG_ID_GPS_RAW:
mavlink_msg_gps_raw_decode(&message, &mlGpsData);
break;
case MAVLINK_MSG_ID_ACTION_ACK: // 62
mavlink_msg_action_ack_decode(&message,&mlActionAck);
break;
case MAVLINK_MSG_ID_CPU_LOAD: //170
mavlink_msg_cpu_load_decode(&message,&mlCpuLoadData);
break;
case MAVLINK_MSG_ID_AIR_DATA: //171
mavlink_msg_air_data_decode(&message,&mlAirData);
break;
case MAVLINK_MSG_ID_SENSOR_BIAS: //172
mavlink_msg_sensor_bias_decode(&message,&mlSensorBiasData);
break;
case MAVLINK_MSG_ID_DIAGNOSTIC: //173
mavlink_msg_diagnostic_decode(&message,&mlDiagnosticData);
break;
case MAVLINK_MSG_ID_PILOT_CONSOLE: //174
mavlink_msg_pilot_console_decode(&message,&mlPilotConsoleData);
break;
case MAVLINK_MSG_ID_PWM_COMMANDS: //175
mavlink_msg_pwm_commands_decode(&message,&mlPwmCommands);
break;
case MAVLINK_MSG_ID_SLUGS_NAVIGATION://176
mavlink_msg_slugs_navigation_decode(&message,&mlNavigation);
break;
case MAVLINK_MSG_ID_DATA_LOG: //177
mavlink_msg_data_log_decode(&message,&mlDataLog);
break;
case MAVLINK_MSG_ID_FILTERED_DATA: //178
mavlink_msg_filtered_data_decode(&message,&mlFilteredData);
break;
case MAVLINK_MSG_ID_GPS_DATE_TIME: //179
mavlink_msg_gps_date_time_decode(&message,&mlGpsDateTime);
break;
case MAVLINK_MSG_ID_MID_LVL_CMDS: //180
break;
case MAVLINK_MSG_ID_CTRL_SRFC_PT: //181
break;
case MAVLINK_MSG_ID_PID: //182
memset(&mlSinglePid,0,sizeof(mavlink_pid_t));
mavlink_msg_pid_decode(&message, &mlSinglePid);
// qDebug() << "\nSLUGS RECEIVED PID Message = "<<mlSinglePid.idx;
emit slugsPidValues(uasId, mlSinglePid);
break;
case MAVLINK_MSG_ID_SLUGS_ACTION: //183
break;
#endif
default:
// qDebug() << "\nSLUGS RECEIVED MESSAGE WITH ID" << message.msgid;
break;
}
}
}
void SlugsMAV::emitSignals (void){
#ifdef MAVLINK_ENABLED_SLUGS
switch(updateRoundRobin){
case 1:
emit slugsCPULoad(uasId, mlCpuLoadData);
emit slugsSensorBias(uasId,mlSensorBiasData);
break;
case 2:
emit slugsAirData(uasId, mlAirData);
emit slugsDiagnostic(uasId,mlDiagnosticData);
break;
case 3:
emit remoteControlChannelScaledChanged(0,(mlPilotConsoleData.de- 1000.0f)/1000.0f);
emit remoteControlChannelScaledChanged(1,(mlPilotConsoleData.dla- 1000.0f)/1000.0f);
emit remoteControlChannelScaledChanged(2,(mlPilotConsoleData.dr- 1000.0f)/1000.0f);
emit remoteControlChannelScaledChanged(3,(mlPilotConsoleData.dra- 1000.0f)/1000.0f);
emit slugsPWM(uasId, mlPwmCommands);
break;
case 4:
emit slugsNavegation(uasId, mlNavigation);
emit slugsDataLog(uasId, mlDataLog);
break;
case 5:
emit slugsFilteredData(uasId,mlFilteredData);
emit slugsGPSDateTime(uasId, mlGpsDateTime);
break;
case 6:
emit slugsActionAck(uasId,mlActionAck);
emit emitGpsSignals();
break;
}
emit slugsAttitude(uasId, mlAttitude);
emit attitudeChanged(this,
mlAttitude.roll,
mlAttitude.pitch,
mlAttitude.yaw,
0.0);
#endif
emit slugsRawImu(uasId, mlRawImuData);
// wrap around
updateRoundRobin = updateRoundRobin > 10? 1: updateRoundRobin + 1;
}
#ifdef MAVLINK_ENABLED_SLUGS
void SlugsMAV::emitGpsSignals (void){
// qDebug()<<"After Emit GPS Signal"<<mlGpsData.fix_type;
//ToDo Uncomment if. it was comment only to test
// if (mlGpsData.fix_type > 0){
emit globalPositionChanged(this,
mlGpsData.lon,
mlGpsData.lat,
mlGpsData.alt,
0.0);
emit slugsGPSCogSog(uasId,mlGpsData.hdg, mlGpsData.v);
// // Smaller than threshold and not NaN
// if (mlGpsData.v < 1000000 && mlGpsData.v == mlGpsData.v){
// // emit speedChanged(this, (double)mlGpsData.v, 0.0, 0.0, 0.0);
// }
// else {
// emit textMessageReceived(uasId, uasId, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(mlGpsData.v));
// }
//}
}
void SlugsMAV::emitPidSignal()
{
// qDebug() << "\nSLUGS RECEIVED PID Message";
emit slugsPidValues(uasId, mlSinglePid);
}
mavlink_pwm_commands_t* SlugsMAV::getPwmCommands()
{
return &mlPwmCommands;
}
#endif // MAVLINK_ENABLED_SLUGS
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef SLUGSMAV_H
#define SLUGSMAV_H
#include "UAS.h"
#include "mavlink.h"
#include <QTimer>
#define SLUGS_UPDATE_RATE 100 // in ms
class SlugsMAV : public UAS
{
Q_OBJECT
Q_INTERFACES(UASInterface)
public:
SlugsMAV(MAVLinkProtocol* mavlink, int id = 0);
public slots:
/** @brief Receive a MAVLink message from this MAV */
void receiveMessage(LinkInterface* link, mavlink_message_t message);
void emitSignals (void);
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_pwm_commands_t* getPwmCommands();
#endif
signals:
void slugsRawImu(int uasId, const mavlink_raw_imu_t& rawData);
void slugsGPSCogSog(int uasId, double cog, double sog);
#ifdef MAVLINK_ENABLED_SLUGS
void slugsCPULoad(int systemId, const mavlink_cpu_load_t& cpuLoad);
void slugsAirData(int systemId, const mavlink_air_data_t& airData);
void slugsSensorBias(int systemId, const mavlink_sensor_bias_t& sensorBias);
void slugsDiagnostic(int systemId, const mavlink_diagnostic_t& diagnostic);
void slugsPilotConsolePWM(int systemId, const mavlink_pilot_console_t& pilotConsole);
void slugsPWM(int systemId, const mavlink_pwm_commands_t& pwmCommands);
void slugsNavegation(int systemId, const mavlink_slugs_navigation_t& slugsNavigation);
void slugsDataLog(int systemId, const mavlink_data_log_t& dataLog);
void slugsFilteredData(int systemId, const mavlink_filtered_data_t& filteredData);
void slugsGPSDateTime(int systemId, const mavlink_gps_date_time_t& gpsDateTime);
void slugsActionAck(int systemId, const mavlink_action_ack_t& actionAck);
void slugsPidValues(int systemId, const mavlink_pid_t& pidValues);
void slugsBootMsg(int uasId, mavlink_boot_t& boot);
void slugsAttitude(int uasId, mavlink_attitude_t& attitude);
#endif
protected:
typedef struct _mavlink_pid_values_t {
float P[11];
float I[11];
float D[11];
}mavlink_pid_values_t;
unsigned char updateRoundRobin;
QTimer* widgetTimer;
mavlink_raw_imu_t mlRawImuData;
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_gps_raw_t mlGpsData;
mavlink_attitude_t mlAttitude;
mavlink_cpu_load_t mlCpuLoadData;
mavlink_air_data_t mlAirData;
mavlink_sensor_bias_t mlSensorBiasData;
mavlink_diagnostic_t mlDiagnosticData;
mavlink_pilot_console_t mlPilotConsoleData;
mavlink_filtered_data_t mlFilteredData;
mavlink_boot_t mlBoot;
mavlink_gps_date_time_t mlGpsDateTime;
mavlink_mid_lvl_cmds_t mlMidLevelCommands;
mavlink_set_mode_t mlApMode;
mavlink_pwm_commands_t mlPwmCommands;
mavlink_pid_values_t mlPidValues;
mavlink_pid_t mlSinglePid;
mavlink_slugs_navigation_t mlNavigation;
mavlink_data_log_t mlDataLog;
mavlink_ctrl_srfc_pt_t mlPassthrough;
mavlink_action_ack_t mlActionAck;
mavlink_slugs_action_t mlAction;
// Standart messages MAVLINK used by SLUGS
private:
void emitGpsSignals (void);
void emitPidSignal(void);
int uasId;
#endif // if SLUGS
};
#endif // SLUGSMAV_H
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef SLUGSMAV_H
#define SLUGSMAV_H
#include "UAS.h"
#include "mavlink.h"
#include <QTimer>
#define SLUGS_UPDATE_RATE 100 // in ms
class SlugsMAV : public UAS
{
Q_OBJECT
Q_INTERFACES(UASInterface)
public:
SlugsMAV(MAVLinkProtocol* mavlink, int id = 0);
public slots:
/** @brief Receive a MAVLink message from this MAV */
void receiveMessage(LinkInterface* link, mavlink_message_t message);
void emitSignals (void);
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_pwm_commands_t* getPwmCommands();
#endif
signals:
void slugsRawImu(int uasId, const mavlink_raw_imu_t& rawData);
void slugsGPSCogSog(int uasId, double cog, double sog);
#ifdef MAVLINK_ENABLED_SLUGS
void slugsCPULoad(int systemId, const mavlink_cpu_load_t& cpuLoad);
void slugsAirData(int systemId, const mavlink_air_data_t& airData);
void slugsSensorBias(int systemId, const mavlink_sensor_bias_t& sensorBias);
void slugsDiagnostic(int systemId, const mavlink_diagnostic_t& diagnostic);
void slugsPilotConsolePWM(int systemId, const mavlink_pilot_console_t& pilotConsole);
void slugsPWM(int systemId, const mavlink_pwm_commands_t& pwmCommands);
void slugsNavegation(int systemId, const mavlink_slugs_navigation_t& slugsNavigation);
void slugsDataLog(int systemId, const mavlink_data_log_t& dataLog);
void slugsFilteredData(int systemId, const mavlink_filtered_data_t& filteredData);
void slugsGPSDateTime(int systemId, const mavlink_gps_date_time_t& gpsDateTime);
void slugsActionAck(int systemId, const mavlink_action_ack_t& actionAck);
void slugsPidValues(int systemId, const mavlink_pid_t& pidValues);
void slugsBootMsg(int uasId, mavlink_boot_t& boot);
void slugsAttitude(int uasId, mavlink_attitude_t& attitude);
#endif
protected:
typedef struct _mavlink_pid_values_t {
float P[11];
float I[11];
float D[11];
}mavlink_pid_values_t;
unsigned char updateRoundRobin;
QTimer* widgetTimer;
mavlink_raw_imu_t mlRawImuData;
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_gps_raw_t mlGpsData;
mavlink_attitude_t mlAttitude;
mavlink_cpu_load_t mlCpuLoadData;
mavlink_air_data_t mlAirData;
mavlink_sensor_bias_t mlSensorBiasData;
mavlink_diagnostic_t mlDiagnosticData;
mavlink_pilot_console_t mlPilotConsoleData;
mavlink_filtered_data_t mlFilteredData;
mavlink_boot_t mlBoot;
mavlink_gps_date_time_t mlGpsDateTime;
mavlink_mid_lvl_cmds_t mlMidLevelCommands;
mavlink_set_mode_t mlApMode;
mavlink_pwm_commands_t mlPwmCommands;
mavlink_pid_values_t mlPidValues;
mavlink_pid_t mlSinglePid;
mavlink_slugs_navigation_t mlNavigation;
mavlink_data_log_t mlDataLog;
mavlink_ctrl_srfc_pt_t mlPassthrough;
mavlink_action_ack_t mlActionAck;
mavlink_slugs_action_t mlAction;
// Standart messages MAVLINK used by SLUGS
private:
void emitGpsSignals (void);
void emitPidSignal(void);
int uasId;
#endif // if SLUGS
};
#endif // SLUGSMAV_H
......@@ -244,7 +244,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_msg_sys_status_decode(&message, &state);
// FIXME
qDebug() << "1 SYSTEM STATUS:" << state.status;
//qDebug() << "1 SYSTEM STATUS:" << state.status;
QString audiostring = "System " + QString::number(this->getUASID());
QString stateAudio = "";
......@@ -260,12 +260,13 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit statusChanged(this, uasState, stateDescription);
emit statusChanged(this->status);
emit loadChanged(this,state.load/10.0f);
emit valueChanged(uasId, "Load", "%", ((float)state.load)/1000.0f, MG::TIME::getGroundTimeNow());
stateAudio = " changed status to " + uasState;
}
qDebug() << "1 SYSTEM MODE:" << state.mode;
qDebug() << "1 THIS MODE:" << this->mode;
//qDebug() << "1 SYSTEM MODE:" << state.mode;
//qDebug() << "1 THIS MODE:" << this->mode;
if (this->mode != static_cast<unsigned int>(state.mode))
{
modechanged = true;
......@@ -308,7 +309,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit modeChanged(this->getUASID(), mode, "");
qDebug() << "2 SYSTEM MODE:" << mode;
//qDebug() << "2 SYSTEM MODE:" << mode;
modeAudio = " is now in " + mode;
}
......@@ -333,6 +334,16 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// COMMUNICATIONS DROP RATE
emit dropRateChanged(this->getUASID(), state.packet_drop/1000.0f);
//add for development
emit remoteControlRSSIChanged(state.packet_drop/1000.0f);
float en = state.packet_drop/1000.0f;
emit remoteControlChannelRawChanged(0, en);//MAVLINK_MSG_ID_RC_CHANNELS_RAW
emit remoteControlChannelScaledChanged(0, en/100.0f);//MAVLINK_MSG_ID_RC_CHANNELS_SCALED
//qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop;
// AUDIO
......
......@@ -537,30 +537,30 @@ void MainWindow::buildSlugsWidgets()
addToToolsMenu (rcViewDockWidget, tr("Radio Control"), SLOT(showToolWidget(bool)), MENU_RC_VIEW, Qt::BottomDockWidgetArea);
}
// if (!slugsDataWidget)
// {
// // Dialog widgets
// slugsDataWidget = new QDockWidget(tr("Slugs Data"), this);
// slugsDataWidget->setWidget( new SlugsDataSensorView(this));
// slugsDataWidget->setObjectName("SLUGS_DATA_DOCK_WIDGET");
// addToToolsMenu (slugsDataWidget, tr("Telemetry Data"), SLOT(showToolWidget()), MENU_SLUGS_DATA, Qt::RightDockWidgetArea);
// }
if (!slugsDataWidget)
{
// Dialog widgets
slugsDataWidget = new QDockWidget(tr("Slugs Data"), this);
slugsDataWidget->setWidget( new SlugsDataSensorView(this));
slugsDataWidget->setObjectName("SLUGS_DATA_DOCK_WIDGET");
addToToolsMenu (slugsDataWidget, tr("Telemetry Data"), SLOT(showToolWidget(bool)), MENU_SLUGS_DATA, Qt::RightDockWidgetArea);
}
// if (!slugsPIDControlWidget)
// {
// slugsPIDControlWidget = new QDockWidget(tr("Slugs PID Control"), this);
// slugsPIDControlWidget->setWidget(new SlugsPIDControl(this));
// slugsPIDControlWidget->setObjectName("SLUGS_PID_CONTROL_DOCK_WIDGET");
// addToToolsMenu (slugsPIDControlWidget, tr("PID Configuration"), SLOT(showToolWidget()), MENU_SLUGS_PID, Qt::LeftDockWidgetArea);
// }
if (!slugsPIDControlWidget)
{
slugsPIDControlWidget = new QDockWidget(tr("Slugs PID Control"), this);
slugsPIDControlWidget->setWidget(new SlugsPIDControl(this));
slugsPIDControlWidget->setObjectName("SLUGS_PID_CONTROL_DOCK_WIDGET");
addToToolsMenu (slugsPIDControlWidget, tr("PID Configuration"), SLOT(showToolWidget(bool)), MENU_SLUGS_PID, Qt::LeftDockWidgetArea);
}
// if (!slugsHilSimWidget)
// {
// slugsHilSimWidget = new QDockWidget(tr("Slugs Hil Sim"), this);
// slugsHilSimWidget->setWidget( new SlugsHilSim(this));
// slugsHilSimWidget->setObjectName("SLUGS_HIL_SIM_DOCK_WIDGET");
// addToToolsMenu (slugsHilSimWidget, tr("HIL Sim Configuration"), SLOT(showToolWidget()), MENU_SLUGS_HIL, Qt::LeftDockWidgetArea);
// }
if (!slugsHilSimWidget)
{
slugsHilSimWidget = new QDockWidget(tr("Slugs Hil Sim"), this);
slugsHilSimWidget->setWidget( new SlugsHilSim(this));
slugsHilSimWidget->setObjectName("SLUGS_HIL_SIM_DOCK_WIDGET");
addToToolsMenu (slugsHilSimWidget, tr("HIL Sim Configuration"), SLOT(showToolWidget(bool)), MENU_SLUGS_HIL, Qt::LeftDockWidgetArea);
}
// if (!slugsCamControlWidget)
// {
......@@ -1024,7 +1024,10 @@ void MainWindow::connectSlugsWidgets()
slugsDataWidget->widget(), SLOT(setActiveUAS(UASInterface*)));
}
if (slugsPIDControlWidget && slugsPIDControlWidget->widget()){
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
slugsPIDControlWidget->widget(), SLOT(activeUasSet(UASInterface*)));
}
}
void MainWindow::arrangeCommonCenterStack()
......@@ -1547,6 +1550,15 @@ void MainWindow::UASCreated(UASInterface* uas)
// Connect Slugs Actions
connectSlugsActions();
// if(slugsDataWidget)
// {
// SlugsDataSensorView *mm = dynamic_cast<SlugsDataSensorView*>(slugsDataWidget->widget());
// if(mm)
// {
// mm->addUAS(uas);
// }
// }
// FIXME: This type checking might be redundant
// // if (slugsDataWidget) {
// // SlugsDataSensorView* dataWidget = dynamic_cast<SlugsDataSensorView*>(slugsDataWidget->widget());
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Implementation of QGCRemoteControlView
* @author Lorenz Meier <mail@qgroundcontrol.org>
* @author Bryan Godbolt <godbolt@ece.ualberta.ca>
*/
#include <QGridLayout>
#include <QVBoxLayout>
#include <QHBoxLayout>
#include <QPushButton>
#include <QLabel>
#include <QProgressBar>
#include "QGCRemoteControlView.h"
#include "ui_QGCRemoteControlView.h"
#include "UASManager.h"
QGCRemoteControlView::QGCRemoteControlView(QWidget *parent) :
QWidget(parent),
uasId(-1),
rssi(0.0f),
updated(false),
channelLayout(new QVBoxLayout()),
ui(new Ui::QGCRemoteControlView)
{
//ui->setupUi(this);
QGridLayout* layout = new QGridLayout(this);
layout->addLayout(channelLayout, 1, 0, 1, 2);
// Name label
nameLabel = new QLabel(this);
nameLabel->setText("No MAV selected yet..");
layout->addWidget(nameLabel, 0, 0, 1, 2);
// RSSI bar
// Create new layout
QHBoxLayout* rssiLayout = new QHBoxLayout();
rssiLayout->setSpacing(5);
// Add content
rssiLayout->addWidget(new QLabel(tr("Signal"), this));
// Append raw label
// Append progress bar
rssiBar = new QProgressBar(this);
rssiBar->setMinimum(0);
rssiBar->setMaximum(100);
rssiBar->setValue(0);
rssiLayout->addWidget(rssiBar);
layout->addItem(rssiLayout, 2, 0, 1, 2);
setVisible(false);
calibrate = new QPushButton(tr("Calibrate"), this);
QHBoxLayout *calibrateButtonLayout = new QHBoxLayout();
calibrateButtonLayout->addWidget(calibrate, 0, Qt::AlignHCenter);
layout->addItem(calibrateButtonLayout, 3, 0, 1, 2);
calibrationWindow = new RadioCalibrationWindow(this);
connect(calibrate, SIGNAL(clicked()), calibrationWindow, SLOT(show()));
connect(UASManager::instance(), SIGNAL(activeUASSet(int)), this, SLOT(setUASId(int)));
}
QGCRemoteControlView::~QGCRemoteControlView()
{
delete ui;
delete channelLayout;
}
void QGCRemoteControlView::setUASId(int id)
{
if (uasId != -1)
{
UASInterface* uas = UASManager::instance()->getUASForId(id);
if (uas)
{
// The UAS exists, disconnect any existing connections
disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float,float)), this, SLOT(setChannel(int,float,float)));
disconnect(uas, SIGNAL(remoteControlRSSIRawChanged(float)), this, SLOT(setRemoteRSSI(float)));
disconnect(uas, SIGNAL(radioCalibrationRawReceived(const QPointer<RadioCalibrationData>)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&)));
disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannelRaw(int,float)));
disconnect(uas, SIGNAL(remoteControlChannelScaledChanged(int,float,float)), calibrationWindow, SLOT(setChannelScaled(int,float)));
}
}
// Connect the new UAS
UASInterface* newUAS = UASManager::instance()->getUASForId(id);
if (newUAS)
{
// New UAS exists, connect
nameLabel->setText(QString("RC Input of %1").arg(newUAS->getUASName()));
calibrationWindow->setUASId(id);
connect(newUAS, SIGNAL(radioCalibrationReceived(const QPointer<RadioCalibrationData>&)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&)));
connect(newUAS, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float)));
connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(setChannelRaw(int,float)));
// connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannelRaw(int,float)));
connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), this, SLOT(setChannelScaled(int,float)));
// connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), calibrationWindow, SLOT(setChannelScaled(int,float)));
}
}
void QGCRemoteControlView::setChannelRaw(int channelId, float raw)
{
if (this->raw.size() <= channelId)
{
// This is a new channel, append it
this->raw.append(raw);
this->normalized.append(0);
appendChannelWidget(channelId);
}
else
{
// This is an existing channel, aupdate it
this->raw[channelId] = raw;
}
updated = true;
// FIXME Will be timer based in the future
redraw();
}
void QGCRemoteControlView::setChannelScaled(int channelId, float normalized)
{
if (this->raw.size() <= channelId) // using raw vector as size indicator
{
// This is a new channel, append it
this->normalized.append(normalized);
this->raw.append(0);
appendChannelWidget(channelId);
}
else
{
// This is an existing channel, update it
this->normalized[channelId] = normalized;
}
updated = true;
// FIXME Will be timer based in the future
redraw();
}
void QGCRemoteControlView::setRemoteRSSI(float rssiNormalized)
{
rssi = rssiNormalized;
updated = true;
}
void QGCRemoteControlView::appendChannelWidget(int channelId)
{
// Create new layout
QHBoxLayout* layout = new QHBoxLayout();
// Add content
layout->addWidget(new QLabel(QString("Channel %1").arg(channelId + 1), this));
QLabel* raw = new QLabel(this);
// Append raw label
rawLabels.append(raw);
layout->addWidget(raw);
// Append progress bar
QProgressBar* normalized = new QProgressBar(this);
normalized->setMinimum(-100);
normalized->setMaximum(100);
normalized->setFormat("%v%");
progressBars.append(normalized);
layout->addWidget(normalized);
channelLayout->addLayout(layout);
}
void QGCRemoteControlView::redraw()
{
if(isVisible() && updated)
{
// Update raw values
for(int i = 0; i < rawLabels.count(); i++)
{
rawLabels.at(i)->setText(QString("%1 us").arg(raw.at(i), 4, 10, QChar('0')));
}
// Update percent bars
for(int i = 0; i < progressBars.count(); i++)
{
progressBars.at(i)->setValue(normalized.at(i)*100.0f);
}
updated = false;
}
}
void QGCRemoteControlView::changeEvent(QEvent *e)
{
Q_UNUSED(e);
// FIXME If the lines below are commented in
// runtime errors can occur on x64 systems.
// QWidget::changeEvent(e);
// switch (e->type()) {
// case QEvent::LanguageChange:
// //ui->retranslateUi(this);
// break;
// default:
// break;
// }
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Implementation of QGCRemoteControlView
* @author Lorenz Meier <mail@qgroundcontrol.org>
* @author Bryan Godbolt <godbolt@ece.ualberta.ca>
*/
#include <QGridLayout>
#include <QVBoxLayout>
#include <QHBoxLayout>
#include <QPushButton>
#include <QLabel>
#include <QProgressBar>
#include "QGCRemoteControlView.h"
#include "ui_QGCRemoteControlView.h"
#include "UASManager.h"
QGCRemoteControlView::QGCRemoteControlView(QWidget *parent) :
QWidget(parent),
uasId(-1),
rssi(0.0f),
updated(false),
channelLayout(new QVBoxLayout())//,
//ui(new Ui::QGCRemoteControlView)
{
ui->setupUi(this);
QGridLayout* layout = new QGridLayout(this);
layout->addLayout(channelLayout, 1, 0, 1, 2);
nameLabel = new QLabel(this);
layout->addWidget(nameLabel, 0, 0, 1, 2);
this->setVisible(false);
//setVisible(false);
calibrate = new QPushButton(tr("Calibrate"), this);
QHBoxLayout *calibrateButtonLayout = new QHBoxLayout();
calibrateButtonLayout->addWidget(calibrate, 0, Qt::AlignHCenter);
layout->addItem(calibrateButtonLayout, 3, 0, 1, 2);
calibrationWindow = new RadioCalibrationWindow(this);
connect(calibrate, SIGNAL(clicked()), calibrationWindow, SLOT(show()));
connect(UASManager::instance(), SIGNAL(activeUASSet(int)), this, SLOT(setUASId(int)));
}
QGCRemoteControlView::~QGCRemoteControlView()
{
delete ui;
delete channelLayout;
}
void QGCRemoteControlView::setUASId(int id)
{
if (uasId != -1)
{
UASInterface* uas = UASManager::instance()->getUASForId(id);
if (uas)
{
// The UAS exists, disconnect any existing connections
disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float,float)), this, SLOT(setChannel(int,float,float)));
disconnect(uas, SIGNAL(remoteControlRSSIRawChanged(float)), this, SLOT(setRemoteRSSI(float)));
disconnect(uas, SIGNAL(radioCalibrationRawReceived(const QPointer<RadioCalibrationData>)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&)));
disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannelRaw(int,float)));
disconnect(uas, SIGNAL(remoteControlChannelScaledChanged(int,float,float)), calibrationWindow, SLOT(setChannelScaled(int,float)));
}
}
// Connect the new UAS
UASInterface* newUAS = UASManager::instance()->getUASForId(id);
if (newUAS)
{
// New UAS exists, connect
nameLabel->setText(QString("RC Input of %1").arg(newUAS->getUASName()));
calibrationWindow->setUASId(id);
connect(newUAS, SIGNAL(radioCalibrationReceived(const QPointer<RadioCalibrationData>&)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&)));
connect(newUAS, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float)));
connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(setChannelRaw(int,float)));
//now comment//connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannelRaw(int,float)));
//connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), this, SLOT(setChannelScaled(int,float)));
//now comment//connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), calibrationWindow, SLOT(setChannelScaled(int,float)));
}
}
void QGCRemoteControlView::setChannelRaw(int channelId, float raw)
{
if (this->raw.size() <= channelId)
{
// This is a new channel, append it
this->raw.append(raw);
//this->normalized.append(0);
appendChannelWidget(channelId);
}
else
{
// This is an existing channel, aupdate it
this->raw[channelId] = raw;
}
updated = true;
// FIXME Will be timer based in the future
redraw();
}
//void QGCRemoteControlView::setChannelScaled(int channelId, float normalized)
//{
// if (this->raw.size() <= channelId) // using raw vector as size indicator
// {
// // This is a new channel, append it
// this->normalized.append(normalized);
// this->raw.append(0);
// appendChannelWidget(channelId);
// }
// else
// {
// // This is an existing channel, update it
// this->normalized[channelId] = normalized;
// }
// updated = true;
// // FIXME Will be timer based in the future
// redraw();
//}
void QGCRemoteControlView::setRemoteRSSI(float rssiNormalized)
{
rssi = rssiNormalized;
updated = true;
}
void QGCRemoteControlView::appendChannelWidget(int channelId)
{
// Create new layout
QHBoxLayout* layout = new QHBoxLayout();
// Add content
layout->addWidget(new QLabel(QString("Channel %1").arg(channelId + 1), this));
QLabel* raw = new QLabel(this);
// Append raw label
rawLabels.append(raw);
layout->addWidget(raw);
// Append progress bar
QProgressBar* normalized = new QProgressBar(this);
normalized->setMinimum(-100);
normalized->setMaximum(100);
normalized->setFormat("%v%");
progressBars.append(normalized);
layout->addWidget(normalized);
channelLayout->addLayout(layout);
}
void QGCRemoteControlView::redraw()
{
if(isVisible() && updated)
{
// Update raw values
//for(int i = 0; i < rawLabels.count(); i++)
//{
//rawLabels.at(i)->setText(QString("%1 us").arg(raw.at(i), 4, 10, QChar('0')));
//}
// Update percent bars
for(int i = 0; i < progressBars.count(); i++)
{
rawLabels.at(i)->setText(QString("%1 us").arg(raw.at(i), 4, 10, QChar('0')));
//int vv = normalized.at(i)*100.0f;
//progressBars.at(i)->setValue(vv);
int vv = raw.at(i)*1.0f;
progressBars.at(i)->setValue(vv);
}
updated = false;
}
}
void QGCRemoteControlView::changeEvent(QEvent *e)
{
Q_UNUSED(e);
// FIXME If the lines below are commented in
// runtime errors can occur on x64 systems.
// QWidget::changeEvent(e);
// switch (e->type()) {
// case QEvent::LanguageChange:
// //ui->retranslateUi(this);
// break;
// default:
// break;
// }
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Declaration of QGCRemoteControlView
* @author Lorenz Meier <mail@qgroundcontrol.org>
*/
#ifndef QGCREMOTECONTROLVIEW_H
#define QGCREMOTECONTROLVIEW_H
#include <QWidget>
#include <QVector>
#include <QPushButton>
#include "RadioCalibration/RadioCalibrationWindow.h"
namespace Ui {
class QGCRemoteControlView;
}
class QVBoxLayout;
class QLabel;
class QProgressBar;
class QGCRemoteControlView : public QWidget {
Q_OBJECT
public:
QGCRemoteControlView(QWidget *parent = 0);
~QGCRemoteControlView();
public slots:
void setUASId(int id);
void setChannelRaw(int channelId, float raw);
void setChannelScaled(int channelId, float normalized);
void setRemoteRSSI(float rssiNormalized);
void redraw();
protected slots:
void appendChannelWidget(int channelId);
protected:
void changeEvent(QEvent *e);
int uasId;
float rssi;
bool updated;
QVBoxLayout* channelLayout;
QVector<int> raw;
QVector<float> normalized;
QVector<QLabel*> rawLabels;
QVector<QProgressBar*> progressBars;
QProgressBar* rssiBar;
QLabel* nameLabel;
QPushButton *calibrate;
RadioCalibrationWindow *calibrationWindow;
private:
Ui::QGCRemoteControlView *ui;
};
#endif // QGCREMOTECONTROLVIEW_H
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Declaration of QGCRemoteControlView
* @author Lorenz Meier <mail@qgroundcontrol.org>
*/
#ifndef QGCREMOTECONTROLVIEW_H
#define QGCREMOTECONTROLVIEW_H
#include <QWidget>
#include <QVector>
#include <QPushButton>
#include "RadioCalibration/RadioCalibrationWindow.h"
namespace Ui {
class QGCRemoteControlView;
}
class QVBoxLayout;
class QLabel;
class QProgressBar;
class QGCRemoteControlView : public QWidget {
Q_OBJECT
public:
QGCRemoteControlView(QWidget *parent = 0);
~QGCRemoteControlView();
public slots:
void setUASId(int id);
void setChannelRaw(int channelId, float raw);
//void setChannelScaled(int channelId, float normalized);
void setRemoteRSSI(float rssiNormalized);
void redraw();
protected slots:
void appendChannelWidget(int channelId);
protected:
void changeEvent(QEvent *e);
int uasId;
float rssi;
bool updated;
QVBoxLayout* channelLayout;
QVector<int> raw;
QVector<float> normalized;
QVector<QLabel*> rawLabels;
QVector<QProgressBar*> progressBars;
QProgressBar* rssiBar;
QLabel* nameLabel;
QPushButton *calibrate;
RadioCalibrationWindow *calibrationWindow;
private:
Ui::QGCRemoteControlView *ui;
};
#endif // QGCREMOTECONTROLVIEW_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCRemoteControlView</class>
<widget class="QWidget" name="QGCRemoteControlView">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>400</width>
<height>300</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<widget class="QPushButton" name="pushButton">
<property name="geometry">
<rect>
<x>300</x>
<y>260</y>
<width>93</width>
<height>27</height>
</rect>
</property>
<property name="text">
<string>Calibrate</string>
</property>
</widget>
<widget class="QLabel" name="label">
<property name="geometry">
<rect>
<x>10</x>
<y>270</y>
<width>171</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>Remote Control detected</string>
</property>
</widget>
<widget class="QLabel" name="label_2">
<property name="geometry">
<rect>
<x>10</x>
<y>10</y>
<width>71</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>Channel 1</string>
</property>
</widget>
<widget class="QLabel" name="label_3">
<property name="geometry">
<rect>
<x>10</x>
<y>30</y>
<width>71</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>Channel 2</string>
</property>
</widget>
<widget class="QLabel" name="label_4">
<property name="geometry">
<rect>
<x>10</x>
<y>50</y>
<width>71</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>Channel 3</string>
</property>
</widget>
<widget class="QLabel" name="label_5">
<property name="geometry">
<rect>
<x>10</x>
<y>70</y>
<width>71</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>Channel 4</string>
</property>
</widget>
<widget class="QLabel" name="label_6">
<property name="geometry">
<rect>
<x>10</x>
<y>90</y>
<width>71</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>Channel 5</string>
</property>
</widget>
<widget class="QLabel" name="label_7">
<property name="geometry">
<rect>
<x>10</x>
<y>110</y>
<width>71</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>Channel 6</string>
</property>
</widget>
<widget class="QLabel" name="label_8">
<property name="geometry">
<rect>
<x>10</x>
<y>130</y>
<width>71</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>Channel 7</string>
</property>
</widget>
<widget class="QLabel" name="label_9">
<property name="geometry">
<rect>
<x>10</x>
<y>150</y>
<width>71</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>Channel 8</string>
</property>
</widget>
<widget class="QLabel" name="label_10">
<property name="geometry">
<rect>
<x>10</x>
<y>170</y>
<width>62</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>RSSI</string>
</property>
</widget>
<widget class="QProgressBar" name="chan1ProgressBar">
<property name="geometry">
<rect>
<x>200</x>
<y>10</y>
<width>118</width>
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>0</number>
</property>
<property name="textVisible">
<bool>true</bool>
</property>
<property name="invertedAppearance">
<bool>false</bool>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan2ProgressBar">
<property name="geometry">
<rect>
<x>200</x>
<y>30</y>
<width>118</width>
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan3ProgressBar">
<property name="geometry">
<rect>
<x>200</x>
<y>50</y>
<width>118</width>
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan4ProgressBar">
<property name="geometry">
<rect>
<x>200</x>
<y>70</y>
<width>118</width>
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan5ProgressBar">
<property name="geometry">
<rect>
<x>200</x>
<y>90</y>
<width>118</width>
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan6ProgressBar">
<property name="geometry">
<rect>
<x>200</x>
<y>110</y>
<width>118</width>
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan7ProgressBar">
<property name="geometry">
<rect>
<x>200</x>
<y>130</y>
<width>118</width>
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan8ProgressBar">
<property name="geometry">
<rect>
<x>200</x>
<y>150</y>
<width>118</width>
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QLabel" name="label_11">
<property name="geometry">
<rect>
<x>90</x>
<y>10</y>
<width>41</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>1120</string>
</property>
</widget>
</widget>
<resources/>
<connections/>
</ui>
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCRemoteControlView</class>
<widget class="QWidget" name="QGCRemoteControlView">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>155</width>
<height>106</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
</widget>
<resources/>
<connections/>
</ui>
#include "SlugsDataSensorView.h"
#include "ui_SlugsDataSensorView.h"
#include <UASManager.h>
#include "SlugsMAV.h"
#include <QDebug>
SlugsDataSensorView::SlugsDataSensorView(QWidget *parent) :
QWidget(parent),
ui(new Ui::SlugsDataSensorView)
{
ui->setupUi(this);
activeUAS = NULL;
this->setVisible(false);
}
SlugsDataSensorView::~SlugsDataSensorView()
{
delete ui;
}
void SlugsDataSensorView::addUAS(UASInterface* uas)
{
SlugsMAV* slugsMav = qobject_cast<SlugsMAV*>(uas);
if (slugsMav != NULL) {
connect(slugsMav, SIGNAL(slugsRawImu(int, const mavlink_raw_imu_t&)), this, SLOT(slugRawDataChanged(int, const mavlink_raw_imu_t&)));
#ifdef MAVLINK_ENABLED_SLUGS
//connect standar messages
connect(slugsMav, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugLocalPositionChanged(UASInterface*,double,double,double,quint64)));
connect(slugsMav, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugSpeedLocalPositionChanged(UASInterface*,double,double,double,quint64)));
connect(slugsMav, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugAttitudeChanged(UASInterface*,double,double,double,quint64)));
connect(slugsMav, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugsGlobalPositionChanged(UASInterface*,double,double,double,quint64)));
connect(slugsMav,SIGNAL(slugsGPSCogSog(int,double,double)),this,SLOT(slugsGPSCogSog(int,double,double)));
//connect slugs especial messages
connect(slugsMav, SIGNAL(slugsSensorBias(int,const mavlink_sensor_bias_t&)), this, SLOT(slugsSensorBiasChanged(int,const mavlink_sensor_bias_t&)));
connect(slugsMav, SIGNAL(slugsDiagnostic(int,const mavlink_diagnostic_t&)), this, SLOT(slugsDiagnosticMessageChanged(int,const mavlink_diagnostic_t&)));
connect(slugsMav, SIGNAL(slugsCPULoad(int,const mavlink_cpu_load_t&)), this, SLOT(slugsCpuLoadChanged(int,const mavlink_cpu_load_t&)));
connect(slugsMav, SIGNAL(slugsNavegation(int,const mavlink_slugs_navigation_t&)),this,SLOT(slugsNavegationChanged(int,const mavlink_slugs_navigation_t&)));
connect(slugsMav, SIGNAL(slugsDataLog(int,const mavlink_data_log_t&)), this, SLOT(slugsDataLogChanged(int,const mavlink_data_log_t&)));
connect(slugsMav, SIGNAL(slugsPWM(int,const mavlink_pwm_commands_t&)),this,SLOT(slugsPWMChanged(int,const mavlink_pwm_commands_t&)));
connect(slugsMav, SIGNAL(slugsFilteredData(int,const mavlink_filtered_data_t&)),this,SLOT(slugsFilteredDataChanged(int,const mavlink_filtered_data_t&)));
connect(slugsMav, SIGNAL(slugsGPSDateTime(int,const mavlink_gps_date_time_t&)),this,SLOT(slugsGPSDateTimeChanged(int,const mavlink_gps_date_time_t&)));
connect(slugsMav,SIGNAL(slugsAirData(int, const mavlink_air_data_t&)),this,SLOT(slugsAirDataChanged(int, const mavlink_air_data_t&)));
#endif // MAVLINK_ENABLED_SLUGS
// Set this UAS as active if it is the first one
if(activeUAS == 0) {
activeUAS = uas;
}
}
}
void SlugsDataSensorView::slugRawDataChanged(int uasId, const mavlink_raw_imu_t &rawData){
Q_UNUSED(uasId);
ui->m_Axr->setText(QString::number(rawData.xacc));
ui->m_Ayr->setText(QString::number(rawData.yacc));
ui->m_Azr->setText(QString::number(rawData.zacc));
ui->m_Mxr->setText(QString::number(rawData.xmag));
ui->m_Myr->setText(QString::number(rawData.ymag));
ui->m_Mzr->setText(QString::number(rawData.zmag));
ui->m_Gxr->setText(QString::number(rawData.xgyro));
ui->m_Gyr->setText(QString::number(rawData.ygyro));
ui->m_Gzr->setText(QString::number(rawData.zgyro));
}
void SlugsDataSensorView::setActiveUAS(UASInterface* uas){
activeUAS = uas;
}
#ifdef MAVLINK_ENABLED_SLUGS
void SlugsDataSensorView::slugsGlobalPositionChanged(UASInterface *uas,
double lat,
double lon,
double alt,
quint64 time) {
Q_UNUSED(uas);
Q_UNUSED(time);
ui->m_GpsLatitude->setText(QString::number(lat));
ui->m_GpsLongitude->setText(QString::number(lon));
ui->m_GpsHeight->setText(QString::number(alt));
//qDebug()<<"GPS Position = "<<lat<<" - "<<lon<<" - "<<alt;
}
void SlugsDataSensorView::slugLocalPositionChanged(UASInterface* uas,
double x,
double y,
double z,
quint64 time) {
Q_UNUSED(uas);
Q_UNUSED(time);
ui->ed_x->setPlainText(QString::number(x));
ui->ed_y->setPlainText(QString::number(y));
ui->ed_z->setPlainText(QString::number(z));
//qDebug()<<"Local Position = "<<x<<" - "<<y<<" - "<<z;
}
void SlugsDataSensorView::slugSpeedLocalPositionChanged(UASInterface* uas,
double vx,
double vy,
double vz,
quint64 time) {
Q_UNUSED( uas);
Q_UNUSED(time);
ui->ed_vx->setPlainText(QString::number(vx));
ui->ed_vy->setPlainText(QString::number(vy));
ui->ed_vz->setPlainText(QString::number(vz));
//qDebug()<<"Speed Local Position = "<<vx<<" - "<<vy<<" - "<<vz;
}
void SlugsDataSensorView::slugAttitudeChanged(UASInterface* uas,
double slugroll,
double slugpitch,
double slugyaw,
quint64 time)
{
Q_UNUSED( uas);
Q_UNUSED(time);
ui->m_Roll->setPlainText(QString::number(slugroll));
ui->m_Pitch->setPlainText(QString::number(slugpitch));
ui->m_Yaw->setPlainText(QString::number(slugyaw));
// qDebug()<<"Attitude change = "<<slugroll<<" - "<<slugpitch<<" - "<<slugyaw;
}
void SlugsDataSensorView::slugsSensorBiasChanged(int systemId,
const mavlink_sensor_bias_t& sensorBias){
Q_UNUSED( systemId);
ui->m_AxBiases->setText(QString::number(sensorBias.axBias));
ui->m_AyBiases->setText(QString::number(sensorBias.ayBias));
ui->m_AzBiases->setText(QString::number(sensorBias.azBias));
ui->m_GxBiases->setText(QString::number(sensorBias.gxBias));
ui->m_GyBiases->setText(QString::number(sensorBias.gyBias));
ui->m_GzBiases->setText(QString::number(sensorBias.gzBias));
}
void SlugsDataSensorView::slugsDiagnosticMessageChanged(int systemId,
const mavlink_diagnostic_t& diagnostic){
Q_UNUSED(systemId);
ui->m_Fl1->setText(QString::number(diagnostic.diagFl1));
ui->m_Fl2->setText(QString::number(diagnostic.diagFl2));
ui->m_Fl3->setText(QString::number(diagnostic.diagFl2));
ui->m_Sh1->setText(QString::number(diagnostic.diagSh1));
ui->m_Sh2->setText(QString::number(diagnostic.diagSh2));
ui->m_Sh3->setText(QString::number(diagnostic.diagSh3));
}
void SlugsDataSensorView::slugsCpuLoadChanged(int systemId,
const mavlink_cpu_load_t& cpuLoad){
Q_UNUSED(systemId);
ui->ed_sens->setText(QString::number(cpuLoad.sensLoad));
ui->ed_control->setText(QString::number(cpuLoad.ctrlLoad));
ui->ed_batvolt->setText(QString::number(cpuLoad.batVolt));
}
void SlugsDataSensorView::slugsNavegationChanged(int systemId,
const mavlink_slugs_navigation_t& slugsNavigation){
Q_UNUSED(systemId);
ui->m_Um->setText(QString::number(slugsNavigation.u_m));
ui->m_PhiC->setText(QString::number(slugsNavigation.phi_c));
ui->m_PitchC->setText(QString::number(slugsNavigation.theta_c));
ui->m_PsidC->setText(QString::number(slugsNavigation.psiDot_c));
ui->m_AyBody->setText(QString::number(slugsNavigation.ay_body));
ui->m_TotRun->setText(QString::number(slugsNavigation.totalDist));
ui->m_DistToGo->setText(QString::number(slugsNavigation.dist2Go));
ui->m_FromWP->setText(QString::number(slugsNavigation.fromWP));
ui->m_ToWP->setText(QString::number(slugsNavigation.toWP));
}
void SlugsDataSensorView::slugsDataLogChanged(int systemId,
const mavlink_data_log_t& dataLog){
Q_UNUSED(systemId);
ui->m_logFl1->setText(QString::number(dataLog.fl_1));
ui->m_logFl2->setText(QString::number(dataLog.fl_2));
ui->m_logFl3->setText(QString::number(dataLog.fl_3));
ui->m_logFl4->setText(QString::number(dataLog.fl_4));
ui->m_logFl5->setText(QString::number(dataLog.fl_5));
ui->m_logFl6->setText(QString::number(dataLog.fl_6));
}
void SlugsDataSensorView::slugsPWMChanged(int systemId,
const mavlink_pwm_commands_t& pwmCommands){
Q_UNUSED(systemId);
ui->m_pwmThro->setText(QString::number(pwmCommands.dt_c));
ui->m_pwmAile->setText(QString::number(pwmCommands.dla_c));
ui->m_pwmElev->setText(QString::number(pwmCommands.dle_c));
ui->m_pwmRudd->setText(QString::number(pwmCommands.dr_c));
ui->m_pwmThroTrim->setText(QString::number(pwmCommands.dre_c));
ui->m_pwmAileTrim->setText(QString::number(pwmCommands.dlf_c));
ui->m_pwmElevTrim->setText(QString::number(pwmCommands.drf_c));
ui->m_pwmRuddTrim->setText(QString::number(pwmCommands.aux1));
}
void SlugsDataSensorView::slugsFilteredDataChanged(int systemId,
const mavlink_filtered_data_t& filteredData){
Q_UNUSED(systemId);
ui->m_Axf->setText(QString::number(filteredData.aX));
ui->m_Ayf->setText(QString::number(filteredData.aY));
ui->m_Azf->setText(QString::number(filteredData.aZ));
ui->m_Gxf->setText(QString::number(filteredData.gX));
ui->m_Gyf->setText(QString::number(filteredData.gY));
ui->m_Gzf->setText(QString::number(filteredData.gZ));
ui->m_Mxf->setText(QString::number(filteredData.mX));
ui->m_Myf->setText(QString::number(filteredData.mY));
ui->m_Mzf->setText(QString::number(filteredData.mZ));
}
void SlugsDataSensorView::slugsGPSDateTimeChanged(int systemId,
const mavlink_gps_date_time_t& gpsDateTime){
Q_UNUSED(systemId);
QString month, day;
month = QString::number(gpsDateTime.month);
day = QString::number(gpsDateTime.day);
if(gpsDateTime.month < 10) month = "0" + QString::number(gpsDateTime.month);
if(gpsDateTime.day < 10) day = "0" + QString::number(gpsDateTime.day);
ui->m_GpsDate->setText(day + "/" +
month + "/" +
QString::number(gpsDateTime.year));
QString hour, min, sec;
hour = QString::number(gpsDateTime.hour);
min = QString::number(gpsDateTime.min);
sec = QString::number(gpsDateTime.sec);
if(gpsDateTime.hour < 10) hour = "0" + QString::number(gpsDateTime.hour);
if(gpsDateTime.min < 10) min = "0" + QString::number(gpsDateTime.min);
if(gpsDateTime.sec < 10) sec = "0" + QString::number(gpsDateTime.sec);
ui->m_GpsTime->setText(hour + ":" +
min + ":" +
sec);
ui->m_GpsSat->setText(QString::number(gpsDateTime.visSat));
}
/**
* @brief Updates the air data widget - 171
*/
void SlugsDataSensorView::slugsAirDataChanged(int systemId, const mavlink_air_data_t &airData)
{
Q_UNUSED(systemId);
ui->ed_dynamic->setText(QString::number(airData.dynamicPressure));
ui->ed_static->setText(QString::number(airData.staticPressure));
ui->ed_temp->setText(QString::number(airData.temperature));
// qDebug()<<"Air Data = "<<airData.dynamicPressure<<" - "
// <<airData.staticPressure<<" - "
// <<airData.temperature;
}
/**
* @brief set COG and SOG values
*
* COG and SOG GPS display on the Widgets
*/
void SlugsDataSensorView::slugsGPSCogSog(int systemId,
double cog,
double sog)
{
Q_UNUSED(systemId);
ui->m_GpsCog->setText(QString::number(cog));
ui->m_GpsSog->setText(QString::number(sog));
}
#endif // MAVLINK_ENABLED_SLUGS
#include "SlugsDataSensorView.h"
#include "ui_SlugsDataSensorView.h"
#include <UASManager.h>
#include "SlugsMAV.h"
#include <QDebug>
SlugsDataSensorView::SlugsDataSensorView(QWidget *parent) :
QWidget(parent),
ui(new Ui::SlugsDataSensorView)
{
ui->setupUi(this);
activeUAS = NULL;
this->setVisible(false);
}
SlugsDataSensorView::~SlugsDataSensorView()
{
delete ui;
}
void SlugsDataSensorView::addUAS(UASInterface* uas)
{
SlugsMAV* slugsMav = qobject_cast<SlugsMAV*>(uas);
if (slugsMav != NULL) {
connect(slugsMav, SIGNAL(slugsRawImu(int, const mavlink_raw_imu_t&)), this, SLOT(slugRawDataChanged(int, const mavlink_raw_imu_t&)));
#ifdef MAVLINK_ENABLED_SLUGS
//connect standar messages
connect(slugsMav, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugLocalPositionChanged(UASInterface*,double,double,double,quint64)));
connect(slugsMav, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugSpeedLocalPositionChanged(UASInterface*,double,double,double,quint64)));
connect(slugsMav, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugAttitudeChanged(UASInterface*,double,double,double,quint64)));
connect(slugsMav, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugsGlobalPositionChanged(UASInterface*,double,double,double,quint64)));
connect(slugsMav,SIGNAL(slugsGPSCogSog(int,double,double)),this,SLOT(slugsGPSCogSog(int,double,double)));
//connect slugs especial messages
connect(slugsMav, SIGNAL(slugsSensorBias(int,const mavlink_sensor_bias_t&)), this, SLOT(slugsSensorBiasChanged(int,const mavlink_sensor_bias_t&)));
connect(slugsMav, SIGNAL(slugsDiagnostic(int,const mavlink_diagnostic_t&)), this, SLOT(slugsDiagnosticMessageChanged(int,const mavlink_diagnostic_t&)));
connect(slugsMav, SIGNAL(slugsCPULoad(int,const mavlink_cpu_load_t&)), this, SLOT(slugsCpuLoadChanged(int,const mavlink_cpu_load_t&)));
connect(slugsMav, SIGNAL(slugsNavegation(int,const mavlink_slugs_navigation_t&)),this,SLOT(slugsNavegationChanged(int,const mavlink_slugs_navigation_t&)));
connect(slugsMav, SIGNAL(slugsDataLog(int,const mavlink_data_log_t&)), this, SLOT(slugsDataLogChanged(int,const mavlink_data_log_t&)));
connect(slugsMav, SIGNAL(slugsPWM(int,const mavlink_pwm_commands_t&)),this,SLOT(slugsPWMChanged(int,const mavlink_pwm_commands_t&)));
connect(slugsMav, SIGNAL(slugsFilteredData(int,const mavlink_filtered_data_t&)),this,SLOT(slugsFilteredDataChanged(int,const mavlink_filtered_data_t&)));
connect(slugsMav, SIGNAL(slugsGPSDateTime(int,const mavlink_gps_date_time_t&)),this,SLOT(slugsGPSDateTimeChanged(int,const mavlink_gps_date_time_t&)));
connect(slugsMav,SIGNAL(slugsAirData(int, const mavlink_air_data_t&)),this,SLOT(slugsAirDataChanged(int, const mavlink_air_data_t&)));
#endif // MAVLINK_ENABLED_SLUGS
// Set this UAS as active if it is the first one
if(activeUAS == 0) {
activeUAS = uas;
}
}
}
void SlugsDataSensorView::slugRawDataChanged(int uasId, const mavlink_raw_imu_t &rawData){
Q_UNUSED(uasId);
ui->m_Axr->setText(QString::number(rawData.xacc));
ui->m_Ayr->setText(QString::number(rawData.yacc));
ui->m_Azr->setText(QString::number(rawData.zacc));
ui->m_Mxr->setText(QString::number(rawData.xmag));
ui->m_Myr->setText(QString::number(rawData.ymag));
ui->m_Mzr->setText(QString::number(rawData.zmag));
ui->m_Gxr->setText(QString::number(rawData.xgyro));
ui->m_Gyr->setText(QString::number(rawData.ygyro));
ui->m_Gzr->setText(QString::number(rawData.zgyro));
}
void SlugsDataSensorView::setActiveUAS(UASInterface* uas){
activeUAS = uas;
addUAS(activeUAS);
}
#ifdef MAVLINK_ENABLED_SLUGS
void SlugsDataSensorView::slugsGlobalPositionChanged(UASInterface *uas,
double lat,
double lon,
double alt,
quint64 time) {
Q_UNUSED(uas);
Q_UNUSED(time);
ui->m_GpsLatitude->setText(QString::number(lat));
ui->m_GpsLongitude->setText(QString::number(lon));
ui->m_GpsHeight->setText(QString::number(alt));
//qDebug()<<"GPS Position = "<<lat<<" - "<<lon<<" - "<<alt;
}
void SlugsDataSensorView::slugLocalPositionChanged(UASInterface* uas,
double x,
double y,
double z,
quint64 time) {
Q_UNUSED(uas);
Q_UNUSED(time);
ui->ed_x->setText(QString::number(x));
ui->ed_y->setText(QString::number(y));
ui->ed_z->setText(QString::number(z));
//qDebug()<<"Local Position = "<<x<<" - "<<y<<" - "<<z;
}
void SlugsDataSensorView::slugSpeedLocalPositionChanged(UASInterface* uas,
double vx,
double vy,
double vz,
quint64 time) {
Q_UNUSED( uas);
Q_UNUSED(time);
ui->ed_vx->setText(QString::number(vx));
ui->ed_vy->setText(QString::number(vy));
ui->ed_vz->setText(QString::number(vz));
//qDebug()<<"Speed Local Position = "<<vx<<" - "<<vy<<" - "<<vz;
}
void SlugsDataSensorView::slugAttitudeChanged(UASInterface* uas,
double slugroll,
double slugpitch,
double slugyaw,
quint64 time)
{
Q_UNUSED( uas);
Q_UNUSED(time);
ui->m_Roll->setText(QString::number(slugroll));
ui->m_Pitch->setText(QString::number(slugpitch));
ui->m_Yaw->setText(QString::number(slugyaw));
// qDebug()<<"Attitude change = "<<slugroll<<" - "<<slugpitch<<" - "<<slugyaw;
}
void SlugsDataSensorView::slugsSensorBiasChanged(int systemId,
const mavlink_sensor_bias_t& sensorBias){
Q_UNUSED( systemId);
ui->m_AxBiases->setText(QString::number(sensorBias.axBias));
ui->m_AyBiases->setText(QString::number(sensorBias.ayBias));
ui->m_AzBiases->setText(QString::number(sensorBias.azBias));
ui->m_GxBiases->setText(QString::number(sensorBias.gxBias));
ui->m_GyBiases->setText(QString::number(sensorBias.gyBias));
ui->m_GzBiases->setText(QString::number(sensorBias.gzBias));
}
void SlugsDataSensorView::slugsDiagnosticMessageChanged(int systemId,
const mavlink_diagnostic_t& diagnostic){
Q_UNUSED(systemId);
ui->m_Fl1->setText(QString::number(diagnostic.diagFl1));
ui->m_Fl2->setText(QString::number(diagnostic.diagFl2));
ui->m_Fl3->setText(QString::number(diagnostic.diagFl2));
ui->m_Sh1->setText(QString::number(diagnostic.diagSh1));
ui->m_Sh2->setText(QString::number(diagnostic.diagSh2));
ui->m_Sh3->setText(QString::number(diagnostic.diagSh3));
}
void SlugsDataSensorView::slugsCpuLoadChanged(int systemId,
const mavlink_cpu_load_t& cpuLoad){
Q_UNUSED(systemId);
ui->ed_sens->setText(QString::number(cpuLoad.sensLoad));
ui->ed_control->setText(QString::number(cpuLoad.ctrlLoad));
ui->ed_batvolt->setText(QString::number(cpuLoad.batVolt));
}
void SlugsDataSensorView::slugsNavegationChanged(int systemId,
const mavlink_slugs_navigation_t& slugsNavigation){
Q_UNUSED(systemId);
ui->m_Um->setText(QString::number(slugsNavigation.u_m));
ui->m_PhiC->setText(QString::number(slugsNavigation.phi_c));
ui->m_PitchC->setText(QString::number(slugsNavigation.theta_c));
ui->m_PsidC->setText(QString::number(slugsNavigation.psiDot_c));
ui->m_AyBody->setText(QString::number(slugsNavigation.ay_body));
ui->m_TotRun->setText(QString::number(slugsNavigation.totalDist));
ui->m_DistToGo->setText(QString::number(slugsNavigation.dist2Go));
ui->m_FromWP->setText(QString::number(slugsNavigation.fromWP));
ui->m_ToWP->setText(QString::number(slugsNavigation.toWP));
}
void SlugsDataSensorView::slugsDataLogChanged(int systemId,
const mavlink_data_log_t& dataLog){
Q_UNUSED(systemId);
ui->m_logFl1->setText(QString::number(dataLog.fl_1));
ui->m_logFl2->setText(QString::number(dataLog.fl_2));
ui->m_logFl3->setText(QString::number(dataLog.fl_3));
ui->m_logFl4->setText(QString::number(dataLog.fl_4));
ui->m_logFl5->setText(QString::number(dataLog.fl_5));
ui->m_logFl6->setText(QString::number(dataLog.fl_6));
}
void SlugsDataSensorView::slugsPWMChanged(int systemId,
const mavlink_pwm_commands_t& pwmCommands){
Q_UNUSED(systemId);
ui->m_pwmThro->setText(QString::number(pwmCommands.dt_c));
ui->m_pwmAile->setText(QString::number(pwmCommands.dla_c));
ui->m_pwmElev->setText(QString::number(pwmCommands.dle_c));
ui->m_pwmRudd->setText(QString::number(pwmCommands.dr_c));
ui->m_pwmThroTrim->setText(QString::number(pwmCommands.dre_c));
ui->m_pwmAileTrim->setText(QString::number(pwmCommands.dlf_c));
ui->m_pwmElevTrim->setText(QString::number(pwmCommands.drf_c));
ui->m_pwmRuddTrim->setText(QString::number(pwmCommands.aux1));
}
void SlugsDataSensorView::slugsFilteredDataChanged(int systemId,
const mavlink_filtered_data_t& filteredData){
Q_UNUSED(systemId);
ui->m_Axf->setText(QString::number(filteredData.aX));
ui->m_Ayf->setText(QString::number(filteredData.aY));
ui->m_Azf->setText(QString::number(filteredData.aZ));
ui->m_Gxf->setText(QString::number(filteredData.gX));
ui->m_Gyf->setText(QString::number(filteredData.gY));
ui->m_Gzf->setText(QString::number(filteredData.gZ));
ui->m_Mxf->setText(QString::number(filteredData.mX));
ui->m_Myf->setText(QString::number(filteredData.mY));
ui->m_Mzf->setText(QString::number(filteredData.mZ));
}
void SlugsDataSensorView::slugsGPSDateTimeChanged(int systemId,
const mavlink_gps_date_time_t& gpsDateTime){
Q_UNUSED(systemId);
QString month, day;
month = QString::number(gpsDateTime.month);
day = QString::number(gpsDateTime.day);
if(gpsDateTime.month < 10) month = "0" + QString::number(gpsDateTime.month);
if(gpsDateTime.day < 10) day = "0" + QString::number(gpsDateTime.day);
ui->m_GpsDate->setText(day + "/" +
month + "/" +
QString::number(gpsDateTime.year));
QString hour, min, sec;
hour = QString::number(gpsDateTime.hour);
min = QString::number(gpsDateTime.min);
sec = QString::number(gpsDateTime.sec);
if(gpsDateTime.hour < 10) hour = "0" + QString::number(gpsDateTime.hour);
if(gpsDateTime.min < 10) min = "0" + QString::number(gpsDateTime.min);
if(gpsDateTime.sec < 10) sec = "0" + QString::number(gpsDateTime.sec);
ui->m_GpsTime->setText(hour + ":" +
min + ":" +
sec);
ui->m_GpsSat->setText(QString::number(gpsDateTime.visSat));
}
/**
* @brief Updates the air data widget - 171
*/
void SlugsDataSensorView::slugsAirDataChanged(int systemId, const mavlink_air_data_t &airData)
{
Q_UNUSED(systemId);
ui->ed_dynamic->setText(QString::number(airData.dynamicPressure));
ui->ed_static->setText(QString::number(airData.staticPressure));
ui->ed_temp->setText(QString::number(airData.temperature));
// qDebug()<<"Air Data = "<<airData.dynamicPressure<<" - "
// <<airData.staticPressure<<" - "
// <<airData.temperature;
}
/**
* @brief set COG and SOG values
*
* COG and SOG GPS display on the Widgets
*/
void SlugsDataSensorView::slugsGPSCogSog(int systemId,
double cog,
double sog)
{
Q_UNUSED(systemId);
ui->m_GpsCog->setText(QString::number(cog));
ui->m_GpsSog->setText(QString::number(sog));
}
#endif // MAVLINK_ENABLED_SLUGS
This source diff could not be displayed because it is too large. You can view the blob instead.
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Configuration Window for Slugs' HIL Simulator
* @author Mariano Lizarraga <malife@gmail.com>
* @author Alejandro Molina <am.alex09@gmail.com>
*/
#include "SlugsHilSim.h"
#include "ui_SlugsHilSim.h"
SlugsHilSim::SlugsHilSim(QWidget *parent) :
QWidget(parent),
ui(new Ui::SlugsHilSim)
{
ui->setupUi(this);
rxSocket = new QUdpSocket(this);
txSocket = new QUdpSocket(this);
hilLink = NULL;
connect(LinkManager::instance(), SIGNAL(newLink(LinkInterface*)), this, SLOT(addToCombo(LinkInterface*)));
connect(ui->cb_mavlinkLinks, SIGNAL(currentIndexChanged(int)), this, SLOT(linkSelected(int)));
connect(ui->bt_startHil, SIGNAL(clicked()), this, SLOT(putInHilMode()));
connect(rxSocket, SIGNAL(readyRead()), this, SLOT(readDatagram()));
linksAvailable.clear();
#ifdef MAVLINK_ENABLED_SLUGS
memset(&tmpAirData, 0, sizeof(mavlink_air_data_t));
memset(&tmpAttitudeData, 0, sizeof(mavlink_attitude_t));
memset(&tmpGpsData, 0, sizeof(mavlink_gps_raw_t));
memset(&tmpGpsTime, 0, sizeof(mavlink_gps_date_time_t));
memset(&tmpLocalPositionData, 0, sizeof(mavlink_sensor_bias_t));
memset(&tmpRawImuData, 0, sizeof(mavlink_raw_imu_t));
#endif
foreach (LinkInterface* link, LinkManager::instance()->getLinks())
{
addToCombo(link);
}
}
SlugsHilSim::~SlugsHilSim()
{
rxSocket->disconnectFromHost();
delete ui;
}
void SlugsHilSim::addToCombo(LinkInterface* theLink){
linksAvailable.insert(ui->cb_mavlinkLinks->count(),theLink);
ui->cb_mavlinkLinks->addItem(theLink->getName());
if (hilLink == NULL){
hilLink = theLink;
}
}
void SlugsHilSim::putInHilMode(void){
bool sw_enableControls = !(ui->bt_startHil->isChecked());
QString buttonCaption= ui->bt_startHil->isChecked()? "Stop Slugs HIL Mode": "Set Slugs in HIL Mode";
if (ui->bt_startHil->isChecked()){
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText("You are about to put SLUGS in HIL Mode.");
msgBox.setInformativeText("It will stop reading the actual sensor readings. Do you wish to continue?");
msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::No);
msgBox.setDefaultButton(QMessageBox::No);
if(msgBox.exec() == QMessageBox::Yes) {
rxSocket->disconnectFromHost();
rxSocket->bind(QHostAddress::Any, ui->ed_rxPort->text().toInt());
//txSocket->bind(QHostAddress::Broadcast, ui->ed_txPort->text().toInt());
ui->ed_ipAdress->setEnabled(sw_enableControls);
ui->ed_rxPort->setEnabled(sw_enableControls);
ui->ed_txPort->setEnabled(sw_enableControls);
ui->cb_mavlinkLinks->setEnabled(sw_enableControls);
ui->bt_startHil->setText(buttonCaption);
} else {
ui->bt_startHil->setChecked(false);
}
} else {
ui->ed_ipAdress->setEnabled(sw_enableControls);
ui->ed_rxPort->setEnabled(sw_enableControls);
ui->ed_txPort->setEnabled(sw_enableControls);
ui->cb_mavlinkLinks->setEnabled(sw_enableControls);
ui->bt_startHil->setText(buttonCaption);
rxSocket->disconnectFromHost();
}
}
void SlugsHilSim::readDatagram(void){
static int count = 0;
while (rxSocket->hasPendingDatagrams()) {
QByteArray datagram;
datagram.resize(rxSocket->pendingDatagramSize());
QHostAddress sender;
quint16 senderPort;
rxSocket->readDatagram(datagram.data(), datagram.size(),
&sender, &senderPort);
if (datagram.size() == 113) {
processHilDatagram(&datagram);
sendMessageToSlugs();
commandDatagramToSimulink();
}
ui->ed_count->setText(QString::number(count++));
}
}
void SlugsHilSim::activeUasSet(UASInterface* uas){
if (uas != NULL) {
activeUas = static_cast <UAS *>(uas);
}
}
void SlugsHilSim::processHilDatagram(const QByteArray* datagram)
{
#ifdef MAVLINK_ENABLED_SLUGS
unsigned char i = 0;
tmpGpsTime.year = datagram->at(i++);
tmpGpsTime.month = datagram->at(i++);
tmpGpsTime.day = datagram->at(i++);
tmpGpsTime.hour = datagram->at(i++);
tmpGpsTime.min = datagram->at(i++);
tmpGpsTime.sec = datagram->at(i++);
tmpGpsData.lat = getFloatFromDatagram(datagram, &i);
tmpGpsData.lon = getFloatFromDatagram(datagram, &i);
tmpGpsData.alt = getFloatFromDatagram(datagram, &i);
tmpGpsData.hdg = getUint16FromDatagram(datagram, &i);
tmpGpsData.v = getUint16FromDatagram(datagram, &i);
tmpGpsData.eph = getUint16FromDatagram(datagram, &i);
tmpGpsData.fix_type = datagram->at(i++);
tmpGpsTime.visSat = datagram->at(i++);
i++;
tmpAirData.dynamicPressure= getFloatFromDatagram(datagram, &i);
tmpAirData.staticPressure= getFloatFromDatagram(datagram, &i);
tmpAirData.temperature= getUint16FromDatagram(datagram, &i);
// TODO Salto en el Datagrama
i=i+8;
tmpRawImuData.xgyro = getUint16FromDatagram(datagram, &i);
tmpRawImuData.ygyro = getUint16FromDatagram(datagram, &i);
tmpRawImuData.zgyro = getUint16FromDatagram(datagram, &i);
tmpRawImuData.xacc = getUint16FromDatagram(datagram, &i);
tmpRawImuData.yacc = getUint16FromDatagram(datagram, &i);
tmpRawImuData.zacc = getUint16FromDatagram(datagram, &i);
tmpRawImuData.xmag = getUint16FromDatagram(datagram, &i);
tmpRawImuData.ymag = getUint16FromDatagram(datagram, &i);
tmpRawImuData.zmag = getUint16FromDatagram(datagram, &i);
tmpAttitudeData.roll = getFloatFromDatagram(datagram, &i);
tmpAttitudeData.pitch = getFloatFromDatagram(datagram, &i);
tmpAttitudeData.yaw = getFloatFromDatagram(datagram, &i);
tmpAttitudeData.rollspeed = getFloatFromDatagram(datagram, &i);
tmpAttitudeData.pitchspeed = getFloatFromDatagram(datagram, &i);
tmpAttitudeData.yawspeed = getFloatFromDatagram(datagram, &i);
// TODO Crear Paquete SYNC TIME
i=i+2;
tmpLocalPositionData.x = getFloatFromDatagram(datagram, &i);
tmpLocalPositionData.y = getFloatFromDatagram(datagram, &i);
tmpLocalPositionData.z = getFloatFromDatagram(datagram, &i);
tmpLocalPositionData.vx = getFloatFromDatagram(datagram, &i);
tmpLocalPositionData.vy = getFloatFromDatagram(datagram, &i);
tmpLocalPositionData.vz = getFloatFromDatagram(datagram, &i);
// TODO: this is legacy of old HIL datagram. Need to remove from Simulink model
i++;
ui->ed_1->setText(QString::number(tmpRawImuData.xacc));
ui->ed_2->setText(QString::number(tmpRawImuData.yacc));
ui->ed_3->setText(QString::number(tmpRawImuData.zacc));
ui->tbA->setText(QString::number(tmpRawImuData.xgyro));
ui->tbB->setText(QString::number(tmpRawImuData.ygyro));
ui->tbC->setText(QString::number(tmpRawImuData.zgyro));
#else
Q_UNUSED(datagram);
#endif
}
float SlugsHilSim::getFloatFromDatagram (const QByteArray* datagram, unsigned char * i){
tFloatToChar tmpF2C;
tmpF2C.chData[0] = datagram->at((*i)++);
tmpF2C.chData[1] = datagram->at((*i)++);
tmpF2C.chData[2] = datagram->at((*i)++);
tmpF2C.chData[3] = datagram->at((*i)++);
return tmpF2C.flData;
}
uint16_t SlugsHilSim::getUint16FromDatagram (const QByteArray* datagram, unsigned char * i){
tUint16ToChar tmpU2C;
tmpU2C.chData[0] = datagram->at((*i)++);
tmpU2C.chData[1] = datagram->at((*i)++);
return tmpU2C.uiData;
}
void SlugsHilSim::linkSelected(int cbIndex)
{
#ifdef MAVLINK_ENABLED_SLUGS
// HIL code to go here...
//hilLink = linksAvailable
// FIXME Mariano
hilLink =linksAvailable.value(cbIndex);
#else
Q_UNUSED(cbIndex)
#endif
}
void SlugsHilSim::sendMessageToSlugs()
{
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_message_t msg;
mavlink_msg_local_position_encode(MG::SYSTEM::ID,
MG::SYSTEM::COMPID,
&msg,
&tmpLocalPositionData);
activeUas->sendMessage(hilLink, msg);
memset(&msg, 0, sizeof(mavlink_message_t));
mavlink_msg_attitude_encode(MG::SYSTEM::ID,
MG::SYSTEM::COMPID,
&msg,
&tmpAttitudeData);
activeUas->sendMessage(hilLink, msg);
memset(&msg, 0, sizeof(mavlink_message_t));
mavlink_msg_raw_imu_encode(MG::SYSTEM::ID,
MG::SYSTEM::COMPID,
&msg,
&tmpRawImuData);
activeUas->sendMessage(hilLink, msg);
memset(&msg, 0, sizeof(mavlink_message_t));
mavlink_msg_air_data_encode(MG::SYSTEM::ID,
MG::SYSTEM::COMPID,
&msg,
&tmpAirData);
activeUas->sendMessage(hilLink, msg);
memset(&msg, 0, sizeof(mavlink_message_t));
mavlink_msg_gps_raw_encode(MG::SYSTEM::ID,
MG::SYSTEM::COMPID,
&msg,
&tmpGpsData);
activeUas->sendMessage(hilLink, msg);
memset(&msg, 0, sizeof(mavlink_message_t));
mavlink_msg_gps_date_time_encode(MG::SYSTEM::ID,
MG::SYSTEM::COMPID,
&msg,
&tmpGpsTime);
activeUas->sendMessage(hilLink, msg);
memset(&msg, 0, sizeof(mavlink_message_t));
#endif
}
void SlugsHilSim::commandDatagramToSimulink()
{
#ifdef MAVLINK_ENABLED_SLUGS
//mavlink_pwm_commands_t* pwdC = (static_cast<SlugsMAV*>(activeUas))->getPwmCommands();
mavlink_pwm_commands_t* pwdC;
if(pwdC != NULL){
}
QByteArray data;
data.resize(22);
unsigned char i=0;
setUInt16ToDatagram(data, &i, 1);//pwdC->dt_c);
setUInt16ToDatagram(data, &i, 2);//pwdC->dla_c);
setUInt16ToDatagram(data, &i, 3);//pwdC->dra_c);
setUInt16ToDatagram(data, &i, 4);//pwdC->dr_c);
setUInt16ToDatagram(data, &i, 5);//pwdC->dle_c);
setUInt16ToDatagram(data, &i, 6);//pwdC->dre_c);
setUInt16ToDatagram(data, &i, 7);//pwdC->dlf_c);
setUInt16ToDatagram(data, &i, 8);//pwdC->drf_c);
setUInt16ToDatagram(data, &i, 9);//pwdC->aux1);
setUInt16ToDatagram(data, &i, 10);//pwdC->aux2);
setUInt16ToDatagram(data, &i, 11);//value default
txSocket->writeDatagram(data, QHostAddress::Broadcast, ui->ed_txPort->text().toInt());
#endif
}
void SlugsHilSim::setUInt16ToDatagram(QByteArray& datagram, unsigned char* pos, uint16_t value)
{
tUint16ToChar tmpUnion;
tmpUnion.uiData= value;
datagram[(*pos)++]= tmpUnion.chData[0];
datagram[(*pos)++]= tmpUnion.chData[1];
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Configuration Window for Slugs' HIL Simulator
* @author Mariano Lizarraga <malife@gmail.com>
* @author Alejandro Molina <am.alex09@gmail.com>
*/
#include "SlugsHilSim.h"
#include "ui_SlugsHilSim.h"
SlugsHilSim::SlugsHilSim(QWidget *parent) :
QWidget(parent),
ui(new Ui::SlugsHilSim)
{
ui->setupUi(this);
rxSocket = new QUdpSocket(this);
txSocket = new QUdpSocket(this);
hilLink = NULL;
connect(LinkManager::instance(), SIGNAL(newLink(LinkInterface*)), this, SLOT(addToCombo(LinkInterface*)));
connect(ui->cb_mavlinkLinks, SIGNAL(currentIndexChanged(int)), this, SLOT(linkSelected(int)));
connect(ui->bt_startHil, SIGNAL(clicked()), this, SLOT(putInHilMode()));
connect(rxSocket, SIGNAL(readyRead()), this, SLOT(readDatagram()));
linksAvailable.clear();
#ifdef MAVLINK_ENABLED_SLUGS
memset(&tmpAirData, 0, sizeof(mavlink_air_data_t));
memset(&tmpAttitudeData, 0, sizeof(mavlink_attitude_t));
memset(&tmpGpsData, 0, sizeof(mavlink_gps_raw_t));
memset(&tmpGpsTime, 0, sizeof(mavlink_gps_date_time_t));
memset(&tmpLocalPositionData, 0, sizeof(mavlink_sensor_bias_t));
memset(&tmpRawImuData, 0, sizeof(mavlink_raw_imu_t));
#endif
foreach (LinkInterface* link, LinkManager::instance()->getLinks())
{
addToCombo(link);
}
}
SlugsHilSim::~SlugsHilSim()
{
rxSocket->disconnectFromHost();
delete ui;
}
void SlugsHilSim::addToCombo(LinkInterface* theLink){
linksAvailable.insert(ui->cb_mavlinkLinks->count(),theLink);
ui->cb_mavlinkLinks->addItem(theLink->getName());
if (hilLink == NULL){
hilLink = theLink;
}
}
void SlugsHilSim::putInHilMode(void){
bool sw_enableControls = !(ui->bt_startHil->isChecked());
QString buttonCaption= ui->bt_startHil->isChecked()? "Stop Slugs HIL Mode": "Set Slugs in HIL Mode";
if (ui->bt_startHil->isChecked()){
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText("You are about to put SLUGS in HIL Mode.");
msgBox.setInformativeText("It will stop reading the actual sensor readings. Do you wish to continue?");
msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::No);
msgBox.setDefaultButton(QMessageBox::No);
if(msgBox.exec() == QMessageBox::Yes) {
rxSocket->disconnectFromHost();
rxSocket->bind(QHostAddress::Any, ui->ed_rxPort->text().toInt());
//txSocket->bind(QHostAddress::Broadcast, ui->ed_txPort->text().toInt());
ui->ed_ipAdress->setEnabled(sw_enableControls);
ui->ed_rxPort->setEnabled(sw_enableControls);
ui->ed_txPort->setEnabled(sw_enableControls);
ui->cb_mavlinkLinks->setEnabled(sw_enableControls);
ui->bt_startHil->setText(buttonCaption);
} else {
ui->bt_startHil->setChecked(false);
}
} else {
ui->ed_ipAdress->setEnabled(sw_enableControls);
ui->ed_rxPort->setEnabled(sw_enableControls);
ui->ed_txPort->setEnabled(sw_enableControls);
ui->cb_mavlinkLinks->setEnabled(sw_enableControls);
ui->bt_startHil->setText(buttonCaption);
rxSocket->disconnectFromHost();
}
}
void SlugsHilSim::readDatagram(void){
static int count = 0;
while (rxSocket->hasPendingDatagrams()) {
QByteArray datagram;
datagram.resize(rxSocket->pendingDatagramSize());
QHostAddress sender;
quint16 senderPort;
rxSocket->readDatagram(datagram.data(), datagram.size(),
&sender, &senderPort);
if (datagram.size() == 113) {
processHilDatagram(&datagram);
sendMessageToSlugs();
commandDatagramToSimulink();
}
ui->ed_count->setText(QString::number(count++));
}
}
void SlugsHilSim::activeUasSet(UASInterface* uas){
if (uas != NULL) {
activeUas = static_cast <UAS *>(uas);
//connect(uas, SIGNAL())
}
}
void SlugsHilSim::processHilDatagram(const QByteArray* datagram)
{
#ifdef MAVLINK_ENABLED_SLUGS
unsigned char i = 0;
tmpGpsTime.year = datagram->at(i++);
tmpGpsTime.month = datagram->at(i++);
tmpGpsTime.day = datagram->at(i++);
tmpGpsTime.hour = datagram->at(i++);
tmpGpsTime.min = datagram->at(i++);
tmpGpsTime.sec = datagram->at(i++);
tmpGpsData.lat = getFloatFromDatagram(datagram, &i);
tmpGpsData.lon = getFloatFromDatagram(datagram, &i);
tmpGpsData.alt = getFloatFromDatagram(datagram, &i);
tmpGpsData.hdg = getUint16FromDatagram(datagram, &i);
tmpGpsData.v = getUint16FromDatagram(datagram, &i);
tmpGpsData.eph = getUint16FromDatagram(datagram, &i);
tmpGpsData.fix_type = datagram->at(i++);
tmpGpsTime.visSat = datagram->at(i++);
i++;
tmpAirData.dynamicPressure= getFloatFromDatagram(datagram, &i);
tmpAirData.staticPressure= getFloatFromDatagram(datagram, &i);
tmpAirData.temperature= getUint16FromDatagram(datagram, &i);
// TODO Salto en el Datagrama
i=i+8;
tmpRawImuData.xgyro = getUint16FromDatagram(datagram, &i);
tmpRawImuData.ygyro = getUint16FromDatagram(datagram, &i);
tmpRawImuData.zgyro = getUint16FromDatagram(datagram, &i);
tmpRawImuData.xacc = getUint16FromDatagram(datagram, &i);
tmpRawImuData.yacc = getUint16FromDatagram(datagram, &i);
tmpRawImuData.zacc = getUint16FromDatagram(datagram, &i);
tmpRawImuData.xmag = getUint16FromDatagram(datagram, &i);
tmpRawImuData.ymag = getUint16FromDatagram(datagram, &i);
tmpRawImuData.zmag = getUint16FromDatagram(datagram, &i);
tmpAttitudeData.roll = getFloatFromDatagram(datagram, &i);
tmpAttitudeData.pitch = getFloatFromDatagram(datagram, &i);
tmpAttitudeData.yaw = getFloatFromDatagram(datagram, &i);
tmpAttitudeData.rollspeed = getFloatFromDatagram(datagram, &i);
tmpAttitudeData.pitchspeed = getFloatFromDatagram(datagram, &i);
tmpAttitudeData.yawspeed = getFloatFromDatagram(datagram, &i);
// TODO Crear Paquete SYNC TIME
i=i+2;
tmpLocalPositionData.x = getFloatFromDatagram(datagram, &i);
tmpLocalPositionData.y = getFloatFromDatagram(datagram, &i);
tmpLocalPositionData.z = getFloatFromDatagram(datagram, &i);
tmpLocalPositionData.vx = getFloatFromDatagram(datagram, &i);
tmpLocalPositionData.vy = getFloatFromDatagram(datagram, &i);
tmpLocalPositionData.vz = getFloatFromDatagram(datagram, &i);
// TODO: this is legacy of old HIL datagram. Need to remove from Simulink model
i++;
ui->ed_1->setText(QString::number(tmpRawImuData.xacc));
ui->ed_2->setText(QString::number(tmpRawImuData.yacc));
ui->ed_3->setText(QString::number(tmpRawImuData.zacc));
ui->tbA->setText(QString::number(tmpRawImuData.xgyro));
ui->tbB->setText(QString::number(tmpRawImuData.ygyro));
ui->tbC->setText(QString::number(tmpRawImuData.zgyro));
#else
Q_UNUSED(datagram);
#endif
}
float SlugsHilSim::getFloatFromDatagram (const QByteArray* datagram, unsigned char * i){
tFloatToChar tmpF2C;
tmpF2C.chData[0] = datagram->at((*i)++);
tmpF2C.chData[1] = datagram->at((*i)++);
tmpF2C.chData[2] = datagram->at((*i)++);
tmpF2C.chData[3] = datagram->at((*i)++);
return tmpF2C.flData;
}
uint16_t SlugsHilSim::getUint16FromDatagram (const QByteArray* datagram, unsigned char * i){
tUint16ToChar tmpU2C;
tmpU2C.chData[0] = datagram->at((*i)++);
tmpU2C.chData[1] = datagram->at((*i)++);
return tmpU2C.uiData;
}
void SlugsHilSim::linkSelected(int cbIndex)
{
#ifdef MAVLINK_ENABLED_SLUGS
// HIL code to go here...
//hilLink = linksAvailable
// FIXME Mariano
hilLink =linksAvailable.value(cbIndex);
#else
Q_UNUSED(cbIndex)
#endif
}
void SlugsHilSim::sendMessageToSlugs()
{
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_message_t msg;
mavlink_msg_local_position_encode(MG::SYSTEM::ID,
MG::SYSTEM::COMPID,
&msg,
&tmpLocalPositionData);
activeUas->sendMessage(hilLink, msg);
memset(&msg, 0, sizeof(mavlink_message_t));
mavlink_msg_attitude_encode(MG::SYSTEM::ID,
MG::SYSTEM::COMPID,
&msg,
&tmpAttitudeData);
activeUas->sendMessage(hilLink, msg);
memset(&msg, 0, sizeof(mavlink_message_t));
mavlink_msg_raw_imu_encode(MG::SYSTEM::ID,
MG::SYSTEM::COMPID,
&msg,
&tmpRawImuData);
activeUas->sendMessage(hilLink, msg);
memset(&msg, 0, sizeof(mavlink_message_t));
mavlink_msg_air_data_encode(MG::SYSTEM::ID,
MG::SYSTEM::COMPID,
&msg,
&tmpAirData);
activeUas->sendMessage(hilLink, msg);
memset(&msg, 0, sizeof(mavlink_message_t));
mavlink_msg_gps_raw_encode(MG::SYSTEM::ID,
MG::SYSTEM::COMPID,
&msg,
&tmpGpsData);
activeUas->sendMessage(hilLink, msg);
memset(&msg, 0, sizeof(mavlink_message_t));
mavlink_msg_gps_date_time_encode(MG::SYSTEM::ID,
MG::SYSTEM::COMPID,
&msg,
&tmpGpsTime);
activeUas->sendMessage(hilLink, msg);
memset(&msg, 0, sizeof(mavlink_message_t));
#endif
}
void SlugsHilSim::commandDatagramToSimulink()
{
#ifdef MAVLINK_ENABLED_SLUGS
//mavlink_pwm_commands_t* pwdC = (static_cast<SlugsMAV*>(activeUas))->getPwmCommands();
mavlink_pwm_commands_t* pwdC;
if(pwdC != NULL){
}
QByteArray data;
data.resize(22);
unsigned char i=0;
setUInt16ToDatagram(data, &i, 1);//pwdC->dt_c);
setUInt16ToDatagram(data, &i, 2);//pwdC->dla_c);
setUInt16ToDatagram(data, &i, 3);//pwdC->dra_c);
setUInt16ToDatagram(data, &i, 4);//pwdC->dr_c);
setUInt16ToDatagram(data, &i, 5);//pwdC->dle_c);
setUInt16ToDatagram(data, &i, 6);//pwdC->dre_c);
setUInt16ToDatagram(data, &i, 7);//pwdC->dlf_c);
setUInt16ToDatagram(data, &i, 8);//pwdC->drf_c);
setUInt16ToDatagram(data, &i, 9);//pwdC->aux1);
setUInt16ToDatagram(data, &i, 10);//pwdC->aux2);
setUInt16ToDatagram(data, &i, 11);//value default
txSocket->writeDatagram(data, QHostAddress::Broadcast, ui->ed_txPort->text().toInt());
#endif
}
void SlugsHilSim::setUInt16ToDatagram(QByteArray& datagram, unsigned char* pos, uint16_t value)
{
tUint16ToChar tmpUnion;
tmpUnion.uiData= value;
datagram[(*pos)++]= tmpUnion.chData[0];
datagram[(*pos)++]= tmpUnion.chData[1];
}
#include "SlugsPIDControl.h"
#include "ui_SlugsPIDControl.h"
#include <QPalette>
#include<QColor>
#include <QDebug>
#include <UASManager.h>
#include <UAS.h>
#include "LinkManager.h"
SlugsPIDControl::SlugsPIDControl(QWidget *parent) :
QWidget(parent),
ui(new Ui::SlugsPIDControl)
{
ui->setupUi(this);
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(activeUasSet(UASInterface*)));
activeUAS = NULL;
setRedColorStyle();
setGreenColorStyle();
refreshTimerGet = new QTimer(this);
refreshTimerGet->setInterval(100); // 10 Hz
connect(refreshTimerGet, SIGNAL(timeout()), this, SLOT(slugsGetGeneral()));
refreshTimerSet = new QTimer(this);
refreshTimerSet->setInterval(100); // 20 Hz
connect(refreshTimerSet, SIGNAL(timeout()), this, SLOT(slugsSetGeneral()));
counterRefreshGet = 1;
counterRefreshSet = 1;
}
/**
* @brief Called when the a new UAS is set to active.
*
* Called when the a new UAS is set to active.
*
* @param uas The new active UAS
*/
void SlugsPIDControl::activeUasSet(UASInterface* uas)
{
#ifdef MAVLINK_ENABLED_SLUGS
SlugsMAV* slugsMav = qobject_cast<SlugsMAV*>(uas);
if (slugsMav)
{
connect(slugsMav,SIGNAL(slugsActionAck(int,const mavlink_action_ack_t&)),this,SLOT(recibeMensaje(int,mavlink_action_ack_t)));
connect(slugsMav,SIGNAL(slugsPidValues(int,mavlink_pid_t)),this, SLOT(receivePidValues(int,mavlink_pid_t)) );
connect(ui->setGeneral_pushButton,SIGNAL(clicked()),this,SLOT(slugsTimerStartSet()));
connect(ui->getGeneral_pushButton,SIGNAL(clicked()),this,SLOT(slugsTimerStartGet()));
}
#endif // MAVLINK_ENABLED_SLUG
// Set this UAS as active if it is the first one
if(!activeUAS)
{
activeUAS = uas;
systemId = activeUAS->getUASID();
connect_editLinesPDIvalues();
}
}
/**
* @brief Connect Edition Lines for PID Values
*
* @param
*/
void SlugsPIDControl::connect_editLinesPDIvalues()
{
if(activeUAS)
{
connect_set_pushButtons();
connect_get_pushButtons();
connect_AirSpeed_LineEdit();
connect_PitchFollowei_LineEdit();
connect_RollControl_LineEdit();
connect_HeigthError_LineEdit();
connect_YawDamper_LineEdit();
connect_Pitch2dT_LineEdit();
}
}
SlugsPIDControl::~SlugsPIDControl()
{
delete ui;
}
/**
*@brief Set the background color RED style for the GroupBox PID when change lineEdit information
*
*/
void SlugsPIDControl::setRedColorStyle()
{
// GroupBox Color
QColor groupColor = QColor(231,72,28);
QString borderColor = "#FA4A4F";
groupColor = groupColor.darker(475);
REDcolorStyle = REDcolorStyle.sprintf("QGroupBox {background-color: #%02X%02X%02X; border: 5px solid %s; }",
groupColor.red(), groupColor.green(), groupColor.blue(), borderColor.toStdString().c_str());
}
/**
*@brief Set the background color GREEN style for the GroupBox PID when change lineEdit information
*
*/
void SlugsPIDControl::setGreenColorStyle()
{
// create Green color style
QColor groupColor = QColor(30,124,16);
QString borderColor = "#24AC23";
groupColor = groupColor.darker(475);
GREENcolorStyle = GREENcolorStyle.sprintf("QGroupBox {background-color: #%02X%02X%02X; border: 5px solid %s; }",
groupColor.red(), groupColor.green(), groupColor.blue(), borderColor.toStdString().c_str());
}
/**
*@brief Connection Signal and Slot of the set buttons on the widget
*/
void SlugsPIDControl::connect_set_pushButtons()
{
//ToDo connect buttons set and get. Before create the slots
connect(ui->dT_PID_set_pushButton, SIGNAL(clicked()),this,SLOT(changeColor_GREEN_AirSpeed_groupBox()));
connect(ui->dE_PID_set_pushButton,SIGNAL(clicked()),this,SLOT(changeColor_GREEN_PitchFollowei_groupBox()));
connect(ui->dA_PID_set_pushButton,SIGNAL(clicked()),this,SLOT(changeColor_GREEN_RollControl_groupBox()));
connect(ui->HELPComm_PDI_set_pushButton,SIGNAL(clicked()),this,SLOT(changeColor_GREEN_HeigthError_groupBox()));
connect(ui->dR_PDI_set_pushButton,SIGNAL(clicked()),this,SLOT(changeColor_GREEN_YawDamper_groupBox()));
connect(ui->Pitch2dT_PDI_set_pushButton,SIGNAL(clicked()),this,SLOT(changeColor_GREEN_Pitch2dT_groupBox()));
}
/**
*@brief Connection Signal and Slot of the set buttons on the widget
*/
void SlugsPIDControl::connect_get_pushButtons()
{
connect(ui->dT_PID_get_pushButton, SIGNAL(clicked()),this,SLOT(get_AirSpeed_PID()));
connect(ui->dE_PID_get_pushButton,SIGNAL(clicked()),this,SLOT(get_PitchFollowei_PID()));
connect(ui->dR_PDI_get_pushButton,SIGNAL(clicked()),this,SLOT(get_YawDamper_PID()));
connect(ui->dA_PID_get_pushButton,SIGNAL(clicked()),this,SLOT(get_RollControl_PID()));
connect(ui->Pitch2dT_PDI_get_pushButton,SIGNAL(clicked()),this,SLOT(get_Pitch2dT_PID()));
connect(ui->HELPComm_PDI_get_pushButton,SIGNAL(clicked()),this,SLOT(get_HeigthError_PID()));
}
// Functions for Air Speed GroupBox
void SlugsPIDControl::connect_AirSpeed_LineEdit()
{
connect(ui->dT_P_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_AirSpeed_groupBox(QString)));
connect(ui->dT_I_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_AirSpeed_groupBox(QString)));
connect(ui->dT_D_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_AirSpeed_groupBox(QString)));
}
void SlugsPIDControl::changeColor_RED_AirSpeed_groupBox(QString text)
{
Q_UNUSED(text);
ui->AirSpeedHold_groupBox->setStyleSheet(REDcolorStyle);
}
void SlugsPIDControl::changeColor_GREEN_AirSpeed_groupBox()
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
//create the packet
#ifdef MAVLINK_ENABLED_SLUGS
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 0;
pidMessage.pVal = ui->dT_P_set->text().toFloat();
pidMessage.iVal = ui->dT_I_set->text().toFloat();
pidMessage.dVal = ui->dT_D_set->text().toFloat();
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->AirSpeedHold_groupBox->setStyleSheet(GREENcolorStyle);
}
}
void SlugsPIDControl::get_AirSpeed_PID()
{
qDebug() << "\nSend Message = Air Speed ";
sendMessagePIDStatus(0);
}
// Functions for PitchFollowei GroupBox
void SlugsPIDControl::connect_PitchFollowei_LineEdit()
{
connect(ui->dE_P_set, SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_PitchFollowei_groupBox(QString)));
connect(ui->dE_I_set, SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_PitchFollowei_groupBox(QString)));
connect(ui->dE_D_set, SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_PitchFollowei_groupBox(QString)));
}
void SlugsPIDControl::changeColor_RED_PitchFollowei_groupBox(QString text)
{
Q_UNUSED(text);
ui->PitchFlowei_groupBox->setStyleSheet(REDcolorStyle);
}
void SlugsPIDControl::changeColor_GREEN_PitchFollowei_groupBox()
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 2;
pidMessage.pVal = ui->dE_P_set->text().toFloat();
pidMessage.iVal = ui->dE_I_set->text().toFloat();
pidMessage.dVal = ui->dE_D_set->text().toFloat();
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->PitchFlowei_groupBox->setStyleSheet(GREENcolorStyle);
}
}
void SlugsPIDControl::get_PitchFollowei_PID()
{
qDebug() << "\nSend Message = Pitch Followei ";
sendMessagePIDStatus(2);
}
// Functions for Roll Control GroupBox
/**
* @brief Change color style to red when PID values of Roll Control are edited
*
*
* @param
*/
void SlugsPIDControl::changeColor_RED_RollControl_groupBox(QString text)
{
Q_UNUSED(text);
ui->RollControl_groupBox->setStyleSheet(REDcolorStyle);
}
/**
* @brief Change color style to green when PID values of Roll Control are send to UAS
*
* @param
*/
void SlugsPIDControl::changeColor_GREEN_RollControl_groupBox()
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 4;
pidMessage.pVal = ui->dA_P_set->text().toFloat();
pidMessage.iVal = ui->dA_I_set->text().toFloat();
pidMessage.dVal = ui->dA_D_set->text().toFloat();
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->RollControl_groupBox->setStyleSheet(GREENcolorStyle);
}
}
/**
* @brief Connects the SIGNALS from the editline to SLOT RollControl_groupBox
*
* @param
*/
void SlugsPIDControl::connect_RollControl_LineEdit()
{
connect(ui->dA_P_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_RollControl_groupBox(QString)));
connect(ui->dA_I_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_RollControl_groupBox(QString)));
connect(ui->dA_D_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_RollControl_groupBox(QString)));
}
void SlugsPIDControl::get_RollControl_PID()
{
qDebug() << "\nSend Message = Roll Control ";
sendMessagePIDStatus(4);
}
// Functions for Heigth Error GroupBox
/**
* @brief Change color style to red when PID values of Heigth Error are edited
*
*
* @param
*/
void SlugsPIDControl::changeColor_RED_HeigthError_groupBox(QString text)
{
Q_UNUSED(text);
ui->HeightErrorLoPitch_groupBox->setStyleSheet(REDcolorStyle);
}
/**
* @brief Change color style to green when PID values of Heigth Error are send to UAS
*
* @param
*/
void SlugsPIDControl::changeColor_GREEN_HeigthError_groupBox()
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 1;
pidMessage.pVal = ui->HELPComm_P_set->text().toFloat();
pidMessage.iVal = ui->HELPComm_I_set->text().toFloat();
pidMessage.dVal = ui->HELPComm_FF_set->text().toFloat();
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->HeightErrorLoPitch_groupBox->setStyleSheet(GREENcolorStyle);
}
}
/**
* @brief Connects the SIGNALS from the editline to SLOT HeigthError_groupBox
*
* @param
*/
void SlugsPIDControl::connect_HeigthError_LineEdit()
{
connect(ui->HELPComm_P_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_HeigthError_groupBox(QString)));
connect(ui->HELPComm_I_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_HeigthError_groupBox(QString)));
connect(ui->HELPComm_FF_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_HeigthError_groupBox(QString)));
}
void SlugsPIDControl::get_HeigthError_PID()
{
qDebug() << "\nSend Message = Heigth Error ";
sendMessagePIDStatus(1);
}
// Functions for Yaw Damper GroupBox
/**
* @brief Change color style to red when PID values of Yaw Damper are edited
*
*
* @param
*/
void SlugsPIDControl::changeColor_RED_YawDamper_groupBox(QString text)
{
Q_UNUSED(text);
ui->YawDamper_groupBox->setStyleSheet(REDcolorStyle);
}
/**
* @brief Change color style to green when PID values of Yaw Damper are send to UAS
*
* @param
*/
void SlugsPIDControl::changeColor_GREEN_YawDamper_groupBox()
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 3;
pidMessage.pVal = ui->dR_P_set->text().toFloat();
pidMessage.iVal = ui->dR_I_set->text().toFloat();
pidMessage.dVal = ui->dR_D_set->text().toFloat();
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->YawDamper_groupBox->setStyleSheet(GREENcolorStyle);
}
}
/**
* @brief Connects the SIGNALS from the editline to SLOT YawDamper_groupBox
*
* @param
*/
void SlugsPIDControl::connect_YawDamper_LineEdit()
{
connect(ui->dR_P_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_YawDamper_groupBox(QString)));
connect(ui->dR_I_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_YawDamper_groupBox(QString)));
connect(ui->dR_D_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_YawDamper_groupBox(QString)));
}
void SlugsPIDControl::get_YawDamper_PID()
{
qDebug() << "\nSend Message = Yaw Damper ";
sendMessagePIDStatus(3);
}
// Functions for Pitch to dT GroupBox
/**
* @brief Change color style to red when PID values of Pitch to dT are edited
*
*
* @param
*/
void SlugsPIDControl::changeColor_RED_Pitch2dT_groupBox(QString text)
{
Q_UNUSED(text);
ui->Pitch2dTFFterm_groupBox->setStyleSheet(REDcolorStyle);
}
/**
* @brief Change color style to green when PID values of Pitch to dT are send to UAS
*
* @param
*/
void SlugsPIDControl::changeColor_GREEN_Pitch2dT_groupBox()
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 8;
pidMessage.pVal = ui->P2dT_FF_set->text().toFloat();
pidMessage.iVal = 0;//ui->dR_I_set->text().toFloat();
pidMessage.dVal = 0;//ui->dR_D_set->text().toFloat();
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->Pitch2dTFFterm_groupBox->setStyleSheet(GREENcolorStyle);
}
}
/**
* @brief Connects the SIGNALS from the editline to SLOT Pitch2dT_groupBox
*
* @param
*/
void SlugsPIDControl::connect_Pitch2dT_LineEdit()
{
connect(ui->P2dT_FF_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_Pitch2dT_groupBox(QString)));
}
void SlugsPIDControl::get_Pitch2dT_PID()
{
qDebug() << "\nSend Message = Pitch to dT ";
sendMessagePIDStatus(8);
}
#ifdef MAVLINK_ENABLED_SLUGS
void SlugsPIDControl::recibeMensaje(int systemId, const mavlink_action_ack_t& action)
{
Q_UNUSED(systemId);
ui->recepcion_label->setText(QString::number(action.action) + ":" + QString::number(action.result));
}
void SlugsPIDControl::receivePidValues(int systemId, const mavlink_pid_t &pidValues)
{
Q_UNUSED(systemId);
qDebug() << "\nACTUALIZANDO GUI = " << pidValues.idx;
switch(pidValues.idx)
{
case 0:
ui->dT_P_get->setText(QString::number(pidValues.pVal));
ui->dT_I_get->setText(QString::number(pidValues.iVal));
ui->dT_D_get->setText(QString::number(pidValues.dVal));
break;
case 1:
ui->HELPComm_P_get->setText(QString::number(pidValues.pVal));
ui->HELPComm_I_get->setText(QString::number(pidValues.iVal));
ui->HELPComm_FF_get->setText(QString::number(pidValues.dVal));
break;
case 2:
ui->dE_P_get->setText(QString::number(pidValues.pVal));
ui->dE_I_get->setText(QString::number(pidValues.iVal));
ui->dE_D_get->setText(QString::number(pidValues.dVal));
break;
case 3:
ui->dR_P_get->setText(QString::number(pidValues.pVal));
ui->dR_I_get->setText(QString::number(pidValues.iVal));
ui->dR_D_get->setText(QString::number(pidValues.dVal));
break;
case 4:
ui->dA_P_get->setText(QString::number(pidValues.pVal));
ui->dA_I_get->setText(QString::number(pidValues.iVal));
ui->dA_D_get->setText(QString::number(pidValues.dVal));
break;
case 8:
ui->P2dT_FF_get->setText(QString::number(pidValues.pVal));
break;
default:
qDebug() << "\nSLUGS RECEIVED AND SHOW PID type ID = " << pidValues.idx;
break;
}
}
#endif // MAVLINK_ENABLED_SLUG
void SlugsPIDControl::sendMessagePIDStatus(int PIDtype)
{
#ifdef MAVLINK_ENABLED_SLUGS
//ToDo remplace actionId values
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
mavlink_message_t msg;
qDebug() << "\n Send Message SLUGS PID with loop index = " << PIDtype;
switch(PIDtype)
{
case 0: //Air Speed PID values Request
actionSlugs.target = activeUAS->getUASID();
actionSlugs.actionId = 9;
actionSlugs.actionVal = 0;
mavlink_msg_slugs_action_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &actionSlugs);
slugsMav->sendMessage(msg);
break;
case 1: //Heigth Error lo Pitch Comm PID values request
actionSlugs.target = activeUAS->getUASID();
actionSlugs.actionId = 9;
actionSlugs.actionVal = 1;
mavlink_msg_slugs_action_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &actionSlugs);
slugsMav->sendMessage(msg);
break;
case 2://Pitch Followei PID values Request
actionSlugs.target = activeUAS->getUASID();
actionSlugs.actionId = 9;
actionSlugs.actionVal = 2;
mavlink_msg_slugs_action_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &actionSlugs);
slugsMav->sendMessage(msg);
break;
case 3:// Yaw Damper PID values request
actionSlugs.target = activeUAS->getUASID();
actionSlugs.actionId = 9;
actionSlugs.actionVal = 3;
mavlink_msg_slugs_action_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &actionSlugs);
slugsMav->sendMessage(msg);
break;
case 4: // Roll Control PID values request
actionSlugs.target = activeUAS->getUASID();
actionSlugs.actionId = 9;
actionSlugs.actionVal = 4;
mavlink_msg_slugs_action_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &actionSlugs);
slugsMav->sendMessage(msg);
break;
case 8: // Pitch to dT FF term
actionSlugs.target = activeUAS->getUASID();
actionSlugs.actionId = 9;
actionSlugs.actionVal = 8;
mavlink_msg_slugs_action_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &actionSlugs);
slugsMav->sendMessage(msg);
break;
default:
qDebug() << "\nSLUGS RECEIVED PID type ID = " << PIDtype;
break;
}
}
#else
Q_UNUSED(PIDtype);
#endif // MAVLINK_ENABLED_SLUG
}
void SlugsPIDControl::slugsGetGeneral()
{
valuesMutex.lock();
switch(counterRefreshGet)
{
case 1:
ui->dT_PID_get_pushButton->click();
break;
case 2:
ui->HELPComm_PDI_get_pushButton->click();
break;
case 3:
ui->dE_PID_get_pushButton->click();
break;
case 4:
ui->dR_PDI_get_pushButton->click();
break;
case 5:
ui->dA_PID_get_pushButton->click();
break;
case 6:
ui->Pitch2dT_PDI_get_pushButton->click();
break;
default:
refreshTimerGet->stop();
break;
}
counterRefreshGet++;
valuesMutex.unlock();
}
void SlugsPIDControl::slugsSetGeneral()
{
valuesMutex.lock();
switch(counterRefreshSet)
{
case 1:
ui->dT_PID_set_pushButton->click();
break;
case 2:
ui->HELPComm_PDI_set_pushButton->click();
break;
case 3:
ui->dE_PID_set_pushButton->click();
break;
case 4:
ui->dR_PDI_set_pushButton->click();
break;
case 5:
ui->dA_PID_set_pushButton->click();
break;
case 6:
ui->Pitch2dT_PDI_set_pushButton->click();
break;
default:
refreshTimerSet->stop();
break;
}
counterRefreshSet++;
valuesMutex.unlock();
}
void SlugsPIDControl::slugsTimerStartSet()
{
counterRefreshSet = 1;
refreshTimerSet->start();
}
void SlugsPIDControl::slugsTimerStartGet()
{
counterRefreshGet = 1;
refreshTimerGet->start();
}
void SlugsPIDControl::slugsTimerStop()
{
// refreshTimerGet->stop();
// counterRefresh = 1;
}
#include "SlugsPIDControl.h"
#include "ui_SlugsPIDControl.h"
#include <QPalette>
#include<QColor>
#include <QDebug>
#include <UASManager.h>
#include <UAS.h>
#include "LinkManager.h"
SlugsPIDControl::SlugsPIDControl(QWidget *parent) :
QWidget(parent),
ui(new Ui::SlugsPIDControl)
{
ui->setupUi(this);
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(activeUasSet(UASInterface*)));
activeUAS = NULL;
setRedColorStyle();
setGreenColorStyle();
refreshTimerGet = new QTimer(this);
refreshTimerGet->setInterval(200);//100); // 10 Hz
connect(refreshTimerGet, SIGNAL(timeout()), this, SLOT(slugsGetGeneral()));
refreshTimerSet = new QTimer(this);
refreshTimerSet->setInterval(200);//100); // 20 Hz
connect(refreshTimerSet, SIGNAL(timeout()), this, SLOT(slugsSetGeneral()));
counterRefreshGet = 1;
counterRefreshSet = 1;
}
/**
* @brief Called when the a new UAS is set to active.
*
* Called when the a new UAS is set to active.
*
* @param uas The new active UAS
*/
void SlugsPIDControl::activeUasSet(UASInterface* uas)
{
#ifdef MAVLINK_ENABLED_SLUGS
SlugsMAV* slugsMav = qobject_cast<SlugsMAV*>(uas);
if (slugsMav)
{
connect(slugsMav,SIGNAL(slugsActionAck(int,const mavlink_action_ack_t&)),this,SLOT(recibeMensaje(int,mavlink_action_ack_t)));
connect(slugsMav,SIGNAL(slugsPidValues(int,mavlink_pid_t)),this, SLOT(receivePidValues(int,mavlink_pid_t)) );
connect(ui->setGeneral_pushButton,SIGNAL(clicked()),this,SLOT(slugsTimerStartSet()));
connect(ui->getGeneral_pushButton,SIGNAL(clicked()),this,SLOT(slugsTimerStartGet()));
}
#endif // MAVLINK_ENABLED_SLUG
// Set this UAS as active if it is the first one
if(!activeUAS)
{
activeUAS = uas;
systemId = activeUAS->getUASID();
connect_editLinesPDIvalues();
}
}
/**
* @brief Connect Edition Lines for PID Values
*
* @param
*/
void SlugsPIDControl::connect_editLinesPDIvalues()
{
if(activeUAS)
{
connect_set_pushButtons();
connect_get_pushButtons();
connect_AirSpeed_LineEdit();
connect_PitchFollowei_LineEdit();
connect_RollControl_LineEdit();
connect_HeigthError_LineEdit();
connect_YawDamper_LineEdit();
connect_Pitch2dT_LineEdit();
}
}
SlugsPIDControl::~SlugsPIDControl()
{
delete ui;
}
/**
*@brief Set the background color RED style for the GroupBox PID when change lineEdit information
*
*/
void SlugsPIDControl::setRedColorStyle()
{
// GroupBox Color
QColor groupColor = QColor(231,72,28);
QString borderColor = "#FA4A4F";
groupColor = groupColor.darker(475);
REDcolorStyle = REDcolorStyle.sprintf("QGroupBox {background-color: #%02X%02X%02X; border: 5px solid %s; }",
groupColor.red(), groupColor.green(), groupColor.blue(), borderColor.toStdString().c_str());
}
/**
*@brief Set the background color GREEN style for the GroupBox PID when change lineEdit information
*
*/
void SlugsPIDControl::setGreenColorStyle()
{
// create Green color style
QColor groupColor = QColor(30,124,16);
QString borderColor = "#24AC23";
groupColor = groupColor.darker(475);
GREENcolorStyle = GREENcolorStyle.sprintf("QGroupBox {background-color: #%02X%02X%02X; border: 5px solid %s; }",
groupColor.red(), groupColor.green(), groupColor.blue(), borderColor.toStdString().c_str());
}
/**
*@brief Connection Signal and Slot of the set buttons on the widget
*/
void SlugsPIDControl::connect_set_pushButtons()
{
//ToDo connect buttons set and get. Before create the slots
connect(ui->dT_PID_set_pushButton, SIGNAL(clicked()),this,SLOT(changeColor_GREEN_AirSpeed_groupBox()));
connect(ui->dE_PID_set_pushButton,SIGNAL(clicked()),this,SLOT(changeColor_GREEN_PitchFollowei_groupBox()));
connect(ui->dA_PID_set_pushButton,SIGNAL(clicked()),this,SLOT(changeColor_GREEN_RollControl_groupBox()));
connect(ui->HELPComm_PDI_set_pushButton,SIGNAL(clicked()),this,SLOT(changeColor_GREEN_HeigthError_groupBox()));
connect(ui->dR_PDI_set_pushButton,SIGNAL(clicked()),this,SLOT(changeColor_GREEN_YawDamper_groupBox()));
connect(ui->Pitch2dT_PDI_set_pushButton,SIGNAL(clicked()),this,SLOT(changeColor_GREEN_Pitch2dT_groupBox()));
}
/**
*@brief Connection Signal and Slot of the set buttons on the widget
*/
void SlugsPIDControl::connect_get_pushButtons()
{
connect(ui->dT_PID_get_pushButton, SIGNAL(clicked()),this,SLOT(get_AirSpeed_PID()));
connect(ui->dE_PID_get_pushButton,SIGNAL(clicked()),this,SLOT(get_PitchFollowei_PID()));
connect(ui->dR_PDI_get_pushButton,SIGNAL(clicked()),this,SLOT(get_YawDamper_PID()));
connect(ui->dA_PID_get_pushButton,SIGNAL(clicked()),this,SLOT(get_RollControl_PID()));
connect(ui->Pitch2dT_PDI_get_pushButton,SIGNAL(clicked()),this,SLOT(get_Pitch2dT_PID()));
connect(ui->HELPComm_PDI_get_pushButton,SIGNAL(clicked()),this,SLOT(get_HeigthError_PID()));
}
// Functions for Air Speed GroupBox
void SlugsPIDControl::connect_AirSpeed_LineEdit()
{
connect(ui->dT_P_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_AirSpeed_groupBox(QString)));
connect(ui->dT_I_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_AirSpeed_groupBox(QString)));
connect(ui->dT_D_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_AirSpeed_groupBox(QString)));
}
void SlugsPIDControl::changeColor_RED_AirSpeed_groupBox(QString text)
{
Q_UNUSED(text);
ui->AirSpeedHold_groupBox->setStyleSheet(REDcolorStyle);
}
void SlugsPIDControl::changeColor_GREEN_AirSpeed_groupBox()
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
//create the packet
#ifdef MAVLINK_ENABLED_SLUGS
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 0;
pidMessage.pVal = ui->dT_P_set->text().toFloat();
pidMessage.iVal = ui->dT_I_set->text().toFloat();
pidMessage.dVal = ui->dT_D_set->text().toFloat();
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->AirSpeedHold_groupBox->setStyleSheet(GREENcolorStyle);
}
}
void SlugsPIDControl::get_AirSpeed_PID()
{
qDebug() << "\nSend Message = Air Speed ";
sendMessagePIDStatus(0);
}
// Functions for PitchFollowei GroupBox
void SlugsPIDControl::connect_PitchFollowei_LineEdit()
{
connect(ui->dE_P_set, SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_PitchFollowei_groupBox(QString)));
connect(ui->dE_I_set, SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_PitchFollowei_groupBox(QString)));
connect(ui->dE_D_set, SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_PitchFollowei_groupBox(QString)));
}
void SlugsPIDControl::changeColor_RED_PitchFollowei_groupBox(QString text)
{
Q_UNUSED(text);
ui->PitchFlowei_groupBox->setStyleSheet(REDcolorStyle);
}
void SlugsPIDControl::changeColor_GREEN_PitchFollowei_groupBox()
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 2;
pidMessage.pVal = ui->dE_P_set->text().toFloat();
pidMessage.iVal = ui->dE_I_set->text().toFloat();
pidMessage.dVal = ui->dE_D_set->text().toFloat();
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->PitchFlowei_groupBox->setStyleSheet(GREENcolorStyle);
}
}
void SlugsPIDControl::get_PitchFollowei_PID()
{
qDebug() << "\nSend Message = Pitch Followei ";
sendMessagePIDStatus(2);
}
// Functions for Roll Control GroupBox
/**
* @brief Change color style to red when PID values of Roll Control are edited
*
*
* @param
*/
void SlugsPIDControl::changeColor_RED_RollControl_groupBox(QString text)
{
Q_UNUSED(text);
ui->RollControl_groupBox->setStyleSheet(REDcolorStyle);
}
/**
* @brief Change color style to green when PID values of Roll Control are send to UAS
*
* @param
*/
void SlugsPIDControl::changeColor_GREEN_RollControl_groupBox()
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 4;
pidMessage.pVal = ui->dA_P_set->text().toFloat();
pidMessage.iVal = ui->dA_I_set->text().toFloat();
pidMessage.dVal = ui->dA_D_set->text().toFloat();
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->RollControl_groupBox->setStyleSheet(GREENcolorStyle);
}
}
/**
* @brief Connects the SIGNALS from the editline to SLOT RollControl_groupBox
*
* @param
*/
void SlugsPIDControl::connect_RollControl_LineEdit()
{
connect(ui->dA_P_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_RollControl_groupBox(QString)));
connect(ui->dA_I_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_RollControl_groupBox(QString)));
connect(ui->dA_D_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_RollControl_groupBox(QString)));
}
void SlugsPIDControl::get_RollControl_PID()
{
qDebug() << "\nSend Message = Roll Control ";
sendMessagePIDStatus(4);
}
// Functions for Heigth Error GroupBox
/**
* @brief Change color style to red when PID values of Heigth Error are edited
*
*
* @param
*/
void SlugsPIDControl::changeColor_RED_HeigthError_groupBox(QString text)
{
Q_UNUSED(text);
ui->HeightErrorLoPitch_groupBox->setStyleSheet(REDcolorStyle);
}
/**
* @brief Change color style to green when PID values of Heigth Error are send to UAS
*
* @param
*/
void SlugsPIDControl::changeColor_GREEN_HeigthError_groupBox()
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 1;
pidMessage.pVal = ui->HELPComm_P_set->text().toFloat();
pidMessage.iVal = ui->HELPComm_I_set->text().toFloat();
pidMessage.dVal = ui->HELPComm_FF_set->text().toFloat();
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->HeightErrorLoPitch_groupBox->setStyleSheet(GREENcolorStyle);
}
}
/**
* @brief Connects the SIGNALS from the editline to SLOT HeigthError_groupBox
*
* @param
*/
void SlugsPIDControl::connect_HeigthError_LineEdit()
{
connect(ui->HELPComm_P_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_HeigthError_groupBox(QString)));
connect(ui->HELPComm_I_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_HeigthError_groupBox(QString)));
connect(ui->HELPComm_FF_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_HeigthError_groupBox(QString)));
}
void SlugsPIDControl::get_HeigthError_PID()
{
qDebug() << "\nSend Message = Heigth Error ";
sendMessagePIDStatus(1);
}
// Functions for Yaw Damper GroupBox
/**
* @brief Change color style to red when PID values of Yaw Damper are edited
*
*
* @param
*/
void SlugsPIDControl::changeColor_RED_YawDamper_groupBox(QString text)
{
Q_UNUSED(text);
ui->YawDamper_groupBox->setStyleSheet(REDcolorStyle);
}
/**
* @brief Change color style to green when PID values of Yaw Damper are send to UAS
*
* @param
*/
void SlugsPIDControl::changeColor_GREEN_YawDamper_groupBox()
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 3;
pidMessage.pVal = ui->dR_P_set->text().toFloat();
pidMessage.iVal = ui->dR_I_set->text().toFloat();
pidMessage.dVal = ui->dR_D_set->text().toFloat();
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->YawDamper_groupBox->setStyleSheet(GREENcolorStyle);
}
}
/**
* @brief Connects the SIGNALS from the editline to SLOT YawDamper_groupBox
*
* @param
*/
void SlugsPIDControl::connect_YawDamper_LineEdit()
{
connect(ui->dR_P_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_YawDamper_groupBox(QString)));
connect(ui->dR_I_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_YawDamper_groupBox(QString)));
connect(ui->dR_D_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_YawDamper_groupBox(QString)));
}
void SlugsPIDControl::get_YawDamper_PID()
{
qDebug() << "\nSend Message = Yaw Damper ";
sendMessagePIDStatus(3);
}
// Functions for Pitch to dT GroupBox
/**
* @brief Change color style to red when PID values of Pitch to dT are edited
*
*
* @param
*/
void SlugsPIDControl::changeColor_RED_Pitch2dT_groupBox(QString text)
{
Q_UNUSED(text);
ui->Pitch2dTFFterm_groupBox->setStyleSheet(REDcolorStyle);
}
/**
* @brief Change color style to green when PID values of Pitch to dT are send to UAS
*
* @param
*/
void SlugsPIDControl::changeColor_GREEN_Pitch2dT_groupBox()
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 8;
pidMessage.pVal = ui->P2dT_FF_set->text().toFloat();
pidMessage.iVal = 0;//ui->dR_I_set->text().toFloat();
pidMessage.dVal = 0;//ui->dR_D_set->text().toFloat();
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->Pitch2dTFFterm_groupBox->setStyleSheet(GREENcolorStyle);
}
}
/**
* @brief Connects the SIGNALS from the editline to SLOT Pitch2dT_groupBox
*
* @param
*/
void SlugsPIDControl::connect_Pitch2dT_LineEdit()
{
connect(ui->P2dT_FF_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_Pitch2dT_groupBox(QString)));
}
void SlugsPIDControl::get_Pitch2dT_PID()
{
qDebug() << "\nSend Message = Pitch to dT ";
sendMessagePIDStatus(8);
}
#ifdef MAVLINK_ENABLED_SLUGS
void SlugsPIDControl::recibeMensaje(int systemId, const mavlink_action_ack_t& action)
{
Q_UNUSED(systemId);
ui->recepcion_label->setText(QString::number(action.action) + ":" + QString::number(action.result));
}
void SlugsPIDControl::receivePidValues(int systemId, const mavlink_pid_t &pidValues)
{
Q_UNUSED(systemId);
qDebug() << "\nACTUALIZANDO GUI = " << pidValues.idx;
switch(pidValues.idx)
{
case 0:
ui->dT_P_get->setText(QString::number(pidValues.pVal));
ui->dT_I_get->setText(QString::number(pidValues.iVal));
ui->dT_D_get->setText(QString::number(pidValues.dVal));
break;
case 1:
ui->HELPComm_P_get->setText(QString::number(pidValues.pVal));
ui->HELPComm_I_get->setText(QString::number(pidValues.iVal));
ui->HELPComm_FF_get->setText(QString::number(pidValues.dVal));
break;
case 2:
ui->dE_P_get->setText(QString::number(pidValues.pVal));
ui->dE_I_get->setText(QString::number(pidValues.iVal));
ui->dE_D_get->setText(QString::number(pidValues.dVal));
break;
case 3:
ui->dR_P_get->setText(QString::number(pidValues.pVal));
ui->dR_I_get->setText(QString::number(pidValues.iVal));
ui->dR_D_get->setText(QString::number(pidValues.dVal));
break;
case 4:
ui->dA_P_get->setText(QString::number(pidValues.pVal));
ui->dA_I_get->setText(QString::number(pidValues.iVal));
ui->dA_D_get->setText(QString::number(pidValues.dVal));
break;
case 8:
ui->P2dT_FF_get->setText(QString::number(pidValues.pVal));
break;
default:
qDebug() << "\nSLUGS RECEIVED AND SHOW PID type ID = " << pidValues.idx;
break;
}
}
#endif // MAVLINK_ENABLED_SLUG
void SlugsPIDControl::sendMessagePIDStatus(int PIDtype)
{
#ifdef MAVLINK_ENABLED_SLUGS
//ToDo remplace actionId values
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
mavlink_message_t msg;
qDebug() << "\n Send Message SLUGS PID with loop index = " << PIDtype;
switch(PIDtype)
{
case 0: //Air Speed PID values Request
actionSlugs.target = activeUAS->getUASID();
actionSlugs.actionId = 9;
actionSlugs.actionVal = 0;
mavlink_msg_slugs_action_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &actionSlugs);
slugsMav->sendMessage(msg);
break;
case 1: //Heigth Error lo Pitch Comm PID values request
actionSlugs.target = activeUAS->getUASID();
actionSlugs.actionId = 9;
actionSlugs.actionVal = 1;
mavlink_msg_slugs_action_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &actionSlugs);
slugsMav->sendMessage(msg);
break;
case 2://Pitch Followei PID values Request
actionSlugs.target = activeUAS->getUASID();
actionSlugs.actionId = 9;
actionSlugs.actionVal = 2;
mavlink_msg_slugs_action_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &actionSlugs);
slugsMav->sendMessage(msg);
break;
case 3:// Yaw Damper PID values request
actionSlugs.target = activeUAS->getUASID();
actionSlugs.actionId = 9;
actionSlugs.actionVal = 3;
mavlink_msg_slugs_action_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &actionSlugs);
slugsMav->sendMessage(msg);
break;
case 4: // Roll Control PID values request
actionSlugs.target = activeUAS->getUASID();
actionSlugs.actionId = 9;
actionSlugs.actionVal = 4;
mavlink_msg_slugs_action_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &actionSlugs);
slugsMav->sendMessage(msg);
break;
case 8: // Pitch to dT FF term
actionSlugs.target = activeUAS->getUASID();
actionSlugs.actionId = 9;
actionSlugs.actionVal = 8;
mavlink_msg_slugs_action_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &actionSlugs);
slugsMav->sendMessage(msg);
break;
default:
qDebug() << "\nSLUGS RECEIVED PID type ID = " << PIDtype;
break;
}
}
#else
Q_UNUSED(PIDtype);
#endif // MAVLINK_ENABLED_SLUG
}
void SlugsPIDControl::slugsGetGeneral()
{
valuesMutex.lock();
switch(counterRefreshGet)
{
case 1:
ui->dT_PID_get_pushButton->click();
break;
case 2:
ui->HELPComm_PDI_get_pushButton->click();
break;
case 3:
ui->dE_PID_get_pushButton->click();
break;
case 4:
ui->dR_PDI_get_pushButton->click();
break;
case 5:
ui->dA_PID_get_pushButton->click();
break;
case 6:
ui->Pitch2dT_PDI_get_pushButton->click();
break;
default:
refreshTimerGet->stop();
break;
}
counterRefreshGet++;
valuesMutex.unlock();
}
void SlugsPIDControl::slugsSetGeneral()
{
valuesMutex.lock();
switch(counterRefreshSet)
{
case 1:
ui->dT_PID_set_pushButton->click();
break;
case 2:
ui->HELPComm_PDI_set_pushButton->click();
break;
case 3:
ui->dE_PID_set_pushButton->click();
break;
case 4:
ui->dR_PDI_set_pushButton->click();
break;
case 5:
ui->dA_PID_set_pushButton->click();
break;
case 6:
ui->Pitch2dT_PDI_set_pushButton->click();
break;
default:
refreshTimerSet->stop();
break;
}
counterRefreshSet++;
valuesMutex.unlock();
}
void SlugsPIDControl::slugsTimerStartSet()
{
counterRefreshSet = 1;
refreshTimerSet->start();
}
void SlugsPIDControl::slugsTimerStartGet()
{
counterRefreshGet = 1;
refreshTimerGet->start();
}
void SlugsPIDControl::slugsTimerStop()
{
// refreshTimerGet->stop();
// counterRefresh = 1;
}
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
(c) 2009 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
This file is part of the PIXHAWK project
PIXHAWK is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
PIXHAWK is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Implementation of class UASInfoWidget
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#include <QtGlobal>
#include <float.h>
#include <UASInfoWidget.h>
#include <UASManager.h>
#include <MG.h>
#include <QTimer>
#include <QDir>
#include <cstdlib>
#include <cmath>
#include <QDebug>
UASInfoWidget::UASInfoWidget(QWidget *parent, QString name) : QWidget(parent)
{
ui.setupUi(this);
this->name = name;
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
activeUAS = NULL;
//instruments = new QMap<QString, QProgressBar*>();
// Set default battery type
// setBattery(0, LIPOLY, 3);
startTime = MG::TIME::getGroundTimeNow();
// startVoltage = 0.0f;
// lastChargeLevel = 0.5f;
// lastRemainingTime = 1;
// Set default values
/** Set two voltage decimals and zero charge level decimals **/
this->voltageDecimals = 2;
this->loadDecimals = 2;
this->voltage = 0;
this->chargeLevel = 0;
this->load = 0;
receiveLoss = 0;
sendLoss = 0;
changed = true;
errors = QMap<QString, int>();
updateTimer = new QTimer(this);
connect(updateTimer, SIGNAL(timeout()), this, SLOT(refresh()));
updateTimer->start(updateInterval);
this->setVisible(false);
}
UASInfoWidget::~UASInfoWidget()
{
}
void UASInfoWidget::showEvent(QShowEvent* event)
{
// React only to internal (pre-display)
// events
Q_UNUSED(event);
updateTimer->start(updateInterval);
}
void UASInfoWidget::hideEvent(QHideEvent* event)
{
// React only to internal (pre-display)
// events
Q_UNUSED(event);
updateTimer->stop();
}
void UASInfoWidget::addUAS(UASInterface* uas)
{
if (uas != NULL)
{
connect(uas, SIGNAL(batteryChanged(UASInterface*,double,double,int)), this, SLOT(updateBattery(UASInterface*,double,double,int)));
connect(uas, SIGNAL(dropRateChanged(int,float)), this, SLOT(updateReceiveLoss(int,float)));
connect(uas, SIGNAL(loadChanged(UASInterface*, double)), this, SLOT(updateCPULoad(UASInterface*,double)));
connect(uas, SIGNAL(errCountChanged(int,QString,QString,int)), this, SLOT(updateErrorCount(int,QString,QString,int)));
// Set this UAS as active if it is the first one
if (activeUAS == 0) activeUAS = uas;
}
}
void UASInfoWidget::setActiveUAS(UASInterface* uas)
{
activeUAS = uas;
}
void UASInfoWidget::updateBattery(UASInterface* uas, double voltage, double percent, int seconds)
{
setVoltage(uas, voltage);
setChargeLevel(uas, percent);
setTimeRemaining(uas, seconds);
}
void UASInfoWidget::updateErrorCount(int uasid, QString component, QString device, int count)
{
//qDebug() << __FILE__ << __LINE__ << activeUAS->getUASID() << "=" << uasid;
if (activeUAS->getUASID() == uasid)
{
errors.remove(component + ":" + device);
errors.insert(component + ":" + device, count);
}
}
/**
*
*/
void UASInfoWidget::updateCPULoad(UASInterface* uas, double load)
{
if (activeUAS == uas)
{
this->load = load;
}
}
void UASInfoWidget::updateReceiveLoss(int uasId, float receiveLoss)
{
Q_UNUSED(uasId);
this->receiveLoss = this->receiveLoss * 0.8f + receiveLoss * 0.2f;
}
/**
The send loss is typically calculated on the GCS based on packets
that were received scrambled from the MAV
*/
void UASInfoWidget::updateSendLoss(int uasId, float sendLoss)
{
Q_UNUSED(uasId);
this->sendLoss = this->sendLoss * 0.8f + sendLoss * 0.2f;
}
void UASInfoWidget::setVoltage(UASInterface* uas, double voltage)
{
Q_UNUSED(uas);
this->voltage = voltage;
}
void UASInfoWidget::setChargeLevel(UASInterface* uas, double chargeLevel)
{
if (activeUAS == uas)
{
this->chargeLevel = chargeLevel;
}
}
void UASInfoWidget::setTimeRemaining(UASInterface* uas, double seconds)
{
if (activeUAS == uas)
{
this->timeRemaining = seconds;
}
}
void UASInfoWidget::refresh()
{
ui.voltageLabel->setText(QString::number(this->voltage, 'f', voltageDecimals));
ui.batteryBar->setValue(qMax(0,qMin(static_cast<int>(this->chargeLevel), 100)));
ui.loadLabel->setText(QString::number(this->load, 'f', loadDecimals));
ui.loadBar->setValue(qMax(0, qMin(static_cast<int>(this->load), 100)));
ui.receiveLossBar->setValue(qMax(0, qMin(static_cast<int>(receiveLoss), 100)));
ui.receiveLossLabel->setText(QString::number(receiveLoss, 'f', 2));
ui.sendLossBar->setValue(sendLoss);
ui.sendLossLabel->setText(QString::number(sendLoss, 'f', 2));
QString errorString;
QMapIterator<QString, int> i(errors);
while (i.hasNext())
{
i.next();
errorString += QString(i.key() + ": %1 ").arg(i.value());
// FIXME
errorString.replace("IMU:", "");
}
ui.errorLabel->setText(errorString);
}
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
(c) 2009 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
This file is part of the PIXHAWK project
PIXHAWK is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
PIXHAWK is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Implementation of class UASInfoWidget
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#include <QtGlobal>
#include <float.h>
#include <UASInfoWidget.h>
#include <UASManager.h>
#include <MG.h>
#include <QTimer>
#include <QDir>
#include <cstdlib>
#include <cmath>
#include <QDebug>
UASInfoWidget::UASInfoWidget(QWidget *parent, QString name) : QWidget(parent)
{
ui.setupUi(this);
this->name = name;
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
activeUAS = NULL;
//instruments = new QMap<QString, QProgressBar*>();
// Set default battery type
// setBattery(0, LIPOLY, 3);
startTime = MG::TIME::getGroundTimeNow();
// startVoltage = 0.0f;
// lastChargeLevel = 0.5f;
// lastRemainingTime = 1;
// Set default values
/** Set two voltage decimals and zero charge level decimals **/
this->voltageDecimals = 2;
this->loadDecimals = 2;
this->voltage = 0;
this->chargeLevel = 0;
this->load = 0;
receiveLoss = 0;
sendLoss = 0;
changed = true;
errors = QMap<QString, int>();
updateTimer = new QTimer(this);
connect(updateTimer, SIGNAL(timeout()), this, SLOT(refresh()));
updateTimer->start(updateInterval);
this->setVisible(false);
}
UASInfoWidget::~UASInfoWidget()
{
}
void UASInfoWidget::showEvent(QShowEvent* event)
{
// React only to internal (pre-display)
// events
Q_UNUSED(event);
updateTimer->start(updateInterval);
}
void UASInfoWidget::hideEvent(QHideEvent* event)
{
// React only to internal (pre-display)
// events
Q_UNUSED(event);
updateTimer->stop();
}
void UASInfoWidget::addUAS(UASInterface* uas)
{
if (uas != NULL)
{
connect(uas, SIGNAL(batteryChanged(UASInterface*,double,double,int)), this, SLOT(updateBattery(UASInterface*,double,double,int)));
connect(uas, SIGNAL(dropRateChanged(int,float)), this, SLOT(updateReceiveLoss(int,float)));
connect(uas, SIGNAL(loadChanged(UASInterface*, double)), this, SLOT(updateCPULoad(UASInterface*,double)));
connect(uas, SIGNAL(errCountChanged(int,QString,QString,int)), this, SLOT(updateErrorCount(int,QString,QString,int)));
// Set this UAS as active if it is the first one
if (activeUAS == 0) activeUAS = uas;
}
}
void UASInfoWidget::setActiveUAS(UASInterface* uas)
{
activeUAS = uas;
}
void UASInfoWidget::updateBattery(UASInterface* uas, double voltage, double percent, int seconds)
{
setVoltage(uas, voltage);
setChargeLevel(uas, percent);
setTimeRemaining(uas, seconds);
}
void UASInfoWidget::updateErrorCount(int uasid, QString component, QString device, int count)
{
//qDebug() << __FILE__ << __LINE__ << activeUAS->getUASID() << "=" << uasid;
if (activeUAS->getUASID() == uasid)
{
errors.remove(component + ":" + device);
errors.insert(component + ":" + device, count);
}
}
/**
*
*/
void UASInfoWidget::updateCPULoad(UASInterface* uas, double load)
{
if (activeUAS == uas)
{
this->load = load;
}
}
void UASInfoWidget::updateReceiveLoss(int uasId, float receiveLoss)
{
Q_UNUSED(uasId);
this->receiveLoss = this->receiveLoss * 0.8f + receiveLoss * 0.2f;
}
/**
The send loss is typically calculated on the GCS based on packets
that were received scrambled from the MAV
*/
void UASInfoWidget::updateSendLoss(int uasId, float sendLoss)
{
Q_UNUSED(uasId);
this->sendLoss = this->sendLoss * 0.8f + sendLoss * 0.2f;
}
void UASInfoWidget::setVoltage(UASInterface* uas, double voltage)
{
Q_UNUSED(uas);
this->voltage = voltage;
}
void UASInfoWidget::setChargeLevel(UASInterface* uas, double chargeLevel)
{
if (activeUAS == uas)
{
this->chargeLevel = chargeLevel;
}
}
void UASInfoWidget::setTimeRemaining(UASInterface* uas, double seconds)
{
if (activeUAS == uas)
{
this->timeRemaining = seconds;
}
}
void UASInfoWidget::refresh()
{
ui.voltageLabel->setText(QString::number(this->voltage, 'f', voltageDecimals));
ui.batteryBar->setValue(qMax(0,qMin(static_cast<int>(this->chargeLevel), 100)));
ui.loadLabel->setText(QString::number(this->load, 'f', loadDecimals));
ui.loadBar->setValue(qMax(0, qMin(static_cast<int>(this->load), 100)));
ui.receiveLossBar->setValue(qMax(0, qMin(static_cast<int>(receiveLoss), 100)));
ui.receiveLossLabel->setText(QString::number(receiveLoss, 'f', 2));
ui.sendLossBar->setValue(sendLoss);
ui.sendLossLabel->setText(QString::number(sendLoss, 'f', 2));
ui.label_5->setText(QString::number(this->load, 'f', loadDecimals));
ui.progressBar->setValue(qMax(0, qMin(static_cast<int>(this->load), 100)));
QString errorString;
QMapIterator<QString, int> i(errors);
while (i.hasNext())
{
i.next();
errorString += QString(i.key() + ": %1 ").arg(i.value());
// FIXME
errorString.replace("IMU:", "");
}
ui.errorLabel->setText(errorString);
}
......@@ -194,7 +194,7 @@ void UASView::updateMode(int sysId, QString status, QString description)
{
Q_UNUSED(description);
int aa=this->uas->getUASID();
//int aa=this->uas->getUASID();
if (sysId == this->uas->getUASID()) m_ui->modeLabel->setText(status);
m_ui->modeLabel->setText(status);
......
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