Commit 4e7f33e3 authored by jaxxzer's avatar jaxxzer Committed by GitHub

Merge branch 'master' into hotplugging

parents be4a4f87 5451d223
......@@ -221,7 +221,7 @@ WindowsBuild {
#
ReleaseBuild {
DEFINES += QT_NO_DEBUG
DEFINES += QT_NO_DEBUG QT_MESSAGELOGCONTEXT
CONFIG += force_debug_info # Enable debugging symbols on release builds
!iOSBuild {
CONFIG += ltcg # Turn on link time code generation
......
......@@ -43,7 +43,8 @@ QGroundControl builds are supported for OSX, Linux, Windows, iOS and Android. QG
###### Install QT
You need to install Qt as described below instead of using pre-built packages from say, a Linux distribution because QGroundControl needs access to private Qt headers.
* Download the [Qt installer](http://www.qt.io/download-open-source)
* Make sure to install Qt version **5.5.1** NOT 5.4.x, 5.6.x, 5.7.x, etc.
* Make sure to install Qt version **5.5.1** NOT 5.4.x, 5.6.x, 5.7.x, etc.
* If you don't install the full Qt 5.5 make sure you install Qt Location and Qt Quick Controls.
* Ubuntu: Set the downloaded file to executable using:`chmod +x`. Install to default location for use with ./qgroundcontrol-start.sh. If you install Qt to a non-default location you will need to modify qgroundcontrol-start.sh in order to run downloaded builds.
* Windows: Default installer not quite correct, use [this](http://download.qt.io/official_releases/qt/5.5/5.5.1/qt-opensource-windows-x86-msvc2013-5.5.1.exe) instead
......
......@@ -2,85 +2,87 @@
<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
<plist version="1.0">
<dict>
<key>CFBundleDisplayName</key>
<string>QGroundControl</string>
<key>CFBundleExecutable</key>
<string>$(EXECUTABLE_NAME)</string>
<key>NSHumanReadableCopyright</key>
<string>Open Source Flight Systems GmbH - Internal Build</string>
<key>CFBundleIconFile</key>
<string></string>
<key>CFBundleIdentifier</key>
<string>org.QGroundControl.qgc</string>
<key>CFBundleName</key>
<string>$(PRODUCT_NAME)</string>
<key>CFBundlePackageType</key>
<string>APPL</string>
<key>CFBundleShortVersionString</key>
<string>0.0.0</string>
<key>CFBundleSignature</key>
<string>????</string>
<key>CFBundleVersion</key>
<string>1</string>
<key>LSRequiresIPhoneOS</key>
<true/>
<key>UILaunchStoryboardName</key>
<string>QGCLaunchScreen</string>
<key>UIRequiresFullScreen</key>
<true/>
<key>CFBundleInfoDictionaryVersion</key>
<string>6.0</string>
<key>ForAppStore</key>
<string>No</string>
<key>NSLocationUsageDescription</key>
<string>Ground Station Location</string>
<key>NSLocationWhenInUseUsageDescription</key>
<string>Ground Station Location</string>
<key>UISupportedInterfaceOrientations</key>
<array>
<string>UIInterfaceOrientationLandscapeLeft</string>
<string>UIInterfaceOrientationLandscapeRight</string>
</array>
<key>CFBundleIcons</key>
<dict>
<key>CFBundlePrimaryIcon</key>
<dict>
<key>CFBundleIconFiles</key>
<array>
<string>AppIcon29x29.png</string>
<string>AppIcon29x29@2x.png</string>
<string>AppIcon40x40@2x.png</string>
<string>AppIcon57x57.png</string>
<string>AppIcon57x57@2x.png</string>
<string>AppIcon60x60@2x.png</string>
</array>
</dict>
</dict>
<key>CFBundleIcons~ipad</key>
<dict>
<key>CFBundlePrimaryIcon</key>
<dict>
<key>CFBundleIconFiles</key>
<array>
<string>AppIcon29x29.png</string>
<string>AppIcon29x29@2x.png</string>
<string>AppIcon40x40@2x.png</string>
<string>AppIcon57x57.png</string>
<string>AppIcon57x57@2x.png</string>
<string>AppIcon60x60@2x.png</string>
<string>AppIcon29x29~ipad.png</string>
<string>AppIcon29x29@2x~ipad.png</string>
<string>AppIcon40x40~ipad.png</string>
<string>AppIcon40x40@2x~ipad.png</string>
<string>AppIcon50x50~ipad.png</string>
<string>AppIcon50x50@2x~ipad.png</string>
<string>AppIcon72x72~ipad.png</string>
<string>AppIcon72x72@2x~ipad.png</string>
<string>AppIcon76x76~ipad.png</string>
<string>AppIcon76x76@2x~ipad.png</string>
<string>AppIcon83.5x83.5@2x~ipad.png</string>
</array>
</dict>
</dict>
<key>NSCameraUsageDescription</key>
<string>QGC uses UVC devices for video streaming.</string>
<key>CFBundleDisplayName</key>
<string>QGroundControl</string>
<key>CFBundleExecutable</key>
<string>$(EXECUTABLE_NAME)</string>
<key>NSHumanReadableCopyright</key>
<string>Open Source Flight Systems GmbH - Internal Build</string>
<key>CFBundleIconFile</key>
<string></string>
<key>CFBundleIdentifier</key>
<string>org.QGroundControl.qgc</string>
<key>CFBundleName</key>
<string>$(PRODUCT_NAME)</string>
<key>CFBundlePackageType</key>
<string>APPL</string>
<key>CFBundleShortVersionString</key>
<string>0.0.0</string>
<key>CFBundleSignature</key>
<string>????</string>
<key>CFBundleVersion</key>
<string>1</string>
<key>LSRequiresIPhoneOS</key>
<true/>
<key>UILaunchStoryboardName</key>
<string>QGCLaunchScreen</string>
<key>UIRequiresFullScreen</key>
<true/>
<key>CFBundleInfoDictionaryVersion</key>
<string>6.0</string>
<key>ForAppStore</key>
<string>No</string>
<key>NSLocationUsageDescription</key>
<string>Ground Station Location</string>
<key>NSLocationWhenInUseUsageDescription</key>
<string>Ground Station Location</string>
<key>UISupportedInterfaceOrientations</key>
<array>
<string>UIInterfaceOrientationLandscapeLeft</string>
<string>UIInterfaceOrientationLandscapeRight</string>
</array>
<key>CFBundleIcons</key>
<dict>
<key>CFBundlePrimaryIcon</key>
<dict>
<key>CFBundleIconFiles</key>
<array>
<string>AppIcon29x29.png</string>
<string>AppIcon29x29@2x.png</string>
<string>AppIcon40x40@2x.png</string>
<string>AppIcon57x57.png</string>
<string>AppIcon57x57@2x.png</string>
<string>AppIcon60x60@2x.png</string>
</array>
</dict>
</dict>
<key>CFBundleIcons~ipad</key>
<dict>
<key>CFBundlePrimaryIcon</key>
<dict>
<key>CFBundleIconFiles</key>
<array>
<string>AppIcon29x29.png</string>
<string>AppIcon29x29@2x.png</string>
<string>AppIcon40x40@2x.png</string>
<string>AppIcon57x57.png</string>
<string>AppIcon57x57@2x.png</string>
<string>AppIcon60x60@2x.png</string>
<string>AppIcon29x29~ipad.png</string>
<string>AppIcon29x29@2x~ipad.png</string>
<string>AppIcon40x40~ipad.png</string>
<string>AppIcon40x40@2x~ipad.png</string>
<string>AppIcon50x50~ipad.png</string>
<string>AppIcon50x50@2x~ipad.png</string>
<string>AppIcon72x72~ipad.png</string>
<string>AppIcon72x72@2x~ipad.png</string>
<string>AppIcon76x76~ipad.png</string>
<string>AppIcon76x76@2x~ipad.png</string>
<string>AppIcon83.5x83.5@2x~ipad.png</string>
</array>
</dict>
</dict>
</dict>
</plist>
......@@ -100,9 +100,6 @@
<file alias="attitudeDial.svg">src/FlightMap/Images/attitudeDial.svg</file>
<file alias="attitudeInstrument.svg">src/FlightMap/Images/attitudeInstrument.svg</file>
<file alias="attitudePointer.svg">src/FlightMap/Images/attitudePointer.svg</file>
<file alias="buttonHome.svg">src/FlightMap/Images/buttonHome.svg</file>
<file alias="buttonMore.svg">src/FlightMap/Images/buttonMore.svg</file>
<file alias="compassInstrumentAirplane.svg">src/FlightMap/Images/compassInstrumentAirplane.svg</file>
<file alias="compassInstrumentArrow.svg">src/FlightMap/Images/compassInstrumentArrow.svg</file>
<file alias="compassInstrumentDial.svg">src/FlightMap/Images/compassInstrumentDial.svg</file>
<file alias="crossHair.svg">src/FlightMap/Images/crossHair.svg</file>
......@@ -113,13 +110,10 @@
<file alias="scale_end.png">src/FlightMap/Images/scale_end.png</file>
<file alias="scaleLight.png">src/FlightMap/Images/scaleLight.png</file>
<file alias="scale_endLight.png">src/FlightMap/Images/scale_endLight.png</file>
<file alias="airplaneOutline.svg">src/FlightMap/Images/airplaneOutline.svg</file>
<file alias="airplaneOpaque.svg">src/FlightMap/Images/airplaneOpaque.svg</file>
<file alias="vehicleArrowOutline.svg">src/FlightMap/Images/vehicleArrowOutline.svg</file>
<file alias="vehicleArrowOpaque.svg">src/FlightMap/Images/vehicleArrowOpaque.svg</file>
<file alias="ZoomPlus.svg">src/FlightMap/Images/ZoomPlus.svg</file>
<file alias="ZoomMinus.svg">src/FlightMap/Images/ZoomMinus.svg</file>
<file alias="ArrowHead.svg">src/FlightMap/Images/ArrowHead.svg</file>
<file alias="Help.svg">src/FlightMap/Images/Help.svg</file>
<file alias="HelpBlack.svg">src/FlightMap/Images/HelpBlack.svg</file>
<file alias="MapAddMission.svg">src/FlightMap/Images/MapAddMission.svg</file>
......@@ -156,6 +150,7 @@
<file alias="Signal100.svg">src/ui/toolbar/Images/Signal100.svg</file>
<file alias="TelemRSSI.svg">src/ui/toolbar/Images/TelemRSSI.svg</file>
<file alias="Yield.svg">src/ui/toolbar/Images/Yield.svg</file>
<file alias="CameraIcon.svg">src/ui/toolbar/Images/CameraIcon.svg</file>
<file alias="CogWheel.svg">src/MissionManager/CogWheel.svg</file>
<file alias="StationMode.svg">src/AutoPilotPlugins/Common/Images/StationMode.svg</file>
<file alias="APMode.svg">src/AutoPilotPlugins/Common/Images/APMode.svg</file>
......@@ -253,17 +248,6 @@
<file alias="radioThrottleDown.png">resources/calibration/mode2/radioThrottleDown.png</file>
<file alias="radioSwitchMinMax.png">resources/calibration/mode2/radioSwitchMinMax.png</file>
</qresource>
<qresource prefix="/qml/calibration/joystick">
<file alias="joystickCenter.png">resources/calibration/joystick/joystickCenter.png</file>
<file alias="joystickRollLeft.png">resources/calibration/joystick/joystickRollLeft.png</file>
<file alias="joystickRollRight.png">resources/calibration/joystick/joystickRollRight.png</file>
<file alias="joystickPitchUp.png">resources/calibration/joystick/joystickPitchUp.png</file>
<file alias="joystickPitchDown.png">resources/calibration/joystick/joystickPitchDown.png</file>
<file alias="joystickYawLeft.png">resources/calibration/joystick/joystickYawLeft.png</file>
<file alias="joystickYawRight.png">resources/calibration/joystick/joystickYawRight.png</file>
<file alias="joystickThrottleUp.png">resources/calibration/joystick/joystickThrottleUp.png</file>
<file alias="joystickThrottleDown.png">resources/calibration/joystick/joystickThrottleDown.png</file>
</qresource>
<qresource prefix="/db/mapping/joystick">
<file alias="gamecontrollerdb.txt">resources/SDL_GameControllerDB/gamecontrollerdb.txt</file>
</qresource>
......@@ -277,4 +261,48 @@
<qresource prefix="/opengl">
<file>resources/opengl/buglist.json</file>
</qresource>
<qresource prefix="/qml/calibration/joystick/mode1">
<file alias="joystickCenter.png">resources/calibration/joystick/mode1/joystickCenter.png</file>
<file alias="joystickPitchDown.png">resources/calibration/joystick/mode1/joystickPitchDown.png</file>
<file alias="joystickPitchUp.png">resources/calibration/joystick/mode1/joystickPitchUp.png</file>
<file alias="joystickRollLeft.png">resources/calibration/joystick/mode1/joystickRollLeft.png</file>
<file alias="joystickRollRight.png">resources/calibration/joystick/mode1/joystickRollRight.png</file>
<file alias="joystickThrottleDown.png">resources/calibration/joystick/mode1/joystickThrottleDown.png</file>
<file alias="joystickThrottleUp.png">resources/calibration/joystick/mode1/joystickThrottleUp.png</file>
<file alias="joystickYawLeft.png">resources/calibration/joystick/mode1/joystickYawLeft.png</file>
<file alias="joystickYawRight.png">resources/calibration/joystick/mode1/joystickYawRight.png</file>
</qresource>
<qresource prefix="/qml/calibration/joystick/mode2">
<file alias="joystickCenter.png">resources/calibration/joystick/mode2/joystickCenter.png</file>
<file alias="joystickPitchDown.png">resources/calibration/joystick/mode2/joystickPitchDown.png</file>
<file alias="joystickPitchUp.png">resources/calibration/joystick/mode2/joystickPitchUp.png</file>
<file alias="joystickRollLeft.png">resources/calibration/joystick/mode2/joystickRollLeft.png</file>
<file alias="joystickRollRight.png">resources/calibration/joystick/mode2/joystickRollRight.png</file>
<file alias="joystickThrottleDown.png">resources/calibration/joystick/mode2/joystickThrottleDown.png</file>
<file alias="joystickThrottleUp.png">resources/calibration/joystick/mode2/joystickThrottleUp.png</file>
<file alias="joystickYawLeft.png">resources/calibration/joystick/mode2/joystickYawLeft.png</file>
<file alias="joystickYawRight.png">resources/calibration/joystick/mode2/joystickYawRight.png</file>
</qresource>
<qresource prefix="/qml/calibration/joystick/mode3">
<file alias="joystickCenter.png">resources/calibration/joystick/mode3/joystickCenter.png</file>
<file alias="joystickPitchDown.png">resources/calibration/joystick/mode3/joystickPitchDown.png</file>
<file alias="joystickPitchUp.png">resources/calibration/joystick/mode3/joystickPitchUp.png</file>
<file alias="joystickRollLeft.png">resources/calibration/joystick/mode3/joystickRollLeft.png</file>
<file alias="joystickRollRight.png">resources/calibration/joystick/mode3/joystickRollRight.png</file>
<file alias="joystickThrottleDown.png">resources/calibration/joystick/mode3/joystickThrottleDown.png</file>
<file alias="joystickThrottleUp.png">resources/calibration/joystick/mode3/joystickThrottleUp.png</file>
<file alias="joystickYawLeft.png">resources/calibration/joystick/mode3/joystickYawLeft.png</file>
<file alias="joystickYawRight.png">resources/calibration/joystick/mode3/joystickYawRight.png</file>
</qresource>
<qresource prefix="/qml/calibration/joystick/mode4">
<file alias="joystickCenter.png">resources/calibration/joystick/mode4/joystickCenter.png</file>
<file alias="joystickPitchDown.png">resources/calibration/joystick/mode4/joystickPitchDown.png</file>
<file alias="joystickPitchUp.png">resources/calibration/joystick/mode4/joystickPitchUp.png</file>
<file alias="joystickRollLeft.png">resources/calibration/joystick/mode4/joystickRollLeft.png</file>
<file alias="joystickRollRight.png">resources/calibration/joystick/mode4/joystickRollRight.png</file>
<file alias="joystickThrottleDown.png">resources/calibration/joystick/mode4/joystickThrottleDown.png</file>
<file alias="joystickThrottleUp.png">resources/calibration/joystick/mode4/joystickThrottleUp.png</file>
<file alias="joystickYawLeft.png">resources/calibration/joystick/mode4/joystickYawLeft.png</file>
<file alias="joystickYawRight.png">resources/calibration/joystick/mode4/joystickYawRight.png</file>
</qresource>
</RCC>
......@@ -15,7 +15,6 @@
<file alias="ESP8266Component.qml">src/AutoPilotPlugins/Common/ESP8266Component.qml</file>
<file alias="ESP8266ComponentSummary.qml">src/AutoPilotPlugins/Common/ESP8266ComponentSummary.qml</file>
<file alias="FirmwareUpgrade.qml">src/VehicleSetup/FirmwareUpgrade.qml</file>
<file alias="FlightDisplayView.qml">src/FlightDisplay/FlightDisplayView.qml</file>
<file alias="FlightDisplayViewDummy.qml">src/FlightDisplay/FlightDisplayViewDummy.qml</file>
<file alias="FlightDisplayViewUVC.qml">src/FlightDisplay/FlightDisplayViewUVC.qml</file>
<file alias="FlightModesComponentSummary.qml">src/AutoPilotPlugins/PX4/FlightModesComponentSummary.qml</file>
......@@ -26,7 +25,6 @@
<file alias="LinkSettings.qml">src/ui/preferences/LinkSettings.qml</file>
<file alias="LogDownloadPage.qml">src/AnalyzeView/LogDownloadPage.qml</file>
<file alias="LogReplaySettings.qml">src/ui/preferences/LogReplaySettings.qml</file>
<file alias="MainToolBar.qml">src/ui/toolbar/MainToolBar.qml</file>
<file alias="MainWindowHybrid.qml">src/ui/MainWindowHybrid.qml</file>
<file alias="MainWindowInner.qml">src/ui/MainWindowInner.qml</file>
<file alias="MainWindowNative.qml">src/ui/MainWindowNative.qml</file>
......
......@@ -178,17 +178,17 @@ bool ExifParser::write(QByteArray &buf, QGeoCoordinate coordinate)
// Filling up the additional information that does not fit into the fields
gpsData.readable.extendedData.gpsLat[0] = abs(static_cast<int>(coordinate.latitude()));
gpsData.readable.extendedData.gpsLat[1] = 1;
gpsData.readable.extendedData.gpsLat[2] = static_cast<int>((fabs(coordinate.latitude()) - floor(fabs(coordinate.latitude()))) * 60000.0);
gpsData.readable.extendedData.gpsLat[3] = 1000;
gpsData.readable.extendedData.gpsLat[4] = 0;
gpsData.readable.extendedData.gpsLat[5] = 1;
gpsData.readable.extendedData.gpsLat[2] = static_cast<int>((fabs(coordinate.latitude()) - floor(fabs(coordinate.latitude()))) * 60.0);
gpsData.readable.extendedData.gpsLat[3] = 1;
gpsData.readable.extendedData.gpsLat[4] = static_cast<int>((fabs(coordinate.latitude()) * 60.0 - floor(fabs(coordinate.latitude()) * 60.0)) * 60000.0);
gpsData.readable.extendedData.gpsLat[5] = 1000;
gpsData.readable.extendedData.gpsLon[0] = abs(static_cast<int>(coordinate.longitude()));
gpsData.readable.extendedData.gpsLon[1] = 1;
gpsData.readable.extendedData.gpsLon[2] = static_cast<int>((fabs(coordinate.longitude()) - floor(fabs(coordinate.longitude()))) * 60000.0);
gpsData.readable.extendedData.gpsLon[3] = 1000;
gpsData.readable.extendedData.gpsLon[4] = 0;
gpsData.readable.extendedData.gpsLon[5] = 1;
gpsData.readable.extendedData.gpsLon[2] = static_cast<int>((fabs(coordinate.longitude()) - floor(fabs(coordinate.longitude()))) * 60.0);
gpsData.readable.extendedData.gpsLon[3] = 1;
gpsData.readable.extendedData.gpsLon[4] = static_cast<int>((fabs(coordinate.longitude()) * 60.0 - floor(fabs(coordinate.longitude()) * 60.0)) * 60000.0);
gpsData.readable.extendedData.gpsLon[5] = 1000;
gpsData.readable.extendedData.gpsAlt[0] = coordinate.altitude() * 100;
gpsData.readable.extendedData.gpsAlt[1] = 100;
......
......@@ -16,6 +16,7 @@
#include "QGCApplication.h"
#include "QGCToolbox.h"
#include "QGCMapEngine.h"
#include "ParameterManager.h"
#include "Vehicle.h"
#include "MainWindow.h"
......@@ -583,8 +584,14 @@ LogDownloadController::_prepareLogDownload()
}
_downloadData = new LogDownloadData(entry);
_downloadData->filename = QString("log_") + QString::number(entry->id()) + "_" + ftime;
if(_vehicle->firmwareType() == MAV_AUTOPILOT_PX4) {
_downloadData->filename += ".px4log";
if (_vehicle->firmwareType() == MAV_AUTOPILOT_PX4) {
// This is a stopgap and should be removed once log file types are properly supported by the log download protocol
if (_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "SYS_LOGGER")->rawValue().toInt() == 0) {
_downloadData->filename += ".px4log";
} else {
_downloadData->filename += ".ulg";
}
} else {
_downloadData->filename += ".bin";
}
......
......@@ -138,11 +138,11 @@ SetupPage {
onClicked: {
var measuredVoltageValue = parseFloat(measuredVoltage.text)
if (measuredVoltageValue == 0) {
if (measuredVoltageValue == 0 || isNaN(measuredVoltageValue)) {
return
}
var newVoltageMultiplier = (measuredVoltageValue * battVoltMult.value) / controller.vehicle.battery.voltage.value
if (newVoltageMultiplier != 0) {
if (newVoltageMultiplier > 0) {
battVoltMult.value = newVoltageMultiplier
}
}
......
......@@ -144,11 +144,11 @@ SetupPage {
onClicked: {
var measuredVoltageValue = parseFloat(measuredVoltage.text)
if (measuredVoltageValue == 0) {
if (measuredVoltageValue == 0 || isNaN(measuredVoltageValue)) {
return
}
var newVoltageDivider = (measuredVoltageValue * battVoltageDivider.value) / controller.vehicle.battery.voltage.value
if (newVoltageDivider != 0) {
if (newVoltageDivider > 0) {
battVoltageDivider.value = newVoltageDivider
}
}
......
......@@ -40,7 +40,7 @@ QGCTextField {
}
}
onHelpClicked: qgcView.showDialog(helpDialogComponent, qsTr("Value Details"), qgcView.showDialogDefaultWidth, StandardButton.Save)
onHelpClicked: qgcView.showDialog(helpDialogComponent, qsTr("Value Details"), qgcView.showDialogDefaultWidth, StandardButton.Save | StandardButton.Cancel)
Component {
......
......@@ -69,6 +69,8 @@ public:
// Overrides from FirmwarePlugin
int manualControlReservedButtonCount(void);
int defaultJoystickTXMode(void) final { return 3; }
bool supportsThrottleModeCenterZero(void);
bool supportsManualControl(void);
......
......@@ -106,6 +106,11 @@ int FirmwarePlugin::manualControlReservedButtonCount(void)
return -1;
}
int FirmwarePlugin::defaultJoystickTXMode(void)
{
return 2;
}
bool FirmwarePlugin::supportsThrottleModeCenterZero(void)
{
// By default, this is supported
......@@ -297,3 +302,21 @@ QString FirmwarePlugin::takeControlFlightMode(void)
{
return QString();
}
QString FirmwarePlugin::vehicleImageOpaque(const Vehicle* vehicle) const
{
Q_UNUSED(vehicle);
return QStringLiteral("/qmlimages/vehicleArrowOpaque.svg");
}
QString FirmwarePlugin::vehicleImageOutline(const Vehicle* vehicle) const
{
Q_UNUSED(vehicle);
return QStringLiteral("/qmlimages/vehicleArrowOutline.svg");
}
QString FirmwarePlugin::vehicleImageCompass(const Vehicle* vehicle) const
{
Q_UNUSED(vehicle);
return QStringLiteral("/qmlimages/compassInstrumentArrow.svg");
}
......@@ -142,6 +142,10 @@ public:
/// @return -1: reserver all buttons, >0 number of buttons to reserve
virtual int manualControlReservedButtonCount(void);
/// Default tx mode to apply to joystick axes
/// TX modes are as outlined here: http://www.rc-airplane-world.com/rc-transmitter-modes.html
virtual int defaultJoystickTXMode(void);
/// Returns true if the vehicle and firmware supports the use of a throttle joystick that
/// is zero when centered. Typically not supported on vehicles that have bidirectional
/// throttle.
......@@ -238,6 +242,15 @@ public:
/// Return the resource file which contains the brand image for the vehicle.
virtual QString brandImage(const Vehicle* vehicle) const { Q_UNUSED(vehicle) return QString(); }
/// Return the resource file which contains the vehicle icon used in the flight view when the view is dark (Satellite for instance)
virtual QString vehicleImageOpaque(const Vehicle* vehicle) const;
/// Return the resource file which contains the vehicle icon used in the flight view when the view is light (Map for instance)
virtual QString vehicleImageOutline(const Vehicle* vehicle) const;
/// Return the resource file which contains the vehicle icon used in the compass
virtual QString vehicleImageCompass(const Vehicle* vehicle) const;
// FIXME: Hack workaround for non pluginize FollowMe support
static const char* px4FollowMeFlightMode;
};
......
......@@ -30,14 +30,11 @@ QList<MAV_AUTOPILOT> FirmwarePluginManager::knownFirmwareTypes(void)
{
if (_knownFirmwareTypes.isEmpty()) {
QList<FirmwarePluginFactory*> factoryList = FirmwarePluginFactoryRegister::instance()->pluginFactories();
for (int i=0; i<factoryList.count(); i++) {
for (int i = 0; i < factoryList.count(); i++) {
_knownFirmwareTypes.append(factoryList[i]->knownFirmwareTypes());
}
_knownFirmwareTypes.append(MAV_AUTOPILOT_GENERIC);
}
_knownFirmwareTypes.append(MAV_AUTOPILOT_GENERIC);
return _knownFirmwareTypes;
}
......
......@@ -7,7 +7,13 @@
{
"id": 21,
"comment": "MAV_CMD_NAV_LAND",
"paramRemove": "1,4"
"paramRemove": "1,4",
"param7": {
"label": "Altitude:",
"units": "m",
"default": 0,
"decimalPlaces": 1
}
},
{
"id": 22,
......
......@@ -64,8 +64,8 @@ static const struct Modes2Name rgModes2Name[] = {
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_LOITER, PX4FirmwarePlugin::_holdFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_MISSION, PX4FirmwarePlugin::_missionFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_RTL, PX4FirmwarePlugin::_rtlFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET, PX4FirmwarePlugin::_followMeFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_OFFBOARD, 0, PX4FirmwarePlugin::_offboardFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET, PX4FirmwarePlugin::_followMeFlightMode, true, false, true },
{ PX4_CUSTOM_MAIN_MODE_OFFBOARD, 0, PX4FirmwarePlugin::_offboardFlightMode, true, false, true },
// modes that can't be directly set by the user
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_LAND, PX4FirmwarePlugin::_landingFlightMode, false, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_READY, PX4FirmwarePlugin::_readyFlightMode, false, true, true },
......
......@@ -260,6 +260,42 @@ QGCView {
visible: singleVehicleView.checked
}
// Button to start/stop video recording
Item {
z: _flightVideoPipControl.z + 1
anchors.margins: ScreenTools.defaultFontPixelHeight / 2
anchors.bottom: _flightVideo.bottom
anchors.right: _flightVideo.right
height: ScreenTools.defaultFontPixelHeight * 2
width: height
visible: QGroundControl.videoManager.videoRunning && QGroundControl.videoManager.recordingEnabled
opacity: 0.75
Rectangle {
anchors.top: parent.top
anchors.bottom: parent.bottom
width: height
radius: QGroundControl.videoManager.videoReceiver && QGroundControl.videoManager.videoReceiver.recording ? 0 : height
color: "red"
}
QGCColoredImage {
anchors.top: parent.top
anchors.bottom: parent.bottom
anchors.horizontalCenter: parent.horizontalCenter
width: height * 0.625
sourceSize.width: width
source: "/qmlimages/CameraIcon.svg"
fillMode: Image.PreserveAspectFit
color: "white"
}
MouseArea {
anchors.fill: parent
onClicked: QGroundControl.videoManager.videoReceiver && QGroundControl.videoManager.videoReceiver.recording ? QGroundControl.videoManager.videoReceiver.stopRecording() : QGroundControl.videoManager.videoReceiver.startRecording()
}
}
MultiVehicleList {
anchors.margins: _margins
anchors.top: singleMultiSelector.bottom
......
......@@ -81,7 +81,6 @@ Item {
anchors.verticalCenter: parent.verticalCenter
visible: !_useAlternateInstruments
size: getGadgetWidth()
active: _activeVehicle != null
heading: _heading
rollAngle: _roll
pitchAngle: _pitch
......@@ -100,7 +99,6 @@ Item {
anchors.right: altitudeSlider.visible ? altitudeSlider.left : parent.right
visible: _useAlternateInstruments
width: ScreenTools.isTinyScreen ? getGadgetWidth() * 1.5 : getGadgetWidth()
active: _activeVehicle != null
heading: _heading
rollAngle: _roll
pitchAngle: _pitch
......@@ -452,8 +450,8 @@ Item {
anchors.left: parent.left
anchors.right: parent.right
orientation: Qt.Vertical
minimumValue: QGroundControl.metersToAppSettingsDistanceUnits(2)
maximumValue: QGroundControl.metersToAppSettingsDistanceUnits((_activeVehicle && _activeVehicle.flying) ? 100 : 10)
minimumValue: QGroundControl.metersToAppSettingsDistanceUnits(0)
maximumValue: QGroundControl.metersToAppSettingsDistanceUnits((_activeVehicle && _activeVehicle.flying) ? Math.round((_activeVehicle.altitudeRelative.value + 100) / 100) * 100 : 10)
}
}
}
......@@ -52,8 +52,8 @@ QGCListView {
QGCCompassWidget {
size: _widgetHeight
active: true
heading: _vehicle.heading.rawValue
vehicle: _vehicle
}
QGCAttitudeWidget {
......
......@@ -11,6 +11,8 @@
#include <QQmlContext>
#include <QQmlEngine>
#include <QSettings>
#include <QUrl>
#include <QDir>
#ifndef QGC_DISABLE_UVC
#include <QCameraInfo>
......@@ -27,11 +29,15 @@
static const char* kVideoSourceKey = "VideoSource";
static const char* kVideoUDPPortKey = "VideoUDPPort";
static const char* kVideoRTSPUrlKey = "VideoRTSPUrl";
static const char* kNoVideo = "No Video Available";
#if defined(QGC_GST_STREAMING)
#if defined(QGC_ENABLE_VIDEORECORDING)
static const char* kVideoSavePathKey= "VideoSavePath";
#endif
static const char* kUDPStream = "UDP Video Stream";
static const char* kRTSPStream = "RTSP Video Stream";
#endif
static const char* kNoVideo = "No Video Available";
QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog")
......@@ -80,6 +86,9 @@ VideoManager::setToolbox(QGCToolbox *toolbox)
setUdpPort(settings.value(kVideoUDPPortKey, 5600).toUInt());
setRtspURL(settings.value(kVideoRTSPUrlKey, "rtsp://192.168.42.1:554/live").toString()); //-- Example RTSP URL
}
#if defined(QGC_ENABLE_VIDEORECORDING)
setVideoSavePath(settings.value(kVideoSavePathKey, QDir::homePath()).toString());
#endif
#endif
_init = true;
#if defined(QGC_GST_STREAMING)
......@@ -186,6 +195,30 @@ VideoManager::setRtspURL(QString url)
*/
}
void
VideoManager::setVideoSavePathByUrl(QUrl url) {
#if defined(QGC_ENABLE_VIDEORECORDING)
setVideoSavePath(url.toLocalFile());
#else
Q_UNUSED(url);
#endif
}
void
VideoManager::setVideoSavePath(QString path)
{
#if defined(QGC_ENABLE_VIDEORECORDING)
_videoSavePath = path;
QSettings settings;
settings.setValue(kVideoSavePathKey, path);
if(_videoReceiver)
_videoReceiver->setVideoSavePath(_videoSavePath);
emit videoSavePathChanged();
#else
Q_UNUSED(path);
#endif
}
//-----------------------------------------------------------------------------
QStringList
VideoManager::videoSourceList()
......@@ -211,37 +244,37 @@ VideoManager::videoSourceList()
void VideoManager::_updateTimer()
{
#if defined(QGC_GST_STREAMING)
if(_videoRunning)
{
time_t elapsed = 0;
if(_videoSurface)
{
elapsed = time(0) - _videoSurface->lastFrame();
}
if(elapsed > 2 && _videoSurface)
{
_videoRunning = false;
_videoSurface->setLastFrame(0);
emit videoRunningChanged();
if(_videoReceiver) {
if(isGStreamer()) {
//-- Stop it
_videoReceiver->stop();
QThread::msleep(100);
//-- And start over
_videoReceiver->start();
}
}
if(_videoReceiver && _videoSurface) {
if(_videoReceiver->stopping() || _videoReceiver->starting()) {
return;
}
}
else
{
if(_videoSurface && _videoSurface->lastFrame()) {
if(!_videoRunning)
{
if(_videoReceiver->streaming()) {
if(!_videoRunning) {
_videoSurface->setLastFrame(0);
_videoRunning = true;
emit videoRunningChanged();
}
} else {
if(_videoRunning) {
_videoRunning = false;
emit videoRunningChanged();
}
}
if(_videoRunning) {
time_t elapsed = 0;
time_t lastFrame = _videoSurface->lastFrame();
if(lastFrame != 0) {
elapsed = time(0) - _videoSurface->lastFrame();
}
if(elapsed > 2 && _videoSurface) {
_videoReceiver->stop();
}
} else {
if(!_videoReceiver->running()) {
_videoReceiver->start();
}
}
}
#endif
......@@ -257,13 +290,16 @@ void VideoManager::_updateVideo()
delete _videoSurface;
_videoSurface = new VideoSurface;
_videoReceiver = new VideoReceiver(this);
#if defined(QGC_GST_STREAMING)
#if defined(QGC_GST_STREAMING)
_videoReceiver->setVideoSink(_videoSurface->videoSink());
if(_videoSource == kUDPStream)
_videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(_udpPort));
else
_videoReceiver->setUri(_rtspURL);
#endif
#if defined(QGC_ENABLE_VIDEORECORDING)
_videoReceiver->setVideoSavePath(_videoSavePath);
#endif
#endif
_videoReceiver->start();
}
}
......@@ -13,6 +13,7 @@
#include <QObject>
#include <QTimer>
#include <QUrl>
#include "QGCLoggingCategory.h"
#include "VideoSurface.h"
......@@ -29,17 +30,21 @@ public:
VideoManager (QGCApplication* app);
~VideoManager ();
Q_PROPERTY(bool hasVideo READ hasVideo NOTIFY hasVideoChanged)
Q_PROPERTY(bool isGStreamer READ isGStreamer NOTIFY isGStreamerChanged)
Q_PROPERTY(QString videoSourceID READ videoSourceID NOTIFY videoSourceIDChanged)
Q_PROPERTY(QString videoSource READ videoSource WRITE setVideoSource NOTIFY videoSourceChanged)
Q_PROPERTY(QStringList videoSourceList READ videoSourceList NOTIFY videoSourceListChanged)
Q_PROPERTY(bool videoRunning READ videoRunning NOTIFY videoRunningChanged)
Q_PROPERTY(quint16 udpPort READ udpPort WRITE setUdpPort NOTIFY udpPortChanged)
Q_PROPERTY(QString rtspURL READ rtspURL WRITE setRtspURL NOTIFY rtspURLChanged)
Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT)
Q_PROPERTY(VideoSurface* videoSurface MEMBER _videoSurface CONSTANT)
Q_PROPERTY(VideoReceiver* videoReceiver MEMBER _videoReceiver CONSTANT)
Q_PROPERTY(bool hasVideo READ hasVideo NOTIFY hasVideoChanged)
Q_PROPERTY(bool isGStreamer READ isGStreamer NOTIFY isGStreamerChanged)
Q_PROPERTY(QString videoSourceID READ videoSourceID NOTIFY videoSourceIDChanged)
Q_PROPERTY(QString videoSource READ videoSource WRITE setVideoSource NOTIFY videoSourceChanged)
Q_PROPERTY(QStringList videoSourceList READ videoSourceList NOTIFY videoSourceListChanged)
Q_PROPERTY(bool videoRunning READ videoRunning NOTIFY videoRunningChanged)
Q_PROPERTY(quint16 udpPort READ udpPort WRITE setUdpPort NOTIFY udpPortChanged)
Q_PROPERTY(QString rtspURL READ rtspURL WRITE setRtspURL NOTIFY rtspURLChanged)
Q_PROPERTY(QString videoSavePath READ videoSavePath NOTIFY videoSavePathChanged)
Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT)
Q_PROPERTY(VideoSurface* videoSurface MEMBER _videoSurface CONSTANT)
Q_PROPERTY(VideoReceiver* videoReceiver MEMBER _videoReceiver CONSTANT)
Q_PROPERTY(bool recordingEnabled READ recordingEnabled CONSTANT)
Q_INVOKABLE void setVideoSavePathByUrl (QUrl url);
bool hasVideo ();
bool isGStreamer ();
......@@ -49,6 +54,7 @@ public:
QStringList videoSourceList ();
quint16 udpPort () { return _udpPort; }
QString rtspURL () { return _rtspURL; }
QString videoSavePath () { return _videoSavePath; }
#if defined(QGC_DISABLE_UVC)
bool uvcEnabled () { return false; }
......@@ -56,9 +62,16 @@ public:
bool uvcEnabled ();
#endif
void setVideoSource (QString vSource);
void setUdpPort (quint16 port);
void setRtspURL (QString url);
#if defined(QGC_GST_STREAMING) && defined(QGC_ENABLE_VIDEORECORDING)
bool recordingEnabled () { return true; }
#else
bool recordingEnabled () { return false; }
#endif
void setVideoSource (QString vSource);
void setUdpPort (quint16 port);
void setRtspURL (QString url);
void setVideoSavePath (QString path);
// Override from QGCTool
void setToolbox (QGCToolbox *toolbox);
......@@ -72,6 +85,7 @@ signals:
void videoSourceIDChanged ();
void udpPortChanged ();
void rtspURLChanged ();
void videoSavePathChanged ();
private:
void _updateTimer ();
......@@ -89,6 +103,7 @@ private:
QStringList _videoSourceList;
quint16 _udpPort;
QString _rtspURL;
QString _videoSavePath;
bool _init;
};
......
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 19.1.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" id="Layer_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="0 0 72 72" enable-background="new 0 0 72 72" xml:space="preserve">
<g>
<polygon fill="#C72B27" points="36,0 36,49.058 0,72 "/>
<polygon fill="#EE3424" points="36,0 36,49.058 72,72 "/>
</g>
</svg>
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 19.1.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" id="Layer_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="253 705 288 288" enable-background="new 253 705 288 288" xml:space="preserve">
<title>Layer 1</title>
<polyline fill="#FF460A" stroke="#000000" stroke-width="6" stroke-linecap="round" stroke-linejoin="round" points="
396.982,969.152 338.217,983.998 338.217,969.152 382.136,930.53 375.619,855.19 284.687,887.839 284.687,859.113 375.619,795.107
375.619,763.004 396.982,714.002 396.999,714.002 418.363,763.004 418.363,795.107 509.294,859.113 509.294,887.839 418.363,855.19
411.845,930.53 455.764,969.152 455.764,983.998 396.999,969.152 "/>
</svg>
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 19.1.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" id="Layer_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="253 705 288 288" enable-background="new 253 705 288 288" xml:space="preserve">
<title>Layer 1</title>
<polyline fill="none" stroke="#000000" stroke-width="8" stroke-linecap="round" stroke-linejoin="round" points="396.991,968.512
338.226,983.357 338.226,968.512 382.145,929.889 375.628,854.549 284.696,887.198 284.696,858.472 375.628,794.466
375.628,762.364 396.991,713.361 397.009,713.361 418.372,762.364 418.372,794.466 509.304,858.472 509.304,887.198
418.372,854.549 411.855,929.889 455.774,968.512 455.774,983.357 397.009,968.512 "/>
</svg>
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 18.1.1, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" id="Layer_2" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="0 0 288 288" enable-background="new 0 0 288 288" xml:space="preserve">
<g>
<path fill="#BCBEC0" d="M131.601,164.5l-0.4-5.2c-1.2-10.801,2.4-22.602,12.399-34.603c9-10.601,14-18.401,14-27.401
c0-10.201-6.399-17.001-18.999-17.201c-7.2,0-15.2,2.4-20.2,6.2l-4.8-12.601c6.6-4.8,18-8,28.6-8c23,0,33.399,14.201,33.399,29.402
c0,13.601-7.6,23.401-17.199,34.802c-8.8,10.401-12,19.201-11.4,29.402l0.2,5.2H131.601z M127.201,192.502
c0-7.4,5-12.602,12-12.602s11.8,5.201,11.8,12.602c0,7-4.6,12.4-12,12.4C132,204.902,127.201,199.502,127.201,192.502z"/>
</g>
</svg>
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 18.1.1, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="0 0 288 288" enable-background="new 0 0 288 288" xml:space="preserve">
<g id="Layer_1">
<g>
<path fill="#212121" d="M288,270c0,9.9-8.1,18-18,18H18c-9.9,0-18-8.1-18-18V18C0,8.1,8.1,0,18,0h252c9.9,0,18,8.1,18,18V270z"/>
</g>
</g>
<g id="Layer_2">
<line fill="none" stroke="#939598" stroke-width="24" stroke-miterlimit="10" x1="36" y1="77.79" x2="252" y2="77.79"/>
<line fill="none" stroke="#939598" stroke-width="24" stroke-miterlimit="10" x1="36" y1="144" x2="252" y2="144"/>
<line fill="none" stroke="#939598" stroke-width="24" stroke-miterlimit="10" x1="36" y1="210.21" x2="252" y2="210.21"/>
</g>
</svg>
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 18.1.1, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" id="Layer_3" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="0 0 288 288" enable-background="new 0 0 288 288" xml:space="preserve">
<polyline fill="#231F20" stroke="#D23528" stroke-width="4" stroke-linecap="round" stroke-linejoin="round" points="
143.993,240.123 96.979,252 96.979,240.123 132.116,209.225 126.901,148.952 54.153,175.072 54.153,152.091 126.901,100.885
126.901,75.203 143.993,36 144.007,36 161.099,75.203 161.099,100.885 233.847,152.091 233.847,175.072 161.099,148.952
155.884,209.225 191.021,240.123 191.021,252 144.007,240.123 "/>
</svg>
......@@ -30,7 +30,7 @@ MapQuickItem {
sourceItem: Image {
id: vehicleIcon
source: isSatellite ? "/qmlimages/vehicleArrowOpaque.svg" : "/qmlimages/vehicleArrowOutline.svg"
source: isSatellite ? vehicle.vehicleImageOpaque : vehicle.vehicleImageOutline
mipmap: true
width: size
sourceSize.width: size
......
......@@ -17,15 +17,16 @@
import QtQuick 2.4
import QtGraphicalEffects 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
Item {
id: root
property bool active: false ///< true: actively connected to data provider, false: show inactive control
property real heading: 0
property real size: _defaultSize
property real heading: 0
property var vehicle: null
property real _defaultSize: ScreenTools.defaultFontPixelHeight * (10)
property real _sizeRatio: ScreenTools.isTinyScreen ? (size / _defaultSize) * 0.5 : size / _defaultSize
......@@ -48,7 +49,7 @@ Item {
Image {
id: pointer
source: "/qmlimages/compassInstrumentArrow.svg"
source: vehicle ? vehicle.vehicleImageCompass : ""
mipmap: true
width: size * 0.75
sourceSize.width: width
......@@ -78,8 +79,8 @@ Item {
color: Qt.rgba(0,0,0,0.65)
QGCLabel {
text: active ? heading.toFixed(0) : qsTr("OFF")
font.family: active ? ScreenTools.demiboldFontFamily : ScreenTools.normalFontFamily
text: vehicle ? heading.toFixed(0) : qsTr("OFF")
font.family: vehicle ? ScreenTools.demiboldFontFamily : ScreenTools.normalFontFamily
font.pointSize: _fontSize < 8 ? 8 : _fontSize;
color: "white"
anchors.centerIn: parent
......
......@@ -150,8 +150,8 @@ Item {
QGCCompassWidget {
id: compass
size: parent.width * 0.95
active: instrumentPanel.active
visible: _showCompass
vehicle: _activeVehicle
anchors.horizontalCenter: parent.horizontalCenter
}
}
......
......@@ -10,6 +10,7 @@
import QtQuick 2.4
import QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.FactSystem 1.0
......@@ -68,7 +69,7 @@ Rectangle {
anchors.leftMargin: _spacing
anchors.left: attitude.right
size: _innerRadius * 2
active: root.active
vehicle: QGroundControl.multiVehicleManager.activeVehicle
anchors.verticalCenter: parent.verticalCenter
}
......
......@@ -18,13 +18,19 @@
QGC_LOGGING_CATEGORY(JoystickLog, "JoystickLog")
QGC_LOGGING_CATEGORY(JoystickValuesLog, "JoystickValuesLog")
const char* Joystick::_settingsGroup = "Joysticks";
const char* Joystick::_calibratedSettingsKey = "Calibrated1"; // Increment number to force recalibration
const char* Joystick::_buttonActionSettingsKey = "ButtonActionName%1";
const char* Joystick::_throttleModeSettingsKey = "ThrottleMode";
const char* Joystick::_exponentialSettingsKey = "Exponential";
const char* Joystick::_accumulatorSettingsKey = "Accumulator";
const char* Joystick::_deadbandSettingsKey = "Deadband";
const char* Joystick::_settingsGroup = "Joysticks";
const char* Joystick::_calibratedSettingsKey = "Calibrated2"; // Increment number to force recalibration
const char* Joystick::_buttonActionSettingsKey = "ButtonActionName%1";
const char* Joystick::_throttleModeSettingsKey = "ThrottleMode";
const char* Joystick::_exponentialSettingsKey = "Exponential";
const char* Joystick::_accumulatorSettingsKey = "Accumulator";
const char* Joystick::_deadbandSettingsKey = "Deadband";
const char* Joystick::_txModeSettingsKey = NULL;
const char* Joystick::_fixedWingTXModeSettingsKey = "TXMode_FixedWing";
const char* Joystick::_multiRotorTXModeSettingsKey = "TXMode_MultiRotor";
const char* Joystick::_roverTXModeSettingsKey = "TXMode_Rover";
const char* Joystick::_vtolTXModeSettingsKey = "TXMode_VTOL";
const char* Joystick::_submarineTXModeSettingsKey = "TXMode_Submarine";
const char* Joystick::_rgFunctionSettingsKey[Joystick::maxFunction] = {
"RollAxis",
......@@ -33,6 +39,8 @@ const char* Joystick::_rgFunctionSettingsKey[Joystick::maxFunction] = {
"ThrottleAxis"
};
int Joystick::_transmitterMode = 2;
Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatCount, MultiVehicleManager* multiVehicleManager)
: _exitThread(false)
, _name(name)
......@@ -67,6 +75,8 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC
}
_loadSettings();
connect(_multiVehicleManager, &MultiVehicleManager::activeVehicleChanged, this, &Joystick::_activeVehicleChanged);
}
Joystick::~Joystick()
......@@ -76,11 +86,74 @@ Joystick::~Joystick()
delete[] _rgButtonValues;
}
void Joystick::_setDefaultCalibration(void) {
QSettings settings;
settings.beginGroup(_settingsGroup);
settings.beginGroup(_name);
_calibrated = settings.value(_calibratedSettingsKey, false).toBool();
// Only set default calibrations if we do not have a calibration for this gamecontroller
if(_calibrated) return;
for(int axis = 0; axis < _axisCount; axis++) {
Joystick::Calibration_t calibration;
_rgCalibration[axis] = calibration;
}
_rgCalibration[1].reversed = true;
_rgCalibration[3].reversed = true;
// Default TX Mode 2 axis assignments for gamecontrollers
_rgFunctionAxis[rollFunction] = 2;
_rgFunctionAxis[pitchFunction] = 3;
_rgFunctionAxis[yawFunction] = 0;
_rgFunctionAxis[throttleFunction] = 1;
_exponential = false;
_accumulator = false;
_deadband = false;
_throttleMode = ThrottleModeCenterZero;
_calibrated = true;
_saveSettings();
}
void Joystick::_activeVehicleChanged(Vehicle *activeVehicle)
{
if(activeVehicle) {
if(activeVehicle->fixedWing()) {
_txModeSettingsKey = _fixedWingTXModeSettingsKey;
} else if(activeVehicle->multiRotor()) {
_txModeSettingsKey = _multiRotorTXModeSettingsKey;
} else if(activeVehicle->rover()) {
_txModeSettingsKey = _roverTXModeSettingsKey;
} else if(activeVehicle->vtol()) {
_txModeSettingsKey = _vtolTXModeSettingsKey;
} else if(activeVehicle->sub()) {
_txModeSettingsKey = _submarineTXModeSettingsKey;
} else {
_txModeSettingsKey = NULL;
qWarning() << "No valid joystick TXmode settings key for selected vehicle";
return;
}
QSettings settings;
settings.beginGroup(_settingsGroup);
int mode = settings.value(_txModeSettingsKey, activeVehicle->firmwarePlugin()->defaultJoystickTXMode()).toInt();
setTXMode(mode);
}
}
void Joystick::_loadSettings(void)
{
QSettings settings;
settings.beginGroup(_settingsGroup);
if(_txModeSettingsKey)
_transmitterMode = settings.value(_txModeSettingsKey, 2).toInt();
settings.beginGroup(_name);
bool badSettings = false;
......@@ -96,7 +169,7 @@ void Joystick::_loadSettings(void)
_throttleMode = (ThrottleMode_t)settings.value(_throttleModeSettingsKey, ThrottleModeCenterZero).toInt(&convertOk);
badSettings |= !convertOk;
qCDebug(JoystickLog) << "_loadSettings calibrated:throttlemode:exponential:deadband:badsettings" << _calibrated << _throttleMode << _exponential << _deadband << badSettings;
qCDebug(JoystickLog) << "_loadSettings calibrated:txmode:throttlemode:exponential:deadband:badsettings" << _calibrated << _transmitterMode << _throttleMode << _exponential << _deadband << badSettings;
QString minTpl ("Axis%1Min");
QString maxTpl ("Axis%1Max");
......@@ -136,6 +209,10 @@ void Joystick::_loadSettings(void)
qCDebug(JoystickLog) << "_loadSettings function:axis:badsettings" << function << functionAxis << badSettings;
}
// FunctionAxis mappings are always stored in TX mode 2
// Remap to stored TX mode in settings
_remapAxes(2, _transmitterMode, _rgFunctionAxis);
for (int button=0; button<_totalButtonCount; button++) {
_rgButtonActions << settings.value(QString(_buttonActionSettingsKey).arg(button), QString()).toString();
qCDebug(JoystickLog) << "_loadSettings button:action" << button << _rgButtonActions[button];
......@@ -152,6 +229,12 @@ void Joystick::_saveSettings(void)
QSettings settings;
settings.beginGroup(_settingsGroup);
// Transmitter mode is static
// Save the mode we are using
if(_txModeSettingsKey)
settings.setValue(_txModeSettingsKey, _transmitterMode);
settings.beginGroup(_name);
settings.setValue(_calibratedSettingsKey, _calibrated);
......@@ -160,7 +243,7 @@ void Joystick::_saveSettings(void)
settings.setValue(_deadbandSettingsKey, _deadband);
settings.setValue(_throttleModeSettingsKey, _throttleMode);
qCDebug(JoystickLog) << "_saveSettings calibrated:throttlemode:deadband" << _calibrated << _throttleMode << _deadband;
qCDebug(JoystickLog) << "_saveSettings calibrated:throttlemode:deadband:txmode" << _calibrated << _throttleMode << _deadband << _transmitterMode;
QString minTpl ("Axis%1Min");
QString maxTpl ("Axis%1Max");
......@@ -187,8 +270,13 @@ void Joystick::_saveSettings(void)
<< calibration->deadband;
}
// Always save function Axis mappings in TX Mode 2
// Write mode 2 mappings without changing mapping currently in use
int temp[maxFunction];
_remapAxes(_transmitterMode, 2, temp);
for (int function=0; function<maxFunction; function++) {
settings.setValue(_rgFunctionSettingsKey[function], _rgFunctionAxis[function]);
settings.setValue(_rgFunctionSettingsKey[function], temp[function]);
qCDebug(JoystickLog) << "_saveSettings name:function:axis" << _name << function << _rgFunctionSettingsKey[function];
}
......@@ -198,6 +286,42 @@ void Joystick::_saveSettings(void)
}
}
// Relative mappings of axis functions between different TX modes
int Joystick::_mapFunctionMode(int mode, int function) {
static const int mapping[][4] = {
{ 2, 1, 0, 3 },
{ 2, 3, 0, 1 },
{ 0, 1, 2, 3 },
{ 0, 3, 2, 1 }};
return mapping[mode-1][function];
}
// Remap current axis functions from current TX mode to new TX mode
void Joystick::_remapAxes(int currentMode, int newMode, int (&newMapping)[maxFunction]) {
int temp[maxFunction];
for(int function = 0; function < maxFunction; function++) {
temp[_mapFunctionMode(newMode, function)] = _rgFunctionAxis[_mapFunctionMode(currentMode, function)];
}
for(int function = 0; function < maxFunction; function++) {
newMapping[function] = temp[function];
}
}
void Joystick::setTXMode(int mode) {
if(mode > 0 && mode <= 4) {
_remapAxes(_transmitterMode, mode, _rgFunctionAxis);
_transmitterMode = mode;
_saveSettings();
} else {
qCWarning(JoystickLog) << "Invalid mode:" << mode;
}
}
/// Adjust the raw axis value to the -1:1 range given calibration information
float Joystick::_adjustRange(int value, Calibration_t calibration, bool withDeadbands)
{
......@@ -475,6 +599,7 @@ void Joystick::setFunctionAxis(AxisFunction_t function, int axis)
_calibrated = true;
_rgFunctionAxis[function] = axis;
_saveSettings();
emit calibratedChanged(_calibrated);
}
......
......@@ -30,12 +30,18 @@ public:
~Joystick();
typedef struct {
typedef struct Calibration_t {
int min;
int max;
int center;
int deadband;
bool reversed;
Calibration_t()
: min(-32767)
, max(32767)
, center(0)
, deadband(0)
, reversed(false) {}
} Calibration_t;
typedef enum {
......@@ -68,7 +74,8 @@ public:
Q_PROPERTY(int throttleMode READ throttleMode WRITE setThrottleMode NOTIFY throttleModeChanged)
Q_PROPERTY(bool exponential READ exponential WRITE setExponential NOTIFY exponentialChanged)
Q_PROPERTY(bool accumulator READ accumulator WRITE setAccumulator NOTIFY accumulatorChanged)
Q_PROPERTY(bool requiresCalibration READ requiresCalibration CONSTANT)
// Property accessors
int axisCount(void) { return _axisCount; }
......@@ -94,6 +101,8 @@ public:
virtual int index(void) = 0;
virtual void setIndex(int index) = 0;
virtual bool requiresCalibration(void) { return true; }
int throttleMode(void);
void setThrottleMode(int mode);
......@@ -106,6 +115,9 @@ public:
bool deadband(void);
void setDeadband(bool accu);
void setTXMode(int mode);
int getTXMode(void) { return _transmitterMode; }
typedef enum {
CalibrationModeOff, // Not calibrating
CalibrationModeMonitor, // Monitors are active, continue to send to vehicle if already polling
......@@ -146,12 +158,13 @@ signals:
void buttonActionTriggered(int action);
protected:
void _saveSettings(void);
void _loadSettings(void);
float _adjustRange(int value, Calibration_t calibration, bool withDeadbands);
void _buttonAction(const QString& action);
bool _validAxis(int axis);
bool _validButton(int button);
void _setDefaultCalibration(void);
void _saveSettings(void);
void _loadSettings(void);
float _adjustRange(int value, Calibration_t calibration, bool withDeadbands);
void _buttonAction(const QString& action);
bool _validAxis(int axis);
bool _validButton(int button);
private:
virtual bool _open() = 0;
......@@ -162,6 +175,9 @@ private:
virtual int _getAxis(int i) = 0;
virtual uint8_t _getHat(int hat,int i) = 0;
int _mapFunctionMode(int mode, int function);
void _remapAxes(int currentMode, int newMode, int (&newMapping)[maxFunction]);
// Override from QThread
virtual void run(void);
......@@ -177,6 +193,7 @@ protected:
int _hatButtonCount;
int _totalButtonCount;
static int _transmitterMode;
CalibrationMode_t _calibrationMode;
int* _rgAxisValues;
......@@ -208,6 +225,15 @@ private:
static const char* _exponentialSettingsKey;
static const char* _accumulatorSettingsKey;
static const char* _deadbandSettingsKey;
static const char* _txModeSettingsKey;
static const char* _fixedWingTXModeSettingsKey;
static const char* _multiRotorTXModeSettingsKey;
static const char* _roverTXModeSettingsKey;
static const char* _vtolTXModeSettingsKey;
static const char* _submarineTXModeSettingsKey;
private slots:
void _activeVehicleChanged(Vehicle* activeVehicle);
};
#endif
......@@ -10,6 +10,7 @@ JoystickSDL::JoystickSDL(const QString& name, int axisCount, int buttonCount, in
, _isGameController(isGameController)
, _index(index)
{
if(_isGameController) _setDefaultCalibration();
}
bool JoystickSDL::init(void) {
......
......@@ -18,6 +18,9 @@ public:
int index(void) { return _index; }
void setIndex(int index) { _index = index; }
// This can be uncommented to hide the calibration buttons for gamecontrollers in the future
// bool requiresCalibration(void) final { return !_isGameController; }
private:
static void _loadGameControllerMappings();
......
......@@ -37,7 +37,7 @@ QGCView {
readonly property real _margin: ScreenTools.defaultFontPixelHeight * 0.5
readonly property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
readonly property real _rightPanelWidth: Math.min(parent.width / 3, ScreenTools.defaultFontPixelWidth * 30)
readonly property real _rightPanelOpacity: 0.8
readonly property real _rightPanelOpacity: 1
readonly property int _toolButtonCount: 6
readonly property real _toolButtonTopMargin: parent.height - ScreenTools.availableHeight + (ScreenTools.defaultFontPixelHeight / 2)
readonly property var _defaultVehicleCoordinate: QtPositioning.coordinate(37.803784, -122.462276)
......@@ -554,6 +554,7 @@ QGCView {
anchors.leftMargin: parent.width - _rightPanelWidth
anchors.left: parent.left
spacing: _horizontalMargin
visible: QGroundControl.corePlugin.options.enablePlanViewSelector
readonly property real _buttonRadius: ScreenTools.defaultFontPixelHeight * 0.75
......@@ -615,7 +616,7 @@ QGCView {
Item {
id: missionItemEditor
anchors.topMargin: _margin
anchors.top: planElementSelectorRow.bottom
anchors.top: planElementSelectorRow.visible ? planElementSelectorRow.bottom : planElementSelectorRow.top
anchors.bottom: parent.bottom
anchors.right: parent.right
width: _rightPanelWidth
......
......@@ -18,8 +18,8 @@ Rectangle {
color: _currentItem ? qgcPal.buttonHighlight : qgcPal.windowShade
radius: _radius
property var missionItem ///< MissionItem associated with this editor
property bool readOnly ///< true: read only view, false: full editing view
property var missionItem ///< MissionItem associated with this editor
property bool readOnly ///< true: read only view, false: full editing view
signal clicked
signal remove
......@@ -33,6 +33,7 @@ Rectangle {
readonly property real _editFieldWidth: Math.min(width - _margin * 2, ScreenTools.defaultFontPixelWidth * 12)
readonly property real _margin: ScreenTools.defaultFontPixelWidth / 2
readonly property real _radius: ScreenTools.defaultFontPixelWidth / 2
readonly property real _hamburgerSize: commandPicker.height * 0.75
QGCPalette {
id: qgcPal
......@@ -54,16 +55,17 @@ Rectangle {
color: _outerTextColor
}
Image {
QGCColoredImage {
id: hamburger
anchors.rightMargin: ScreenTools.defaultFontPixelWidth
anchors.right: parent.right
anchors.verticalCenter: commandPicker.verticalCenter
width: commandPicker.height
height: commandPicker.height
sourceSize.height: height
width: _hamburgerSize
height: _hamburgerSize
sourceSize.height: _hamburgerSize
source: "qrc:/qmlimages/Hamburger.svg"
visible: missionItem.isCurrentItem && missionItem.sequenceNumber != 0
color: qgcPal.windowShade
MouseArea {
anchors.fill: parent
......
This diff is collapsed.
......@@ -2,6 +2,7 @@ import QtQuick 2.5
import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.2
import QtQuick.Dialogs 1.2
import QtQuick.Layouts 1.2
import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
......@@ -42,65 +43,65 @@ Rectangle {
width: parent.width
wrapMode: Text.WordWrap
font.pointSize: ScreenTools.smallFontPointSize
text: missionItem.sequenceNumber == 0 ?
qsTr("Planned home position. Actual home position set by Vehicle.") :
(missionItem.rawEdit ?
qsTr("Provides advanced access to all commands/parameters. Be very careful!") :
missionItem.commandDescription)
text: missionItem.rawEdit ?
qsTr("Provides advanced access to all commands/parameters. Be very careful!") :
missionItem.commandDescription
}
Repeater {
model: missionItem.comboboxFacts
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columns: 2
Item {
width: valuesColumn.width
height: comboBoxFact.height
Repeater {
model: missionItem.comboboxFacts
QGCLabel {
id: comboBoxLabel
anchors.baseline: comboBoxFact.baseline
text: object.name
visible: object.name != ""
text: object.name
visible: object.name != ""
Layout.column: 0
Layout.row: index
}
}
Repeater {
model: missionItem.comboboxFacts
FactComboBox {
id: comboBoxFact
anchors.right: parent.right
width: comboBoxLabel.visible ? _editFieldWidth : parent.width
indexModel: false
model: object.enumStrings
fact: object
indexModel: false
model: object.enumStrings
fact: object
Layout.column: 1
Layout.row: index
Layout.fillWidth: true
}
}
}
Repeater {
model: missionItem.textFieldFacts
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columns: 2
Item {
width: valuesColumn.width
height: textField.height
Repeater {
model: missionItem.textFieldFacts
QGCLabel {
id: textFieldLabel
anchors.baseline: textField.baseline
text: object.name
text: object.name
Layout.column: 0
Layout.row: index
}
}
FactTextField {
id: textField
anchors.right: parent.right
width: _editFieldWidth
showUnits: true
fact: object
visible: !_root.readOnly
}
Repeater {
model: missionItem.textFieldFacts
FactLabel {
anchors.baseline: textFieldLabel.baseline
anchors.right: parent.right
FactTextField {
showUnits: true
fact: object
visible: _root.readOnly
Layout.column: 1
Layout.row: index
Layout.fillWidth: true
}
}
}
......@@ -113,13 +114,6 @@ Rectangle {
fact: object
}
}
QGCButton {
text: qsTr("Move Home to map center")
visible: missionItem.homePosition
onClicked: editorRoot.moveHomeToMapCenter()
anchors.horizontalCenter: parent.horizontalCenter
}
} // Column
} // Item
} // Component
......
This diff is collapsed.
......@@ -180,26 +180,6 @@ void ComplexMissionItemTest::_testCameraTrigger(void)
{
QCOMPARE(_complexItem->property("cameraTrigger").toBool(), true);
// Turning on/off camera triggering while there is no grid should trigger:
// cameraTriggerChanged
// dirtyChanged
// lastSequenceNumber should not change
int lastSeq = _complexItem->lastSequenceNumber();
_complexItem->setProperty("cameraTrigger", false);
QVERIFY(_multiSpy->checkOnlySignalByMask(dirtyChangedMask | cameraTriggerChangedMask));
QVERIFY(!_multiSpy->pullBoolFromSignalIndex(cameraTriggerChangedIndex));
QCOMPARE(_complexItem->lastSequenceNumber(), lastSeq);
_complexItem->setDirty(false);
_multiSpy->clearAllSignals();
_complexItem->setProperty("cameraTrigger", true);
QVERIFY(_multiSpy->checkOnlySignalByMask(dirtyChangedMask | cameraTriggerChangedMask));
QVERIFY(_multiSpy->pullBoolFromSignalIndex(cameraTriggerChangedIndex));
QCOMPARE(_complexItem->lastSequenceNumber(), lastSeq);
// Set up a grid
for (int i=0; i<3; i++) {
......@@ -209,7 +189,7 @@ void ComplexMissionItemTest::_testCameraTrigger(void)
_complexItem->setDirty(false);
_multiSpy->clearAllSignals();
lastSeq = _complexItem->lastSequenceNumber();
int lastSeq = _complexItem->lastSequenceNumber();
QVERIFY(lastSeq > 0);
// Turning off camera triggering should remove two camera trigger mission items, this should trigger:
......
......@@ -136,9 +136,13 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent)
connect(this, &SurveyMissionItem::cameraTriggerChanged, this, &SurveyMissionItem::_cameraTriggerChanged);
connect(&_cameraTriggerDistanceFact, &Fact::valueChanged, this, &SurveyMissionItem::timeBetweenShotsChanged);
connect(_vehicle, &Vehicle::cruiseSpeedChanged, this, &SurveyMissionItem::timeBetweenShotsChanged);
connect(_vehicle, &Vehicle::hoverSpeedChanged, this, &SurveyMissionItem::timeBetweenShotsChanged);
connect(&_cameraTriggerDistanceFact, &Fact::valueChanged, this, &SurveyMissionItem::timeBetweenShotsChanged);
// NULL check since object creation during unit testing passes NULL for vehicle
if (_vehicle) {
connect(_vehicle, &Vehicle::cruiseSpeedChanged, this, &SurveyMissionItem::timeBetweenShotsChanged);
connect(_vehicle, &Vehicle::hoverSpeedChanged, this, &SurveyMissionItem::timeBetweenShotsChanged);
}
}
void SurveyMissionItem::_setSurveyDistance(double surveyDistance)
......
......@@ -42,7 +42,7 @@ QColor QGCPalette::_text[QGCPalette::_cThemes][QGCPalette::_cColorGroups] = {
QColor QGCPalette::_warningText[QGCPalette::_cThemes][QGCPalette::_cColorGroups] = {
{ QColor("#cc0808"), QColor("#cc0808") },
{ QColor("#e4e428"), QColor("#e4e428") }
{ QColor("#fd5d13"), QColor("#fd5d13") }
};
QColor QGCPalette::_button[QGCPalette::_cThemes][QGCPalette::_cColorGroups] = {
......@@ -57,7 +57,7 @@ QColor QGCPalette::_buttonText[QGCPalette::_cThemes][QGCPalette::_cColorGroups]
QColor QGCPalette::_buttonHighlight[QGCPalette::_cThemes][QGCPalette::_cColorGroups] = {
{ QColor("#e4e4e4"), QColor("#33b5e5") },
{ QColor(0x58, 0x58, 0x58), QColor(237, 235, 51) },
{ QColor(0x58, 0x58, 0x58), QColor(0xed, 0xd4, 0x69) },
};
QColor QGCPalette::_buttonHighlightText[QGCPalette::_cThemes][QGCPalette::_cColorGroups] = {
......
......@@ -79,7 +79,7 @@ private:
MAVLinkProtocol* _mavlinkProtocol;
MissionCommandTree* _missionCommandTree;
MultiVehicleManager* _multiVehicleManager;
QGCMapEngineManager* _mapEngineManager;
QGCMapEngineManager* _mapEngineManager;
UASMessageHandler* _uasMessageHandler;
FollowMe* _followMe;
QGCPositionManager* _qgcPositionManager;
......
......@@ -12,6 +12,7 @@ import QtQuick 2.5
import QtQuick.Controls 1.4
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
......@@ -110,6 +111,25 @@ Column {
onValueChanged: {
if (_loadComplete) {
fact.value = value
}
}
activeFocusOnPress: true
MultiPointTouchArea {
anchors.fill: parent
minimumTouchPoints: 1
maximumTouchPoints: 1
mouseEnabled: false
}
// Block wheel events
MouseArea {
anchors.fill: parent
acceptedButtons: Qt.NoButton
onWheel: {
wheel.accepted = true
}
}
} // Slider
......
......@@ -56,6 +56,17 @@ QGCView {
anchors.right: parent.right
spacing: ScreenTools.defaultFontPixelWidth
Timer {
id: clearTimer
interval: 100;
running: false;
repeat: false
onTriggered: {
searchText.text = ""
controller.searchText = ""
}
}
QGCLabel {
anchors.baseline: clearButton.baseline
text: qsTr("Search:")
......@@ -71,7 +82,12 @@ QGCView {
QGCButton {
id: clearButton
text: qsTr("Clear")
onClicked: searchText.text = ""
onClicked: {
if(ScreenTools.isMobile) {
Qt.inputMethod.hide();
}
clearTimer.start()
}
}
} // Row - Header
......@@ -118,6 +134,11 @@ QGCView {
onTriggered: controller.clearRCToParam()
visible: _showRCToParam
}
MenuSeparator { }
MenuItem {
text: qsTr("Reboot Vehicle")
onTriggered: showDialog(rebootVehicleConfirmComponent, qsTr("Reboot Vehicle"), qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
}
}
}
......@@ -294,4 +315,21 @@ QGCView {
}
}
}
Component {
id: rebootVehicleConfirmComponent
QGCViewDialog {
function accept() {
QGroundControl.multiVehicleManager.activeVehicle.rebootVehicle()
hideDialog()
}
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
text: qsTr("Select Ok to reboot vehicle.")
}
}
}
} // QGCView
......@@ -36,20 +36,20 @@ public:
Q_PROPERTY(QmlObjectListModel* parameters MEMBER _parameters CONSTANT)
Q_PROPERTY(QVariantList componentIds MEMBER _componentIds CONSTANT)
Q_INVOKABLE QStringList getGroupsForComponent(int componentId);
Q_INVOKABLE QStringList getParametersForGroup(int componentId, QString group);
Q_INVOKABLE QStringList getGroupsForComponent(int componentId);
Q_INVOKABLE QStringList getParametersForGroup(int componentId, QString group);
Q_INVOKABLE QStringList searchParametersForComponent(int componentId, const QString& searchText, bool searchInName=true, bool searchInDescriptions=true);
Q_INVOKABLE void clearRCToParam(void);
Q_INVOKABLE void clearRCToParam(void);
Q_INVOKABLE void saveToFilePicker(void);
Q_INVOKABLE void loadFromFilePicker(void);
Q_INVOKABLE void saveToFile(const QString& filename);
Q_INVOKABLE void loadFromFile(const QString& filename);
Q_INVOKABLE void refresh(void);
Q_INVOKABLE void resetAllToDefaults(void);
Q_INVOKABLE void setRCToParam(const QString& paramName);
Q_INVOKABLE void setRCToParam(const QString& paramName);
QList<QObject*> model(void);
QList<QObject*> model(void);
signals:
void searchTextChanged(QString searchText);
......
......@@ -7,12 +7,9 @@
*
****************************************************************************/
/// @file
/// @author Don Gagne <don@thegagnes.com>
import QtQuick 2.5
import QtQuick.Controls 1.3
import QtQuick.Layouts 1.2
import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
......@@ -29,7 +26,8 @@ QGCViewDialog {
property bool validate: false
property string validateValue
property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 20
property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 20
property bool _longDescriptionAvailable: fact.longDescription != ""
ParameterEditorController { id: controller; factPanel: parent }
......@@ -68,7 +66,6 @@ QGCViewDialog {
validationError.text = fact.validate(validateValue, false /* convertOnly */)
forceSave.visible = true
}
//valueField.forceActiveFocus()
}
QGCFlickable {
......@@ -83,28 +80,24 @@ QGCViewDialog {
anchors.right: parent.right
QGCLabel {
id: validationError
width: parent.width
wrapMode: Text.WordWrap
visible: fact.shortDescription
text: fact.shortDescription
}
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
visible: fact.longDescription
text: fact.longDescription
color: qgcPal.warningText
}
Row {
spacing: defaultTextWidth
RowLayout {
spacing: defaultTextWidth
anchors.left: parent.left
anchors.right: parent.right
QGCTextField {
id: valueField
text: validate ? validateValue : fact.valueString
visible: fact.enumStrings.length == 0 || validate
//focus: true
id: valueField
text: validate ? validateValue : fact.valueString
visible: fact.enumStrings.length == 0 || validate
unitsLabel: fact.units
showUnits: fact.units != ""
Layout.fillWidth: true
inputMethodHints: ScreenTools.isiOS ?
Qt.ImhNone : // iOS numeric keyboard has not done button, we can't use it
Qt.ImhFormattedNumbersOnly // Forces use of virtual numeric keyboard
......@@ -113,7 +106,6 @@ QGCViewDialog {
QGCButton {
anchors.baseline: valueField.baseline
visible: fact.defaultValueAvailable
width: _editFieldWidth
text: qsTr("Reset to default")
onClicked: {
......@@ -159,63 +151,55 @@ QGCViewDialog {
}
QGCLabel {
text: fact.name
visible: fact.componentId > 0 // > 0 means it's a parameter fact
width: parent.width
wrapMode: Text.WordWrap
visible: !longDescriptionLabel.visible
text: fact.shortDescription
}
Column {
spacing: defaultTextHeight / 2
anchors.left: parent.left
anchors.right: parent.right
Row {
spacing: defaultTextWidth
QGCLabel { text: qsTr("Units:") }
QGCLabel { text: fact.units ? fact.units : qsTr("none") }
}
Row {
spacing: defaultTextWidth
visible: !fact.minIsDefaultForType
QGCLabel { text: qsTr("Minimum value:") }
QGCLabel { text: fact.minString }
}
QGCLabel {
id: longDescriptionLabel
width: parent.width
wrapMode: Text.WordWrap
visible: fact.longDescription != ""
text: fact.longDescription
}
Row {
spacing: defaultTextWidth
visible: !fact.maxIsDefaultForType
Row {
spacing: defaultTextWidth
QGCLabel { text: qsTr("Maximum value:") }
QGCLabel { text: fact.maxString }
QGCLabel {
id: minValueDisplay
text: qsTr("Min: ") + fact.minString
visible: !fact.minIsDefaultForType
}
Row {
spacing: defaultTextWidth
QGCLabel { text: qsTr("Default value:") }
QGCLabel { text: fact.defaultValueAvailable ? fact.defaultValueString : qsTr("none") }
QGCLabel {
text: qsTr("Max: ") + fact.maxString
visible: !fact.maxIsDefaultForType
}
QGCLabel {
visible: fact.rebootRequired
text: "Reboot required after change"
text: qsTr("Default: ") + fact.defaultValueString
visible: fact.defaultValueAvailable
}
} // Column
}
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
text: qsTr("Warning: Modifying values while vehicle is in flight can lead to vehicle instability and possible vehicle loss. ") +
qsTr("Make sure you know what you are doing and double-check your values before Save!")
text: qsTr("Parameter name: ") + fact.name
visible: fact.componentId > 0 // > 0 means it's a parameter fact
}
QGCLabel {
visible: fact.rebootRequired
text: "Reboot required after change"
}
QGCLabel {
id: validationError
width: parent.width
wrapMode: Text.WordWrap
color: qsTr("yellow")
text: qsTr("Warning: Modifying values while vehicle is in flight can lead to vehicle instability and possible vehicle loss. ") +
qsTr("Make sure you know what you are doing and double-check your values before Save!")
}
QGCCheckBox {
......
......@@ -50,10 +50,10 @@ Button {
style: ButtonStyle {
/*! The padding between the background and the label components. */
padding {
top: __padding
top: __padding * 0.5
left: __padding
right: control.menu !== null ? Math.round(ScreenTools.defaultFontPixelHeight) : __padding
bottom: __padding
bottom: __padding * 0.5
}
/*! This defines the background of the button. */
......@@ -66,6 +66,7 @@ Button {
anchors.fill: parent
border.width: _showBorder ? 1: 0
border.color: _qgcPal.buttonText
//radius: 3
color: _showHighlight ?
control._qgcPal.buttonHighlight :
(primary ? control._qgcPal.primaryButton : control._qgcPal.button)
......
......@@ -24,6 +24,7 @@ ComboBox {
Rectangle {
anchors.fill: parent
color: _showHighlight ? control._qgcPal.buttonHighlight : control._qgcPal.button
//radius: 3
border.width: _showBorder ? 1: 0
border.color: control._qgcPal.buttonText
}
......
......@@ -6,6 +6,7 @@ import QGroundControl.Palette 1.0
Flickable {
id: root
boundsBehavior: Flickable.StopAtBounds
clip: true
property color indicatorColor: qgcPal.text
......
......@@ -97,9 +97,10 @@ TextField {
}
MouseArea {
anchors.fill: unitsHelpLayout
enabled: control.activeFocus
onClicked: root.helpClicked()
anchors.margins: ScreenTools.isMobile ? -(ScreenTools.defaultFontPixelWidth * 0.66) : 0 // Larger touch area for mobile
anchors.fill: unitsHelpLayout
enabled: control.activeFocus
onClicked: root.helpClicked()
}
}
......
......@@ -46,6 +46,7 @@ QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app)
, _videoManager(NULL)
, _mavlinkLogManager(NULL)
, _corePlugin(NULL)
, _firmwarePluginManager(NULL)
, _virtualTabletJoystick(false)
, _baseFontPointSize(0.0)
{
......@@ -74,6 +75,7 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox)
_videoManager = toolbox->videoManager();
_mavlinkLogManager = toolbox->mavlinkLogManager();
_corePlugin = toolbox->corePlugin();
_firmwarePluginManager = toolbox->firmwarePluginManager();
}
void QGroundControlQmlGlobal::saveGlobalSetting (const QString& key, const QString& value)
......@@ -337,6 +339,12 @@ Fact* QGroundControlQmlGlobal::batteryPercentRemainingAnnounce(void)
return _batteryPercentRemainingAnnounceFact;
}
int QGroundControlQmlGlobal::supportedFirmwareCount()
{
return _firmwarePluginManager->knownFirmwareTypes().count();
}
bool QGroundControlQmlGlobal::linesIntersect(QPointF line1A, QPointF line1B, QPointF line2A, QPointF line2B)
{
QPointF intersectPoint;
......
......@@ -99,6 +99,7 @@ public:
Q_PROPERTY(Fact* areaUnits READ areaUnits CONSTANT)
Q_PROPERTY(Fact* speedUnits READ speedUnits CONSTANT)
Q_PROPERTY(Fact* batteryPercentRemainingAnnounce READ batteryPercentRemainingAnnounce CONSTANT)
Q_PROPERTY(int supportedFirmwareCount READ supportedFirmwareCount CONSTANT)
Q_PROPERTY(QGeoCoordinate lastKnownHomePosition READ lastKnownHomePosition CONSTANT)
Q_PROPERTY(QGeoCoordinate flightMapPosition MEMBER _flightMapPosition NOTIFY flightMapPositionChanged)
......@@ -196,6 +197,8 @@ public:
static Fact* speedUnits (void);
static Fact* batteryPercentRemainingAnnounce(void);
int supportedFirmwareCount ();
void setIsDarkStyle (bool dark);
void setIsAudioMuted (bool muted);
void setIsSaveLogPrompt (bool prompt);
......@@ -245,6 +248,7 @@ private:
VideoManager* _videoManager;
MAVLinkLogManager* _mavlinkLogManager;
QGCCorePlugin* _corePlugin;
FirmwarePluginManager* _firmwarePluginManager;
bool _virtualTabletJoystick;
qreal _baseFontPointSize;
......
......@@ -47,7 +47,7 @@ Item {
property real largeFontPointSize: 10
property real availableHeight: 0
property real toolbarHeight: defaultFontPixelHeight * 3
property real toolbarHeight: 0
readonly property real smallFontPointRatio: 0.75
readonly property real mediumFontPointRatio: 1.25
......@@ -93,6 +93,7 @@ Item {
smallFontPointSize = defaultFontPointSize * _screenTools.smallFontPointRatio
mediumFontPointSize = defaultFontPointSize * _screenTools.mediumFontPointRatio
largeFontPointSize = defaultFontPointSize * _screenTools.largeFontPointRatio
toolbarHeight = defaultFontPixelHeight * 3 * QGroundControl.corePlugin.options.toolbarHeightMultiplier
}
Text {
......@@ -107,7 +108,10 @@ Item {
property real fontWidth: contentWidth
property real fontHeight: contentHeight
Component.onCompleted: {
var baseSize = QGroundControl.baseFontPointSize;
var baseSize = QGroundControl.corePlugin.options.defaultFontPointSize
if(baseSize == 0.0) {
baseSize = QGroundControl.baseFontPointSize;
}
//-- If this is the first time (not saved in settings)
if(baseSize < 6 || baseSize > 48) {
//-- Init base size base on the platform
......
......@@ -42,34 +42,35 @@ public:
Q_INVOKABLE int mouseX(void) { return QCursor::pos().x(); }
Q_INVOKABLE int mouseY(void) { return QCursor::pos().y(); }
#if defined(__mobile__)
bool isMobile () { return true; }
#else
bool isMobile () { return qgcApp()->fakeMobile(); }
#endif
#if defined (__android__)
bool isAndroid () { return true; }
bool isiOS () { return false; }
bool isMobile () { return true; }
bool isLinux () { return false; }
bool isMacOS () { return false; }
#elif defined(__ios__)
bool isAndroid () { return false; }
bool isiOS () { return true; }
bool isMobile () { return true; }
bool isLinux () { return false; }
bool isMacOS () { return false; }
#elif defined(__macos__)
bool isAndroid () { return false; }
bool isiOS () { return false; }
bool isMobile () { return qgcApp()->fakeMobile(); }
bool isLinux () { return false; }
bool isMacOS () { return true; }
#elif defined(Q_OS_LINUX)
bool isAndroid () { return false; }
bool isiOS () { return false; }
bool isMobile () { return qgcApp()->fakeMobile(); }
bool isLinux () { return true; }
bool isMacOS () { return false; }
#else
bool isAndroid () { return false; }
bool isiOS () { return false; }
bool isMobile () { return qgcApp()->fakeMobile(); }
bool isLinux () { return false; }
bool isMacOS () { return false; }
#endif
......
......@@ -130,11 +130,13 @@ QGCMapEngine::QGCMapEngine()
, _maxMemCache(0)
, _prunning(false)
, _cacheWasReset(false)
, _isInternetActive(false)
{
qRegisterMetaType<QGCMapTask::TaskType>();
qRegisterMetaType<QGCTile>();
qRegisterMetaType<QList<QGCTile*>>();
connect(&_worker, &QGCCacheWorker::updateTotals, this, &QGCMapEngine::_updateTotals);
connect(&_worker, &QGCCacheWorker::updateTotals, this, &QGCMapEngine::_updateTotals);
connect(&_worker, &QGCCacheWorker::internetStatus, this, &QGCMapEngine::_internetStatus);
}
//-----------------------------------------------------------------------------
......@@ -483,5 +485,19 @@ QGCCreateTileSetTask::~QGCCreateTileSetTask()
delete _tileSet;
}
//-----------------------------------------------------------------------------
void
QGCMapEngine::testInternet()
{
getQGCMapEngine()->addTask(new QGCTestInternetTask());
}
//-----------------------------------------------------------------------------
void
QGCMapEngine::_internetStatus(bool active)
{
_isInternetActive = active;
}
// Resolution math: https://wiki.openstreetmap.org/wiki/Slippy_map_tilenames#Resolution_and_Scale
......@@ -86,7 +86,9 @@ public:
void setMaxMemCache (quint32 size);
const QString getCachePath () { return _cachePath; }
const QString getCacheFilename () { return _cacheFile; }
void testInternet ();
bool wasCacheReset () { return _cacheWasReset; }
bool isInternetActive () { return _isInternetActive; }
UrlFactory* urlFactory () { return _urlFactory; }
......@@ -103,6 +105,7 @@ public:
private slots:
void _updateTotals (quint32 totaltiles, quint64 totalsize, quint32 defaulttiles, quint64 defaultsize);
void _pruned ();
void _internetStatus (bool active);
signals:
void updateTotals (quint32 totaltiles, quint64 totalsize, quint32 defaulttiles, quint64 defaultsize);
......@@ -123,6 +126,7 @@ private:
quint32 _maxMemCache;
bool _prunning;
bool _cacheWasReset;
bool _isInternetActive;
};
extern QGCMapEngine* getQGCMapEngine();
......
......@@ -110,6 +110,7 @@ public:
enum TaskType {
taskInit,
taskTestInternet,
taskCacheTile,
taskFetchTile,
taskFetchTileSets,
......@@ -129,7 +130,7 @@ public:
virtual TaskType type () { return _type; }
void setError(QString errorString)
void setError(QString errorString = QString())
{
emit error(_type, errorString);
}
......@@ -141,6 +142,16 @@ private:
TaskType _type;
};
//-----------------------------------------------------------------------------
class QGCTestInternetTask : public QGCMapTask
{
Q_OBJECT
public:
QGCTestInternetTask()
: QGCMapTask(QGCMapTask::taskTestInternet)
{}
};
//-----------------------------------------------------------------------------
class QGCFetchTileSetTask : public QGCMapTask
{
......
......@@ -232,11 +232,20 @@ void QGCCachedTileSet::_prepareDownload()
_tilesToDownload.removeFirst();
QNetworkRequest request = getQGCMapEngine()->urlFactory()->getTileURL(tile->type(), tile->x(), tile->y(), tile->z(), _networkManager);
request.setAttribute(QNetworkRequest::User, tile->hash());
#if !defined(__mobile__)
QNetworkProxy proxy = _networkManager->proxy();
QNetworkProxy tProxy;
tProxy.setType(QNetworkProxy::DefaultProxy);
_networkManager->setProxy(tProxy);
#endif
QNetworkReply* reply = _networkManager->get(request);
reply->setParent(0);
connect(reply, &QNetworkReply::finished, this, &QGCCachedTileSet::_networkReplyFinished);
connect(reply, static_cast<void (QNetworkReply::*)(QNetworkReply::NetworkError)>(&QNetworkReply::error), this, &QGCCachedTileSet::_networkReplyError);
_replies.insert(tile->hash(), reply);
#if !defined(__mobile__)
_networkManager->setProxy(proxy);
#endif
delete tile;
//-- Refill queue if running low
if(!_batchRequested && !_noMoreTiles && _tilesToDownload.count() < (QGCMapEngine::concurrentDownloads(_type) * 10)) {
......@@ -309,7 +318,7 @@ QGCCachedTileSet::_networkReplyError(QNetworkReply::NetworkError error)
if (!reply) {
return;
}
//-- Upodate error count
//-- Update error count
_errorCount++;
emit errorCountChanged();
//-- Get tile hash
......
......@@ -93,20 +93,15 @@ QGCCacheWorker::enqueueTask(QGCMapTask* task)
task->deleteLater();
return false;
}
if(!_taskQueue.contains(task))
{
_mutex.lock();
_taskQueue.enqueue(task);
_mutex.unlock();
if(this->isRunning()) {
_waitc.wakeAll();
} else {
this->start(QThread::NormalPriority);
}
return true;
_mutex.lock();
_taskQueue.enqueue(task);
_mutex.unlock();
if(this->isRunning()) {
_waitc.wakeAll();
} else {
this->start(QThread::HighPriority);
}
//-- Should never happen
return false;
return true;
}
//-----------------------------------------------------------------------------
......@@ -158,6 +153,9 @@ QGCCacheWorker::run()
case QGCMapTask::taskReset:
_resetCacheDatabase(task);
break;
case QGCMapTask::taskTestInternet:
_testInternet();
break;
}
task->deleteLater();
//-- Check for update timeout
......@@ -662,6 +660,7 @@ QGCCacheWorker::_init()
qCritical() << "Could not find suitable cache directory.";
_failed = true;
}
_testInternet();
return _failed;
}
......@@ -749,3 +748,17 @@ QGCCacheWorker::_createDB()
}
_failed = !_valid;
}
//-----------------------------------------------------------------------------
void
QGCCacheWorker::_testInternet()
{
QTcpSocket socket;
socket.connectToHost("8.8.8.8", 53);
if (socket.waitForConnected(2500)) {
emit internetStatus(true);
return;
}
qWarning() << "No Internet Access";
emit internetStatus(false);
}
......@@ -59,6 +59,7 @@ private:
void _deleteTileSet (QGCMapTask* mtask);
void _resetCacheDatabase (QGCMapTask* mtask);
void _pruneCache (QGCMapTask* mtask);
void _testInternet ();
quint64 _findTile (const QString hash);
bool _findTileSetID (const QString name, quint64& setID);
......@@ -70,6 +71,7 @@ private:
signals:
void updateTotals (quint32 totaltiles, quint64 totalsize, quint32 defaulttiles, quint64 defaultsize);
void internetStatus (bool active);
private:
QQueue<QGCMapTask*> _taskQueue;
......
......@@ -46,11 +46,14 @@
#include "QGCMapEngine.h"
#include "QGeoMapReplyQGC.h"
#include "QGeoTileFetcherQGC.h"
#include <QtLocation/private/qgeotilespec_p.h>
#include <QtNetwork/QNetworkAccessManager>
#include <QFile>
int QGeoTiledMapReplyQGC::_requestCount = 0;
//-----------------------------------------------------------------------------
QGeoTiledMapReplyQGC::QGeoTiledMapReplyQGC(QNetworkAccessManager *networkManager, const QNetworkRequest &request, const QGeoTileSpec &spec, QObject *parent)
: QGeoTiledMapReply(spec, parent)
......@@ -59,15 +62,7 @@ QGeoTiledMapReplyQGC::QGeoTiledMapReplyQGC(QNetworkAccessManager *networkManager
, _networkManager(networkManager)
{
if(_request.url().isEmpty()) {
if(!_badMapBox.size()) {
QFile b(":/res/notile.png");
if(b.open(QFile::ReadOnly))
_badMapBox = b.readAll();
}
setMapImageData(_badMapBox);
setMapImageFormat("png");
setFinished(true);
setCached(false);
_returnBadTile();
} else {
QGCFetchTileTask* task = getQGCMapEngine()->createFetchTileTask((UrlFactory::MapType)spec.mapId(), spec.x(), spec.y(), spec.zoom());
connect(task, &QGCFetchTileTask::tileFetched, this, &QGeoTiledMapReplyQGC::cacheReply);
......@@ -78,31 +73,49 @@ QGeoTiledMapReplyQGC::QGeoTiledMapReplyQGC(QNetworkAccessManager *networkManager
//-----------------------------------------------------------------------------
QGeoTiledMapReplyQGC::~QGeoTiledMapReplyQGC()
{
_clearReply();
}
//-----------------------------------------------------------------------------
void
QGeoTiledMapReplyQGC::_clearReply()
{
if (_reply) {
_reply->deleteLater();
_reply = 0;
_requestCount--;
}
}
//-----------------------------------------------------------------------------
void
QGeoTiledMapReplyQGC::abort()
QGeoTiledMapReplyQGC::_returnBadTile()
{
if (_reply)
_reply->abort();
if(!_badMapBox.size()) {
QFile b(":/res/notile.png");
if(b.open(QFile::ReadOnly))
_badMapBox = b.readAll();
}
setMapImageData(_badMapBox);
setMapImageFormat("png");
setFinished(true);
setCached(false);
}
//-----------------------------------------------------------------------------
void
QGeoTiledMapReplyQGC::replyDestroyed()
QGeoTiledMapReplyQGC::abort()
{
_reply = 0;
if (_reply)
_reply->abort();
}
//-----------------------------------------------------------------------------
void
QGeoTiledMapReplyQGC::networkReplyFinished()
{
_timer.stop();
if (!_reply) {
return;
}
......@@ -117,51 +130,54 @@ QGeoTiledMapReplyQGC::networkReplyFinished()
getQGCMapEngine()->cacheTile((UrlFactory::MapType)tileSpec().mapId(), tileSpec().x(), tileSpec().y(), tileSpec().zoom(), a, format);
}
setFinished(true);
_reply->deleteLater();
_reply = 0;
_clearReply();
}
//-----------------------------------------------------------------------------
void
QGeoTiledMapReplyQGC::networkReplyError(QNetworkReply::NetworkError error)
{
_timer.stop();
if (!_reply) {
return;
}
if (error != QNetworkReply::OperationCanceledError) {
qWarning() << "Fetch tile error:" << _reply->errorString();
}
_reply->deleteLater();
_reply = 0;
if(!_badTile.size()) {
QFile b(":/res/notile.png");
if(b.open(QFile::ReadOnly))
_badTile = b.readAll();
}
setMapImageData(_badTile);
setMapImageFormat("png");
setFinished(true);
setCached(false);
_returnBadTile();
_clearReply();
}
//-----------------------------------------------------------------------------
void
QGeoTiledMapReplyQGC::cacheError(QGCMapTask::TaskType type, QString /*errorString*/)
{
if(type != QGCMapTask::taskFetchTile) {
qWarning() << "QGeoTiledMapReplyQGC::cacheError() for wrong task";
if(_networkManager->networkAccessible() < QNetworkAccessManager::Accessible || !getQGCMapEngine()->isInternetActive()) {
_returnBadTile();
} else {
if(type != QGCMapTask::taskFetchTile) {
qWarning() << "QGeoTiledMapReplyQGC::cacheError() for wrong task";
}
//-- Tile not in cache. Get it off the Internet.
#if !defined(__mobile__)
QNetworkProxy proxy = _networkManager->proxy();
QNetworkProxy tProxy;
tProxy.setType(QNetworkProxy::DefaultProxy);
_networkManager->setProxy(tProxy);
#endif
_reply = _networkManager->get(_request);
_reply->setParent(0);
connect(_reply, SIGNAL(finished()), this, SLOT(networkReplyFinished()));
connect(_reply, SIGNAL(error(QNetworkReply::NetworkError)), this, SLOT(networkReplyError(QNetworkReply::NetworkError)));
#if !defined(__mobile__)
_networkManager->setProxy(proxy);
#endif
//- Wait for an answer up to 10 seconds
connect(&_timer, &QTimer::timeout, this, &QGeoTiledMapReplyQGC::timeout);
_timer.setSingleShot(true);
_timer.start(10000);
_requestCount++;
}
//-- Tile not in cache. Get it off the Internet.
QNetworkProxy proxy = _networkManager->proxy();
QNetworkProxy tProxy;
tProxy.setType(QNetworkProxy::DefaultProxy);
_networkManager->setProxy(tProxy);
_reply = _networkManager->get(_request);
_reply->setParent(0);
connect(_reply, SIGNAL(finished()), this, SLOT(networkReplyFinished()));
connect(_reply, SIGNAL(error(QNetworkReply::NetworkError)), this, SLOT(networkReplyError(QNetworkReply::NetworkError)));
connect(_reply, SIGNAL(destroyed()), this, SLOT(replyDestroyed()));
_networkManager->setProxy(proxy);
}
//-----------------------------------------------------------------------------
......@@ -174,3 +190,12 @@ QGeoTiledMapReplyQGC::cacheReply(QGCCacheTile* tile)
setCached(true);
tile->deleteLater();
}
//-----------------------------------------------------------------------------
void
QGeoTiledMapReplyQGC::timeout()
{
if(_reply) {
_reply->abort();
}
}
......@@ -49,6 +49,7 @@
#include <QtNetwork/QNetworkReply>
#include <QtLocation/private/qgeotiledmapreply_p.h>
#include <QTimer>
#include "QGCMapEngineData.h"
......@@ -61,11 +62,15 @@ public:
void abort();
private slots:
void replyDestroyed ();
void networkReplyFinished ();
void networkReplyError (QNetworkReply::NetworkError error);
void cacheReply (QGCCacheTile* tile);
void cacheError (QGCMapTask::TaskType type, QString errorString);
void timeout ();
private:
void _clearReply ();
void _returnBadTile ();
private:
QNetworkReply* _reply;
......@@ -73,6 +78,8 @@ private:
QNetworkAccessManager* _networkManager;
QByteArray _badMapBox;
QByteArray _badTile;
QTimer _timer;
static int _requestCount;
};
#endif // QGEOMAPREPLYQGC_H
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
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