diff --git a/QGCInstaller.pri b/QGCInstaller.pri index 88d98e5c73dbb01095d94b8cd2819387c342da9b..9873915e882d01f3cbb6aa656aa41c795a8755c6 100644 --- a/QGCInstaller.pri +++ b/QGCInstaller.pri @@ -35,7 +35,7 @@ installer { QMAKE_POST_LINK += && hdiutil create -verbose -stretch 4g -layout SPUD -srcfolder $${DESTDIR}/$${TARGET}.app -volname $${TARGET} $${DESTDIR}/package/$${TARGET}.dmg } WindowsBuild { - QMAKE_POST_LINK += $$escape_expand(\\n) cd $$BASEDIR_WIN && $$quote("\"C:\\Program Files \(x86\)\\NSIS\\makensis.exe\"" /DAPPNAME="\"$${QGC_APP_NAME}\"" /DEXENAME="\"$${TARGET}\"" /DORGNAME="\"$${QGC_ORG_NAME}\"" /DDESTDIR=$${DESTDIR} /NOCD "\"/XOutFile $${DESTDIR_WIN}\\$${TARGET}-installer.exe\"" "$$BASEDIR_WIN\\deploy\\qgroundcontrol_installer.nsi") + QMAKE_POST_LINK += $$escape_expand(\\n) cd $$BASEDIR_WIN && $$quote("\"C:\\Program Files \(x86\)\\NSIS\\makensis.exe\"" /DINSTALLER_ICON="\"$${QGC_INSTALLER_ICON}\"" /DHEADER_BITMAP="\"$${QGC_INSTALLER_HEADER_BITMAP}\"" /DAPPNAME="\"$${QGC_APP_NAME}\"" /DEXENAME="\"$${TARGET}\"" /DORGNAME="\"$${QGC_ORG_NAME}\"" /DDESTDIR=$${DESTDIR} /NOCD "\"/XOutFile $${DESTDIR_WIN}\\$${TARGET}-installer.exe\"" "$$BASEDIR_WIN\\deploy\\qgroundcontrol_installer.nsi") OTHER_FILES += deploy/qgroundcontrol_installer.nsi } LinuxBuild { diff --git a/deploy/qgroundcontrol_installer.nsi b/deploy/qgroundcontrol_installer.nsi index a7a952d6280a3e67ff7957cc23a8a53928b04b69..67a17f29dd89737bdbb8d123fdf30ffda7e8b9ff 100644 --- a/deploy/qgroundcontrol_installer.nsi +++ b/deploy/qgroundcontrol_installer.nsi @@ -44,9 +44,9 @@ InstallDir "$PROGRAMFILES\${APPNAME}" SetCompressor /SOLID /FINAL lzma !define MUI_HEADERIMAGE -!define MUI_HEADERIMAGE_BITMAP "installheader.bmp"; -!define MUI_ICON "WindowsQGC.ico"; -!define MUI_UNICON "WindowsQGC.ico"; +!define MUI_HEADERIMAGE_BITMAP "${HEADER_BITMAP}"; +!define MUI_ICON "${INSTALLER_ICON}"; +!define MUI_UNICON "${INSTALLER_ICON}"; !insertmacro MUI_PAGE_STARTMENU Application $StartMenuFolder !insertmacro MUI_PAGE_DIRECTORY diff --git a/ios/iOSForAppStore-Info-Source.plist b/ios/iOSForAppStore-Info-Source.plist index 09f03afee2d0bcb324b04aba1e4e381c0b4a6edb..de8c15ec7a3cf9955a5b701bfe2cd2450ce407aa 100644 --- a/ios/iOSForAppStore-Info-Source.plist +++ b/ios/iOSForAppStore-Info-Source.plist @@ -85,6 +85,8 @@ Ground Station Location UILaunchStoryboardName QGCLaunchScreen + NSBluetoothPeripheralUsageDescription + QGroundControl would like to use bluetooth. UIRequiresFullScreen UISupportedInterfaceOrientations diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 69406dffcf6f90fbe0fd180a739a472309c1ae5b..71426a1851091bb0af102b0b45e65f9abe43a205 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -55,6 +55,8 @@ iOSBuild { count(APP_ERROR, 1) { error("Error building .plist file. 'ForAppStore' builds are only possible through the official build system.") } + QT += qml-private + CONFIG += qtquickcompiler QMAKE_INFO_PLIST = $${BASEDIR}/ios/iOSForAppStore-Info.plist OTHER_FILES += $${BASEDIR}/ios/iOSForAppStore-Info.plist } else { @@ -82,6 +84,10 @@ QGC_ORG_DOMAIN = "org.qgroundcontrol" QGC_APP_DESCRIPTION = "Open source ground control app provided by QGroundControl dev team" QGC_APP_COPYRIGHT = "Copyright (C) 2017 QGroundControl Development Team. All rights reserved." +WindowsBuild { + QGC_INSTALLER_ICON = "WindowsQGC.ico" + QGC_INSTALLER_HEADER_BITMAP = "installheader.bmp" +} # Load additional config flags from user_config.pri exists(user_config.pri):infile(user_config.pri, CONFIG) { diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index 26ada3e125df3084d174ce229afeb57b2fc3a14a..328ec17a28a65aeb21dbf1087f89b7a906d88d56 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -74,6 +74,7 @@ src/PlanView/MissionItemStatus.qml src/QmlControls/ModeSwitchDisplay.qml src/QmlControls/MultiRotorMotorDisplay.qml + src/QmlControls/NoMouseThroughRectangle.qml src/QmlControls/OfflineMapButton.qml src/QmlControls/ParameterEditor.qml src/QmlControls/ParameterEditorDialog.qml diff --git a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml index ab7acd0a247a3deaf9616be219a15d37d1ab76e1..480b910d744e82c397c6115643fc948463a6d9a3 100644 --- a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml +++ b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml @@ -5,6 +5,7 @@ 1 + Copter Emmanuel Roussel Coaxial Helicopter Left swashplate servomotor, pitch axis @@ -13,77 +14,28 @@ Lower rotor (CW) - - - Simon Wilks <simon@px4.io> - Flying Wing - https://pixhawk.org/platforms/planes/bormatec_camflyer_q - left aileron - right aileron - throttle - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - - - Simon Wilks <simon@px4.io> - Flying Wing - https://pixhawk.org/platforms/planes/z-84_wing_wing - left aileron - right aileron - throttle - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - - - Thomas Gubler <thomas@px4.io>, Julian Oes <julian@px4.io> - Flying Wing - https://pixhawk.org/platforms/planes/skywalker_x5 - left aileron - right aileron - throttle - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - - - Lorenz Meier <lorenz@px4.io> - Flying Wing - https://pixhawk.org/platforms/planes/z-84_wing_wing - left aileron - right aileron - throttle - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - - - Simon Wilks <simon@px4.io> - Flying Wing - - - Simon Wilks <simon@px4.io> - Flying Wing - - - Simon Wilks <simon@px4.io> - Flying Wing - http://www.sparkletech.hk/ - left aileron - right aileron - throttle - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - - - Lorenz Meier <lorenz@px4.io> - Flying Wing + + + Copter + William Peale <develop707@gmail.com> + Dodecarotor cox + motor 1 + motor 2 + motor 3 + motor 4 + motor 5 + motor 6 + motor 7 + motor 8 + motor 9 + motor 10 + motor 11 + motor 12 + Copter Bart Slinger <bartslinger@gmail.com> Helicopter main motor @@ -94,8 +46,9 @@ - - Anton Babushkin <anton@px4.io> + + Copter + Lorenz Meier <lorenz@px4.io> Hexarotor + motor1 motor2 @@ -110,6 +63,7 @@ + Copter Lorenz Meier <lorenz@px4.io> Hexarotor Coaxial front right top, CW @@ -124,8 +78,9 @@ - - Anton Babushkin <anton@px4.io> + + Copter + Lorenz Meier <lorenz@px4.io> Hexarotor x motor 1 motor 2 @@ -140,6 +95,7 @@ + Copter Simon Wilks <simon@uaventure.com> Octo Coax Wide motor 1 @@ -153,8 +109,9 @@ - - Anton Babushkin <anton@px4.io> + + Copter + Lorenz Meier <lorenz@px4.io> Octorotor + motor 1 motor 2 @@ -171,6 +128,7 @@ + Copter Lorenz Meier <lorenz@px4.io> Octorotor Coaxial motor 1 @@ -184,8 +142,9 @@ - - Anton Babushkin <anton@px4.io> + + Copter + Lorenz Meier <lorenz@px4.io> Octorotor x motor 1 motor 2 @@ -200,26 +159,10 @@ feed-through of RC AUX3 channel - - - Andreas Antener <andreas@uaventure.com> - Plane A-Tail - aileron right - aileron left - v-tail right - v-tail left - throttle - wheel - flaps right - flaps left - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - - - - Anton Babushkin <anton@px4.io> + + Copter + Lorenz Meier <lorenz@px4.io> Quadrotor + motor 1 motor 2 @@ -234,8 +177,9 @@ - - Anton Babushkin <anton@px4.io>, Simon Wilks <simon@px4.io> + + Copter + Lorenz Meier <lorenz@px4.io> Quadrotor Wide motor 1 motor 2 @@ -248,8 +192,9 @@ feed-through of RC AUX3 channel feed-through of RC FLAPS channel - - Anton Babushkin <anton@px4.io> + + Copter + Lorenz Meier <lorenz@px4.io> Quadrotor Wide motor 1 motor 2 @@ -260,8 +205,9 @@ feed-through of RC AUX3 channel feed-through of RC FLAPS channel - - Thomas Gubler <thomas@px4.io> + + Copter + Lorenz Meier <lorenz@px4.io> Quadrotor Wide motor 1 motor 2 @@ -274,8 +220,9 @@ feed-through of RC AUX3 channel feed-through of RC FLAPS channel - - Simon Wilks <simon@px4.io> + + Copter + Simon Wilks <simon@uaventure.com> Quadrotor Wide motor 1 motor 2 @@ -290,8 +237,9 @@ - - Mark Whitehorn <kd0aij@gmail.com> + + Copter + Lorenz Meier <lorenz@px4.io> Quadrotor asymmetric motor1 (front right: CCW) motor2 (back left: CCW) @@ -303,14 +251,17 @@ + Copter Lorenz Meier <lorenz@px4.io> Quadrotor x + Copter Leon Mueller <thedevleon> Quadrotor x + Copter Lorenz Meier <lorenz@px4.io> Quadrotor x motor 1 @@ -325,6 +276,7 @@ feed-through of RC FLAPS channel + Copter Leon Mueller <thedevleon> Quadrotor x motor 1 @@ -339,64 +291,183 @@ Mount retract + Copter James Goppert <james.goppert@gmail.com> Quadrotor x - - Mark Whitehorn <kd0aij@gmail.com> + + Copter + Lorenz Meier <lorenz@px4.io> Quadrotor x + Copter Lorenz Meier <lorenz@px4.io> Quadrotor x + Copter Lorenz Meier <lorenz@px4.io> Quadrotor x - - Pavel Kirienko <pavel@px4.io> + + Copter + Pavel Kirienko <pavel.kirienko@gmail.com> Quadrotor x + Copter Blankered Quadrotor x - - Mark Whitehorn <kd0aij@gmail.com> + + Copter + Lorenz Meier <lorenz@px4.io> Quadrotor x + Copter James Goppert <james.goppert@gmail.com> Quadrotor x + Copter Anton Matosov <anton.matosov@gmail.com> Quadrotor x - - - Rover - pass-through of control group 0, channel 0 - pass-through of control group 0, channel 1 - pass-through of control group 0, channel 2 - pass-through of control group 0, channel 3 - pass-through of control group 0, channel 4 - pass-through of control group 0, channel 5 - pass-through of control group 0, channel 6 - pass-through of control group 0, channel 7 + + + Copter + Lorenz Meier <lorenz@px4.io> + Simulation - - Marco Zorzi - Rover - https://traxxas.com/products/models/electric/stampede-vxl-tsm - steering + + Copter + Lorenz Meier <lorenz@px4.io> + Simulation + + + + + Copter + Trent Lukaczyk <aerialhedgehog@gmail.com> + Tricopter Y+ + motor 1 + motor 2 + motor 3 + yaw servo + + + + + Copter + Trent Lukaczyk <aerialhedgehog@gmail.com> + Tricopter Y- + motor 1 + motor 2 + motor 3 + yaw servo + + + + + Plane + Simon Wilks <simon@uaventure.com> + Flying Wing + https://pixhawk.org/platforms/planes/bormatec_camflyer_q + left aileron + right aileron + throttle + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + + + Plane + Simon Wilks <simon@uaventure.com> + Flying Wing + https://pixhawk.org/platforms/planes/z-84_wing_wing + left aileron + right aileron + throttle + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + + + Plane + Julian Oes <julian@px4.io> + Flying Wing + https://pixhawk.org/platforms/planes/skywalker_x5 + left aileron + right aileron + throttle + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + + + Plane + Lorenz Meier <lorenz@px4.io> + Flying Wing + https://pixhawk.org/platforms/planes/z-84_wing_wing + left aileron + right aileron throttle + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + + + Plane + Simon Wilks <simon@uaventure.com> + Flying Wing + + + Plane + Simon Wilks <simon@uaventure.com> + Flying Wing + + + Plane + Simon Wilks <simon@uaventure.com> + Flying Wing + http://www.sparkletech.hk/ + left aileron + right aileron + throttle + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + + + Plane + Lorenz Meier <lorenz@px4.io> + Flying Wing + + + + + Plane + Andreas Antener <andreas@uaventure.com> + Plane A-Tail + aileron right + aileron left + v-tail right + v-tail left + throttle + wheel + flaps right + flaps left + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel - + + Plane Lorenz Meier <lorenz@px4.io> Simulation aileron @@ -404,17 +475,10 @@ rudder throttle - - Anton Babushkin <anton@px4.io> - Simulation - - - Anton Babushkin <anton@px4.io> - Simulation - + Plane Lorenz Meier <lorenz@px4.io> Standard Plane aileron @@ -423,6 +487,7 @@ throttle + Plane Lorenz Meier <lorenz@px4.io> Standard Plane aileron @@ -435,6 +500,7 @@ feed-through of RC AUX3 channel + Plane Lorenz Meier <lorenz@px4.io> Standard Plane aileron @@ -447,6 +513,7 @@ feed-through of RC AUX3 channel + Plane Lorenz Meier <lorenz@px4.io> Standard Plane aileron @@ -457,6 +524,7 @@ feed-through of RC AUX3 channel + Plane Lorenz Meier <lorenz@px4.io> Standard Plane aileron @@ -469,6 +537,7 @@ feed-through of RC AUX3 channel + Plane Andreas Antener <andreas@uaventure.com> Standard Plane aileron @@ -483,8 +552,40 @@ feed-through of RC AUX3 channel + + + Rover + Rover + pass-through of control group 0, channel 0 + pass-through of control group 0, channel 1 + pass-through of control group 0, channel 2 + pass-through of control group 0, channel 3 + pass-through of control group 0, channel 4 + pass-through of control group 0, channel 5 + pass-through of control group 0, channel 6 + pass-through of control group 0, channel 7 + + + Rover + Marco Zorzi + Rover + https://traxxas.com/products/models/electric/stampede-vxl-tsm + steering + throttle + + + + + Tool + Julian Oes <julian@oes.ch> +This startup can be used on Pixhawk/Pixfalcon/Pixracer for the +passthrough of RC input and PWM output. + custom + + + VTOL Simon Wilks <simon@uaventure.com> Standard VTOL motor 1 @@ -498,6 +599,7 @@ Throttle + VTOL Simon Wilks <simon@uaventure.com> Standard VTOL motor 1 @@ -509,18 +611,22 @@ Motor + VTOL Sander Smeets <sander@droneslab.com> Standard VTOL + VTOL Sander Smeets <sander@droneslab.com> Standard VTOL + VTOL Andreas Antener <andreas@uaventure.com> Standard VTOL + VTOL Sander Smeets <sander@droneslab.com> Standard VTOL motor 1 @@ -532,28 +638,9 @@ Motor - - - Trent Lukaczyk <aerialhedgehog@gmail.com> - Tricopter Y+ - motor 1 - motor 2 - motor 3 - yaw servo - - - - - Trent Lukaczyk <aerialhedgehog@gmail.com> - Tricopter Y- - motor 1 - motor 2 - motor 3 - yaw servo - - + VTOL Roman Bapst <roman@px4.io> VTOL Duo Tailsitter motor right @@ -564,10 +651,12 @@ + VTOL Roman Bapst <roman@px4.io> VTOL Quad Tailsitter + VTOL Roman Bapst <roman@px4.io> VTOL Quad Tailsitter motor 1 @@ -582,6 +671,7 @@ + VTOL Roman Bapst <roman@uaventure.com> VTOL Tiltrotor Front right motor bottom @@ -596,10 +686,12 @@ Gear + VTOL Samay Siga <samay_s@icloud.com> VTOL Tiltrotor + VTOL Andreas Antener <andreas@uaventure.com> VTOL Tiltrotor Motor right @@ -612,12 +704,4 @@ Elevon left - - - Julian Oes <julian@oes.ch> -This startup can be used on Pixhawk/Pixfalcon/Pixracer for the -passthrough of RC input and PWM output. - custom - - diff --git a/src/AutoPilotPlugins/PX4/PX4TuningComponentCopter.qml b/src/AutoPilotPlugins/PX4/PX4TuningComponentCopter.qml index ef2c32ce3f48f31ad4b315b35c47f6943421c644..56980007f6e5eae06a24e833232feb33d96f9687 100644 --- a/src/AutoPilotPlugins/PX4/PX4TuningComponentCopter.qml +++ b/src/AutoPilotPlugins/PX4/PX4TuningComponentCopter.qml @@ -60,24 +60,6 @@ SetupPage { max: 0.25 step: 0.01 } - - ListElement { - title: qsTr("Altitude control sensitivity") - description: qsTr("Slide to the left to make altitude control smoother and less twitchy. Slide to the right to make altitude control more accurate and more aggressive.") - param: "MPC_Z_FF" - min: 0 - max: 1.0 - step: 0.1 - } - - ListElement { - title: qsTr("Position control sensitivity") - description: qsTr("Slide to the left to make flight in position control mode smoother and less twitchy. Slide to the right to make position control more accurate and more aggressive.") - param: "MPC_XY_FF" - min: 0 - max: 1.0 - step: 0.1 - } } } } // Component diff --git a/src/AutoPilotPlugins/PX4/PX4TuningComponentVTOL.qml b/src/AutoPilotPlugins/PX4/PX4TuningComponentVTOL.qml index 8523a91617c95d4647de883726046a103ef72281..3feb7ca67e7c0c25474fb51ccc0a3244b15d1ea4 100644 --- a/src/AutoPilotPlugins/PX4/PX4TuningComponentVTOL.qml +++ b/src/AutoPilotPlugins/PX4/PX4TuningComponentVTOL.qml @@ -44,23 +44,6 @@ SetupPage { step: 0.01 } - ListElement { - title: qsTr("Hover Altitude control sensitivity") - description: qsTr("Slide to the left to make altitude control during hover smoother and less twitchy. Slide to the right to make altitude control more accurate and more aggressive.") - param: "MPC_Z_FF" - min: 0 - max: 1.0 - step: 0.1 - } - - ListElement { - title: qsTr("Hover Position control sensitivity") - description: qsTr("Slide to the left to make flight during hover in position control mode smoother and less twitchy. Slide to the right to make position control more accurate and more aggressive.") - param: "MPC_XY_FF" - min: 0 - max: 1.0 - step: 0.1 - } ListElement { title: qsTr("Plane Roll sensitivity") description: qsTr("Slide to the left to make roll control faster and more accurate. Slide to the right if roll oscillates or is too twitchy.") diff --git a/src/FirmwarePlugin/CameraMetaData.cc b/src/FirmwarePlugin/CameraMetaData.cc index 0f75c6e218454a382624c72ac83b7e8265227811..de6fa8845addaff20d739ecaced97724b70a0007 100644 --- a/src/FirmwarePlugin/CameraMetaData.cc +++ b/src/FirmwarePlugin/CameraMetaData.cc @@ -17,16 +17,18 @@ CameraMetaData::CameraMetaData(const QString& name, double focalLength, bool landscape, bool fixedOrientation, + double minTriggerInterval, QObject* parent) - : QObject(parent) - , _name(name) - , _sensorWidth(sensorWidth) - , _sensorHeight(sensorHeight) - , _imageWidth(imageWidth) - , _imageHeight(imageHeight) - , _focalLength(focalLength) - , _landscape(landscape) - , _fixedOrientation(fixedOrientation) + : QObject (parent) + , _name (name) + , _sensorWidth (sensorWidth) + , _sensorHeight (sensorHeight) + , _imageWidth (imageWidth) + , _imageHeight (imageHeight) + , _focalLength (focalLength) + , _landscape (landscape) + , _fixedOrientation (fixedOrientation) + , _minTriggerInterval (minTriggerInterval) { } diff --git a/src/FirmwarePlugin/CameraMetaData.h b/src/FirmwarePlugin/CameraMetaData.h index 1302ae453befa696ffde8fba644b56a2c7b3d809..50ab89495933c4d311bde0479804f8a99a83f097 100644 --- a/src/FirmwarePlugin/CameraMetaData.h +++ b/src/FirmwarePlugin/CameraMetaData.h @@ -26,6 +26,7 @@ public: double focalLength, bool landscape, bool fixedOrientation, + double minTriggerInterval, QObject* parent = NULL); Q_PROPERTY(QString name MEMBER _name CONSTANT) ///< Camera name @@ -36,6 +37,7 @@ public: Q_PROPERTY(double focalLength MEMBER _focalLength CONSTANT) ///< Focal length in millimeters Q_PROPERTY(bool landscape MEMBER _landscape CONSTANT) ///< true: camera is in landscape orientation Q_PROPERTY(bool fixedOrientation MEMBER _fixedOrientation CONSTANT) ///< true: camera is in fixed orientation + Q_PROPERTY(double minTriggerInterval MEMBER _minTriggerInterval CONSTANT) ///< Minimum time in seconds between each photo taken, 0 for not specified private: QString _name; @@ -46,6 +48,7 @@ private: double _focalLength; bool _landscape; bool _fixedOrientation; + double _minTriggerInterval; }; #endif diff --git a/src/FirmwarePlugin/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc index 683c863c5131d5b77cf4eb8f48c8f8ae17ed2d52..1b87d16475b0992a98f2c38609134fc174570428 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.cc +++ b/src/FirmwarePlugin/FirmwarePlugin.cc @@ -354,6 +354,7 @@ const QVariantList& FirmwarePlugin::cameraList(const Vehicle* vehicle) 16, true, false, + 0, this); _cameraList.append(QVariant::fromValue(metaData)); @@ -365,6 +366,7 @@ const QVariantList& FirmwarePlugin::cameraList(const Vehicle* vehicle) 5.2, true, false, + 0, this); _cameraList.append(QVariant::fromValue(metaData)); @@ -376,6 +378,7 @@ const QVariantList& FirmwarePlugin::cameraList(const Vehicle* vehicle) 10.2, true, false, + 0, this); _cameraList.append(QVariant::fromValue(metaData)); @@ -387,6 +390,7 @@ const QVariantList& FirmwarePlugin::cameraList(const Vehicle* vehicle) 4.5, true, false, + 0, this); metaData = new CameraMetaData(tr("Canon EOS-M 22mm"), @@ -397,6 +401,7 @@ const QVariantList& FirmwarePlugin::cameraList(const Vehicle* vehicle) 22, true, false, + 0, this); _cameraList.append(QVariant::fromValue(metaData)); @@ -408,6 +413,7 @@ const QVariantList& FirmwarePlugin::cameraList(const Vehicle* vehicle) 16, true, false, + 0, this); _cameraList.append(QVariant::fromValue(metaData)); @@ -419,6 +425,7 @@ const QVariantList& FirmwarePlugin::cameraList(const Vehicle* vehicle) 10.4, true, false, + 0, this); _cameraList.append(QVariant::fromValue(metaData)); } @@ -478,7 +485,7 @@ bool FirmwarePlugin::_setFlightModeAndValidate(Vehicle* vehicle, const QString& vehicle->setFlightMode(flightMode); // Wait for vehicle to return flight mode - for (int i=0; i<30; i++) { + for (int i=0; i<13; i++) { if (vehicle->flightMode() == flightMode) { flightModeChanged = true; break; diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index 0453c587d210733e6d12de3682300223ab9a60e7..a8f8816c0ea6d928a97bfe9b5167f6b9e93f72fc 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -76,7 +76,8 @@ PX4FirmwarePlugin::PX4FirmwarePlugin(void) { PX4_CUSTOM_MAIN_MODE_RATTITUDE, 0, true, true, true }, { PX4_CUSTOM_MAIN_MODE_ALTCTL, 0, true, true, true }, { PX4_CUSTOM_MAIN_MODE_POSCTL, 0, true, true, true }, - { PX4_CUSTOM_MAIN_MODE_SIMPLE, 0, true, false, true }, + // simple can't be set by the user right now + { PX4_CUSTOM_MAIN_MODE_SIMPLE, 0, false, false, true }, { PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_LOITER, true, true, true }, { PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_MISSION, true, true, true }, { PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_RTL, true, true, true }, @@ -460,12 +461,15 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu void PX4FirmwarePlugin::startMission(Vehicle* vehicle) { - if (!_armVehicleAndValidate(vehicle)) { - qgcApp()->showMessage(tr("Unable to start mission: Vehicle failed to arm.")); - return; - } - _setFlightModeAndValidate(vehicle, missionFlightMode()); + if (_setFlightModeAndValidate(vehicle, missionFlightMode())) { + if (!_armVehicleAndValidate(vehicle)) { + qgcApp()->showMessage(tr("Unable to start mission: Vehicle rejected arming.")); + return; + } + } else { + qgcApp()->showMessage(tr("Unable to start mission: Vehicle not ready.")); + } } void PX4FirmwarePlugin::setGuidedMode(Vehicle* vehicle, bool guidedMode) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 753da16bcfe6cb3524a12355b9df0bcc094ec733..216a7bd601c340160cad4e36e5c24c9f0d8a127e 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -1234,6 +1234,14 @@ This parameter is used when the magnetometer fusion method is set automatically 2 modules/ekf2 + + Range finder range dependant noise scaler + Specifies the increase in range finder noise with range. + 0.0 + 0.2 + m/m + modules/ekf2 + Gate size for range finder fusion 1.0 @@ -1522,6 +1530,29 @@ Smaller values make the saved mag bias learn slower from flight to flight. Large 2 modules/ekf2 + + Range sensor aid + If this parameter is enabled then the estimator will make use of the range finder measurements to estimate it's height even if range sensor is not the primary height source. It will only do so if conditions for range measurement fusion are met. + modules/ekf2 + + Range aid enabled + Range aid disabled + + + + Maximum horizontal velocity allowed for range aid mode + If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements to estimate it's height. This only applies when range aid mode is activated (EKF2_RNG_AID = enabled). + 0.1 + 2 + modules/ekf2 + + + Maximum absolute altitude (height above ground level) allowed for range aid mode + If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements to estimate it's height. This only applies when range aid mode is activated (EKF2_RNG_AID = enabled). + 1.0 + 10.0 + modules/ekf2 + @@ -2638,6 +2669,21 @@ but also ignore less noise Disable + + u-blox GPS dynamic platform model + u-blox receivers support different dynamic platform models to adjust the navigation engine to the expected application environment. + 0 + 9 + true + drivers/gps + + airborne with <4g acceleration + stationary + automotive + airborne with <2g acceleration + airborne with <1g acceleration + + @@ -3983,14 +4029,6 @@ if required for the gimbal (only in AUX output mode) m/s modules/mc_pos_control - - Vertical velocity feed forward - Feed forward weight for altitude control in stabilized modes (ALTCTRL, POSCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot. - 0.0 - 1.0 - 2 - modules/mc_pos_control - Proportional gain for horizontal position error 0.0 @@ -4059,14 +4097,6 @@ if required for the gimbal (only in AUX output mode) 1 modules/mc_pos_control - - Horizontal velocity feed forward - Feed forward weight for position control in position control mode (POSCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot. - 0.0 - 1.0 - 2 - modules/mc_pos_control - Maximum tilt angle in air Limits maximum tilt in AUTO and POSCTRL modes during flight. @@ -7291,7 +7321,8 @@ This is used for gathering replay logs for the ekf2 module modules/sensors - Select primary magnetometer + Select primary magnetometer. +DEPRECATED, only used on V1 hardware 0 2 modules/sensors diff --git a/src/FirmwarePlugin/PX4/px4_custom_mode.h b/src/FirmwarePlugin/PX4/px4_custom_mode.h index 6569ce6e0b092f6fb98b1804b77d9e98759ee4fc..2c0087e8f165189f89ec4d35015d7b45697fb38d 100644 --- a/src/FirmwarePlugin/PX4/px4_custom_mode.h +++ b/src/FirmwarePlugin/PX4/px4_custom_mode.h @@ -34,7 +34,7 @@ /** * @file px4_custom_mode.h * PX4 custom flight modes - * + * Copied from PX4 2017-07-08 - https://github.com/PX4/Firmware/blob/master/src/modules/commander/px4_custom_mode.h#L45 */ #ifndef PX4_CUSTOM_MODE_H_ @@ -50,8 +50,8 @@ enum PX4_CUSTOM_MAIN_MODE { PX4_CUSTOM_MAIN_MODE_ACRO, PX4_CUSTOM_MAIN_MODE_OFFBOARD, PX4_CUSTOM_MAIN_MODE_STABILIZED, - PX4_CUSTOM_MAIN_MODE_RATTITUDE, - PX4_CUSTOM_MAIN_MODE_SIMPLE + PX4_CUSTOM_MAIN_MODE_RATTITUDE, + PX4_CUSTOM_MAIN_MODE_SIMPLE /* unused, but reserved for future use */ }; enum PX4_CUSTOM_SUB_MODE_AUTO { diff --git a/src/FlightDisplay/FlightDisplayView.qml b/src/FlightDisplay/FlightDisplayView.qml index ae6dcb71c9758aa169644947f40cef71080a0c48..587f8052c45e3572da7564d0a4280824382034dc 100644 --- a/src/FlightDisplay/FlightDisplayView.qml +++ b/src/FlightDisplay/FlightDisplayView.qml @@ -542,6 +542,7 @@ QGCView { id: guidedActionsController missionController: _missionController confirmDialog: guidedActionConfirm + actionList: guidedActionList altitudeSlider: _altitudeSlider z: _flightVideoPipControl.z + 1 diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml index 3e38ee151f56202779f93afea5c40ea0819ec0dd..c8c844f667b486f72db9117e5e964f783986ec47 100644 --- a/src/FlightDisplay/FlightDisplayViewMap.qml +++ b/src/FlightDisplay/FlightDisplayViewMap.qml @@ -240,8 +240,9 @@ FlightMap { anchorPoint.y: sourceItem.anchorPointY sourceItem: MissionItemIndexLabel { - checked: true - label: qsTr("G", "Goto here waypoint") // second string is translator's hint. + checked: true + index: -1 + label: qsTr("Goto here", "Goto here waypoint") } } @@ -260,7 +261,7 @@ FlightMap { anchors.fill: parent onClicked: { - if (guidedActionsController.showGotoLocation) { + if (guidedActionsController.showGotoLocation && !guidedActionsController.guidedUIVisible) { _gotoHereCoordinate = flightMap.toCoordinate(Qt.point(mouse.x, mouse.y), false /* clipToViewPort */) guidedActionsController.confirmAction(guidedActionsController.actionGoto, _gotoHereCoordinate) } diff --git a/src/FlightDisplay/GuidedActionConfirm.qml b/src/FlightDisplay/GuidedActionConfirm.qml index 562298a6d95d933a111b5b5f480bac4978f924c0..48c159fa2e9cf0804683f9a2d7b7a77e176f6ece 100644 --- a/src/FlightDisplay/GuidedActionConfirm.qml +++ b/src/FlightDisplay/GuidedActionConfirm.qml @@ -16,7 +16,7 @@ import QGroundControl.Controls 1.0 import QGroundControl.Palette 1.0 /// Guided actions confirmation dialog -Rectangle { +NoMouseThroughRectangle { id: _root border.color: qgcPal.alertBorder border.width: 1 diff --git a/src/FlightDisplay/GuidedActionList.qml b/src/FlightDisplay/GuidedActionList.qml index 6ff749c8faf0dcfc085a33a865204ac7c9d35ffb..4c002c3ce1137a02353932f17ae89dd20bd53948 100644 --- a/src/FlightDisplay/GuidedActionList.qml +++ b/src/FlightDisplay/GuidedActionList.qml @@ -17,7 +17,7 @@ import QGroundControl.Controls 1.0 import QGroundControl.Palette 1.0 /// Dialog showing list of available guided actions -Rectangle { +NoMouseThroughRectangle { id: _root width: actionColumn.width + (_margins * 4) height: actionColumn.height + (_margins * 4) diff --git a/src/FlightDisplay/GuidedActionsController.qml b/src/FlightDisplay/GuidedActionsController.qml index 5d959145a945fce961bbe79a69aa329569ed4628..ed5624c4012271a24e604e01707721116192e55e 100644 --- a/src/FlightDisplay/GuidedActionsController.qml +++ b/src/FlightDisplay/GuidedActionsController.qml @@ -29,6 +29,7 @@ Item { property var missionController property var confirmDialog + property var actionList property var altitudeSlider readonly property string emergencyStopTitle: qsTr("Emergency Stop") @@ -89,13 +90,15 @@ Item { property bool showLand: _activeVehicle && _activeVehicle.guidedModeSupported && _vehicleArmed && !_activeVehicle.fixedWing && !_vehicleInLandMode property bool showStartMission: _activeVehicle && _missionAvailable && !_missionActive && !_vehicleFlying property bool showContinueMission: _activeVehicle && _missionAvailable && !_missionActive && _vehicleFlying && (_currentMissionIndex < missionController.visualItems.count - 1) - property bool showResumeMission: _activeVehicle && !_vehicleFlying && _missionAvailable && _resumeMissionIndex > 0 && (_resumeMissionIndex < missionController.visualItems.count - 2) + property bool showResumeMission: _activeVehicle && !_vehicleArmed && _vehicleWasFlying && _missionAvailable && _resumeMissionIndex > 0 && (_resumeMissionIndex < missionController.visualItems.count - 2) property bool showPause: _activeVehicle && _vehicleArmed && _activeVehicle.pauseVehicleSupported && _vehicleFlying && !_vehiclePaused property bool showChangeAlt: (_activeVehicle && _vehicleFlying) && _activeVehicle.guidedModeSupported && _vehicleArmed && !_missionActive property bool showOrbit: !_hideOrbit && _activeVehicle && _vehicleFlying && _activeVehicle.orbitModeSupported && _vehicleArmed && !_missionActive property bool showLandAbort: _activeVehicle && _vehicleFlying && _activeVehicle.fixedWing && _vehicleLanding property bool showGotoLocation: _activeVehicle && _activeVehicle.guidedMode && _vehicleFlying + property bool guidedUIVisible: guidedActionConfirm.visible || guidedActionList.visible + property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property string _flightMode: _activeVehicle ? _activeVehicle.flightMode : "" property bool _missionAvailable: missionController.containsItems @@ -111,6 +114,7 @@ Item { property int _resumeMissionIndex: missionController.resumeMissionIndex property bool _hideEmergenyStop: !QGroundControl.corePlugin.options.guidedBarShowEmergencyStop property bool _hideOrbit: !QGroundControl.corePlugin.options.guidedBarShowOrbit + property bool _vehicleWasFlying: false // This is a temporary hack to debug a problem with RTL and Pause being disabled at the wrong time @@ -125,7 +129,6 @@ Item { Component.onCompleted: _outputState() on_ActiveVehicleChanged: _outputState() on_VehicleArmedChanged: _outputState() - on_VehicleFlyingChanged: _outputState() on_VehicleInRTLModeChanged: _outputState() on_VehiclePausedChanged: _outputState() on__FlightModeChanged: _outputState() @@ -134,6 +137,15 @@ Item { // End of hack + on_VehicleFlyingChanged: { + _outputState() + if (!_vehicleFlying) { + // We use _vehicleWasFLying to help trigger Resume Mission only if the vehicle actually flew and came back down. + // Otherwise it may trigger during the Start Mission sequence due to signal ordering or armed and resume mission index. + _vehicleWasFlying = true + } + } + property var _actionData on_CurrentMissionIndexChanged: console.log("_currentMissionIndex", _currentMissionIndex) @@ -262,6 +274,7 @@ Item { missionController.resumeMission(missionController.resumeMissionIndex) break case actionResumeMissionReady: + _vehicleWasFlying = false _activeVehicle.startMission() break case actionStartMission: diff --git a/src/MissionManager/CameraSection.cc b/src/MissionManager/CameraSection.cc index f7889c507da7786f36671aab0279de2df1567caf..ebcccbc9d7bb78bf02993589cab2014bee0d0a57 100644 --- a/src/MissionManager/CameraSection.cc +++ b/src/MissionManager/CameraSection.cc @@ -165,7 +165,9 @@ void CameraSection::appendSectionItems(QList& items, QObject* miss MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_FRAME_MISSION, _cameraPhotoIntervalDistanceFact.rawValue().toDouble(), // Trigger distance - 0, 0, 0, 0, 0, 0, // param 2-7 not used + 0, // No shutter integartion + 1, // Trigger immediately + 0, 0, 0, 0, // param 4-7 not used true, // autoContinue false, // isCurrentItem missionItemParent); @@ -313,13 +315,31 @@ bool CameraSection::_scanStopTakingPhotos(QmlObjectListModel* visualItems, int s return false; } -bool CameraSection::_scanTriggerDistance(QmlObjectListModel* visualItems, int scanIndex) +bool CameraSection::_scanTriggerStartDistance(QmlObjectListModel* visualItems, int scanIndex) { SimpleMissionItem* item = visualItems->value(scanIndex); if (item) { MissionItem& missionItem = item->missionItem(); if ((MAV_CMD)item->command() == MAV_CMD_DO_SET_CAM_TRIGG_DIST) { - if (missionItem.param1() >= 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) { + if (missionItem.param1() > 0 && missionItem.param2() == 0 && missionItem.param3() == 1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) { + cameraAction()->setRawValue(TakePhotoIntervalDistance); + cameraPhotoIntervalDistance()->setRawValue(missionItem.param1()); + visualItems->removeAt(scanIndex)->deleteLater(); + return true; + } + } + } + + return false; +} + +bool CameraSection::_scanTriggerStopDistance(QmlObjectListModel* visualItems, int scanIndex) +{ + SimpleMissionItem* item = visualItems->value(scanIndex); + if (item) { + MissionItem& missionItem = item->missionItem(); + if ((MAV_CMD)item->command() == MAV_CMD_DO_SET_CAM_TRIGG_DIST) { + if (missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) { cameraAction()->setRawValue(TakePhotoIntervalDistance); cameraPhotoIntervalDistance()->setRawValue(missionItem.param1()); visualItems->removeAt(scanIndex)->deleteLater(); @@ -415,7 +435,11 @@ bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int scanInde foundCameraAction = true; continue; } - if (!foundCameraAction && _scanTriggerDistance(visualItems, scanIndex)) { + if (!foundCameraAction && _scanTriggerStartDistance(visualItems, scanIndex)) { + foundCameraAction = true; + continue; + } + if (!foundCameraAction && _scanTriggerStopDistance(visualItems, scanIndex)) { foundCameraAction = true; continue; } diff --git a/src/MissionManager/CameraSection.h b/src/MissionManager/CameraSection.h index 5094ae82648f58079c6ec0819473060fdd471833..e0538473a98a5b9b7e15114d80fb1b3e67950f53 100644 --- a/src/MissionManager/CameraSection.h +++ b/src/MissionManager/CameraSection.h @@ -94,7 +94,8 @@ private: bool _scanTakePhoto(QmlObjectListModel* visualItems, int scanIndex); bool _scanTakePhotosIntervalTime(QmlObjectListModel* visualItems, int scanIndex); bool _scanStopTakingPhotos(QmlObjectListModel* visualItems, int scanIndex); - bool _scanTriggerDistance(QmlObjectListModel* visualItems, int scanIndex); + bool _scanTriggerStartDistance(QmlObjectListModel* visualItems, int scanIndex); + bool _scanTriggerStopDistance(QmlObjectListModel* visualItems, int scanIndex); bool _scanTakeVideo(QmlObjectListModel* visualItems, int scanIndex); bool _scanStopTakingVideo(QmlObjectListModel* visualItems, int scanIndex); bool _scanSetCameraMode(QmlObjectListModel* visualItems, int scanIndex); diff --git a/src/MissionManager/CameraSectionTest.cc b/src/MissionManager/CameraSectionTest.cc index e30a9a6bb0e4154aa012f28ea464b725123041bb..4e87df7b464d876b5f9ec12bdfec32fb8550369a 100644 --- a/src/MissionManager/CameraSectionTest.cc +++ b/src/MissionManager/CameraSectionTest.cc @@ -50,7 +50,14 @@ void CameraSectionTest::init(void) MissionItem(0, MAV_CMD_IMAGE_START_CAPTURE, MAV_FRAME_MISSION, 0, 48, 0, NAN, NAN, NAN, NAN, true, false), this); _validDistanceItem = new SimpleMissionItem(_offlineVehicle, - MissionItem(0, MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_FRAME_MISSION, 72, 0, 0, 0, 0, 0, 0, true, false), + MissionItem(0, + MAV_CMD_DO_SET_CAM_TRIGG_DIST, + MAV_FRAME_MISSION, + 72, // trigger distance + 0, // not shutter integration + 1, // trigger immediately + 0, 0, 0, 0, + true, false), this); _validStartVideoItem = new SimpleMissionItem(_offlineVehicle, MissionItem(0, // sequence number @@ -729,15 +736,15 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void) _commonScanTest(_cameraSection); /* - MAV_CMD_DO_SET_CAM_TRIGG_DIST Mission command to set CAM_TRIGG_DIST for this flight - Mission Param #1 Camera trigger distance (meters) - Mission Param #2 Empty - Mission Param #3 Empty + MAV_CMD_DO_SET_CAM_TRIGG_DIST Mission command to set camera trigger distance for this flight. The camera is trigerred each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera. + Mission Param #1 Camera trigger distance (meters). 0 to stop triggering. + Mission Param #2 Camera shutter integration time (milliseconds). -1 or 0 to ignore + Mission Param #3 Trigger camera once immediately. (0 = no trigger, 1 = trigger) Mission Param #4 Empty Mission Param #5 Empty Mission Param #6 Empty Mission Param #7 Empty -*/ + */ SimpleMissionItem* newValidDistanceItem = new SimpleMissionItem(_offlineVehicle, this); newValidDistanceItem->missionItem() = _validDistanceItem->missionItem(); @@ -769,7 +776,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void) visualItems.clear(); invalidSimpleItem.missionItem() = _validDistanceItem->missionItem(); - invalidSimpleItem.missionItem().setParam3(1); // must be 0 + invalidSimpleItem.missionItem().setParam3(0); // must be 1 visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); QCOMPARE(visualItems.count(), 1); diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index b00d9699e3dd74d91f3b727674e7ac9ef525b686..11c40c2c59dc0e1ff50c3ac41b31571c2ab4edb8 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -158,7 +158,10 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque qWarning() << "First item is not settings item"; return; } - settingsItem->setCoordinate(newMissionItems[0]->coordinate()); + MissionItem* fakeHomeItem = newMissionItems[0]; + if (fakeHomeItem->coordinate().latitude() != 0 || fakeHomeItem->coordinate().longitude() != 0) { + settingsItem->setCoordinate(fakeHomeItem->coordinate()); + } i = 1; } diff --git a/src/MissionManager/PlanMasterController.cc b/src/MissionManager/PlanMasterController.cc index b3c676d2f1f535257df7387ef0ec972afa651245..797bd59cc6d4e16926f1b976fd0e0a387f2ea02f 100644 --- a/src/MissionManager/PlanMasterController.cc +++ b/src/MissionManager/PlanMasterController.cc @@ -89,6 +89,16 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle) qCDebug(PlanMasterControllerLog) << "_activeVehicleChanged" << activeVehicle; + if (_managerVehicle) { + // Disconnect old vehicle + disconnect(_managerVehicle->missionManager(), &MissionManager::newMissionItemsAvailable, this, &PlanMasterController::_loadMissionComplete); + disconnect(_managerVehicle->geoFenceManager(), &GeoFenceManager::loadComplete, this, &PlanMasterController::_loadGeoFenceComplete); + disconnect(_managerVehicle->rallyPointManager(), &RallyPointManager::loadComplete, this, &PlanMasterController::_loadRallyPointsComplete); + disconnect(_managerVehicle->missionManager(), &MissionManager::sendComplete, this, &PlanMasterController::_sendMissionComplete); + disconnect(_managerVehicle->geoFenceManager(), &GeoFenceManager::sendComplete, this, &PlanMasterController::_sendGeoFenceComplete); + disconnect(_managerVehicle->rallyPointManager(), &RallyPointManager::sendComplete, this, &PlanMasterController::_sendRallyPointsComplete); + } + bool newOffline = false; if (activeVehicle == NULL) { // Since there is no longer an active vehicle we use the offline controller vehicle as the manager vehicle @@ -353,6 +363,7 @@ void PlanMasterController::removeAllFromVehicle(void) _missionController.removeAllFromVehicle(); _geoFenceController.removeAllFromVehicle(); _rallyPointController.removeAllFromVehicle(); + setDirty(false); } else { qWarning() << "PlanMasterController::removeAllFromVehicle called while offline"; } @@ -410,6 +421,14 @@ void PlanMasterController::sendPlanToVehicle(Vehicle* vehicle, const QString& fi void PlanMasterController::_showPlanFromManagerVehicle(void) { + if (!_managerVehicle->initialPlanRequestComplete() && + !_missionController.syncInProgress() && + !_geoFenceController.syncInProgress() && + !_rallyPointController.syncInProgress()) { + // Something went wrong with initial load. All controllers are idle, so just force it off + _managerVehicle->forceInitialPlanRequestComplete(); + } + // The crazy if structure is to handle the load propogating by itself through the system if (!_missionController.showPlanFromManagerVehicle()) { if (!_geoFenceController.showPlanFromManagerVehicle()) { diff --git a/src/MissionManager/QGCMapPolygon.cc b/src/MissionManager/QGCMapPolygon.cc index d8471b0ea0d41c56c5fb117dfac2e5a3941c9609..a7c5ca9ae01194587dfaa5dce7628b84c5e1c6c3 100644 --- a/src/MissionManager/QGCMapPolygon.cc +++ b/src/MissionManager/QGCMapPolygon.cc @@ -253,6 +253,8 @@ void QGCMapPolygon::removeVertex(int vertexIndex) _polygonPath.removeAt(vertexIndex); emit pathChanged(); + + _updateCenter(); } void QGCMapPolygon::_polygonModelCountChanged(int count) @@ -265,9 +267,13 @@ void QGCMapPolygon::_updateCenter(void) if (!_ignoreCenterUpdates) { QGeoCoordinate center; - if (_polygonPath.count() > 2) { - QPointF centerPoint = _toPolygonF().boundingRect().center(); - center = _coordFromPointF(centerPoint); + if (_polygonPath.count() > 2) { + QPointF centroid(0, 0); + QPolygonF polygonF = _toPolygonF(); + for (int i=0; iremoveVertex(1); - QVERIFY(_multiSpyPolygon->checkOnlySignalByMask(pathChangedMask | polygonDirtyChangedMask | polygonCountChangedMask | centerChangedMask)); + // There is some double signalling on centerChanged which is not yet fixed, hence checkOnlySignals + QVERIFY(_multiSpyPolygon->checkOnlySignalsByMask(pathChangedMask | polygonDirtyChangedMask | polygonCountChangedMask | centerChangedMask)); QVERIFY(_multiSpyModel->checkOnlySignalByMask(modelDirtyChangedMask | modelCountChangedMask)); QCOMPARE(_mapPolygon->count(), 3); polyList = _mapPolygon->path(); diff --git a/src/MissionManager/QGCMapPolygonVisuals.qml b/src/MissionManager/QGCMapPolygonVisuals.qml index f311753a744c48308c55186646fda4ac004dcc8b..5d630a7a27cdc33ec6fe2f5a5ef3f3c7b711e6d4 100644 --- a/src/MissionManager/QGCMapPolygonVisuals.qml +++ b/src/MissionManager/QGCMapPolygonVisuals.qml @@ -35,8 +35,9 @@ Item { property var _splitHandlesComponent property var _centerDragHandleComponent - property real _zorderDragHandle: QGroundControl.zOrderMapItems + 2 - property real _zorderSplitHandle: QGroundControl.zOrderMapItems + 1 + property real _zorderDragHandle: QGroundControl.zOrderMapItems + 3 // Highest to prevent splitting when items overlap + property real _zorderSplitHandle: QGroundControl.zOrderMapItems + 2 + property real _zorderCenterHandle: QGroundControl.zOrderMapItems + 1 // Lowest such that drag or split takes precedence function addVisuals() { _polygonComponent = polygonComponent.createObject(mapControl) @@ -281,7 +282,7 @@ Item { id: centerDragAreaComponent MissionItemIndicatorDrag { - z: _zorderDragHandle + z: _zorderCenterHandle onItemCoordinateChanged: mapPolygon.center = itemCoordinate onDragStart: mapPolygon.centerDrag = true onDragStop: mapPolygon.centerDrag = false diff --git a/src/MissionManager/Survey.SettingsGroup.json b/src/MissionManager/Survey.SettingsGroup.json index 5d4ef9c2d875756b96772ef6b9d27e67035655aa..b11c5e461e63c143b203be930d5a708cb262659c 100644 --- a/src/MissionManager/Survey.SettingsGroup.json +++ b/src/MissionManager/Survey.SettingsGroup.json @@ -64,7 +64,7 @@ "min": 0, "max": 85, "units": "%", - "defaultValue": 10 + "defaultValue": 70 }, { "name": "SideOverlap", @@ -74,7 +74,7 @@ "min": 0, "max": 85, "units": "%", - "defaultValue": 10 + "defaultValue": 70 }, { "name": "CameraSensorWidth", @@ -132,7 +132,7 @@ "name": "CameraTriggerInTurnaround", "shortDescription": "Camera continues taking images in turnarounds.", "type": "bool", - "defaultValue": false + "defaultValue": true }, { "name": "HoverAndCapture", diff --git a/src/MissionManager/SurveyMissionItem.cc b/src/MissionManager/SurveyMissionItem.cc index 9a519f7b4280dd754967c52e250caf1cb353dc33..e9d63b832bcbccf7167b2455aca4a80e3b9cb50f 100644 --- a/src/MissionManager/SurveyMissionItem.cc +++ b/src/MissionManager/SurveyMissionItem.cc @@ -39,6 +39,7 @@ const char* SurveyMissionItem::_jsonCameraSensorHeightKey = "sensorHeigh const char* SurveyMissionItem::_jsonCameraResolutionWidthKey = "resolutionWidth"; const char* SurveyMissionItem::_jsonCameraResolutionHeightKey = "resolutionHeight"; const char* SurveyMissionItem::_jsonCameraFocalLengthKey = "focalLength"; +const char* SurveyMissionItem::_jsonCameraMinTriggerIntervalKey = "minTriggerInterval"; const char* SurveyMissionItem::_jsonCameraObjectKey = "camera"; const char* SurveyMissionItem::_jsonCameraNameKey = "name"; const char* SurveyMissionItem::_jsonManualGridKey = "manualGrid"; @@ -79,6 +80,7 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent) , _missionCommandCount(0) , _refly90Degrees(false) , _additionalFlightDelaySeconds(0) + , _cameraMinTriggerInterval(0) , _ignoreRecalc(false) , _surveyDistance(0.0) , _cameraShots(0) @@ -240,6 +242,7 @@ void SurveyMissionItem::save(QJsonArray& missionItems) cameraObject[_jsonCameraResolutionWidthKey] = _cameraResolutionWidthFact.rawValue().toDouble(); cameraObject[_jsonCameraResolutionHeightKey] = _cameraResolutionHeightFact.rawValue().toDouble(); cameraObject[_jsonCameraFocalLengthKey] = _cameraFocalLengthFact.rawValue().toDouble(); + cameraObject[_jsonCameraMinTriggerIntervalKey] = _cameraMinTriggerInterval; cameraObject[_jsonGroundResolutionKey] = _groundResolutionFact.rawValue().toDouble(); cameraObject[_jsonFrontalOverlapKey] = _frontalOverlapFact.rawValue().toInt(); cameraObject[_jsonSideOverlapKey] = _sideOverlapFact.rawValue().toInt(); @@ -373,6 +376,7 @@ bool SurveyMissionItem::load(const QJsonObject& complexObject, int sequenceNumbe { _jsonCameraFocalLengthKey, QJsonValue::Double, true }, { _jsonCameraNameKey, QJsonValue::String, true }, { _jsonCameraOrientationLandscapeKey, QJsonValue::Bool, true }, + { _jsonCameraMinTriggerIntervalKey, QJsonValue::Double, false }, }; if (!JsonHelper::validateKeys(cameraObject, cameraKeyInfoList, errorString)) { return false; @@ -389,6 +393,7 @@ bool SurveyMissionItem::load(const QJsonObject& complexObject, int sequenceNumbe _cameraResolutionWidthFact.setRawValue (cameraObject[_jsonCameraResolutionWidthKey].toDouble()); _cameraResolutionHeightFact.setRawValue (cameraObject[_jsonCameraResolutionHeightKey].toDouble()); _cameraFocalLengthFact.setRawValue (cameraObject[_jsonCameraFocalLengthKey].toDouble()); + _cameraMinTriggerInterval = cameraObject[_jsonCameraMinTriggerIntervalKey].toDouble(0); } // Polygon shape @@ -967,8 +972,8 @@ int SurveyMissionItem::_gridGenerator(const QList& polygonPoints, QLis qCDebug(SurveyMissionItemLog) << "Generate left to right"; float x = largeBoundRect.topLeft().x() - (gridSpacing / 2); while (x < largeBoundRect.bottomRight().x()) { - float yTop = largeBoundRect.topLeft().y() - 100.0; - float yBottom = largeBoundRect.bottomRight().y() + 100.0; + float yTop = largeBoundRect.topLeft().y() - 10000.0; + float yBottom = largeBoundRect.bottomRight().y() + 10000.0; lineList += QLineF(_rotatePoint(QPointF(x, yTop), boundingCenter, gridAngle), _rotatePoint(QPointF(x, yBottom), boundingCenter, gridAngle)); qCDebug(SurveyMissionItemLog) << "line(" << lineList.last().x1() << ", " << lineList.last().y1() << ")-(" << lineList.last().x2() <<", " << lineList.last().y2() << ")"; @@ -980,8 +985,8 @@ int SurveyMissionItem::_gridGenerator(const QList& polygonPoints, QLis qCDebug(SurveyMissionItemLog) << "Generate right to left"; float x = largeBoundRect.topRight().x() + (gridSpacing / 2); while (x > largeBoundRect.bottomLeft().x()) { - float yTop = largeBoundRect.topRight().y() - 100.0; - float yBottom = largeBoundRect.bottomLeft().y() + 100.0; + float yTop = largeBoundRect.topRight().y() - 10000.0; + float yBottom = largeBoundRect.bottomLeft().y() + 10000.0; lineList += QLineF(_rotatePoint(QPointF(x, yTop), boundingCenter, gridAngle), _rotatePoint(QPointF(x, yBottom), boundingCenter, gridAngle)); qCDebug(SurveyMissionItemLog) << "line(" << lineList.last().x1() << ", " << lineList.last().y1() << ")-(" << lineList.last().x2() <<", " << lineList.last().y2() << ")"; @@ -997,8 +1002,8 @@ int SurveyMissionItem::_gridGenerator(const QList& polygonPoints, QLis qCDebug(SurveyMissionItemLog) << "Generate top to bottom"; float y = largeBoundRect.bottomLeft().y() + (gridSpacing / 2); while (y > largeBoundRect.topRight().y()) { - float xLeft = largeBoundRect.bottomLeft().x() - 100.0; - float xRight = largeBoundRect.topRight().x() + 100.0; + float xLeft = largeBoundRect.bottomLeft().x() - 10000.0; + float xRight = largeBoundRect.topRight().x() + 10000.0; lineList += QLineF(_rotatePoint(QPointF(xLeft, y), boundingCenter, gridAngle), _rotatePoint(QPointF(xRight, y), boundingCenter, gridAngle)); qCDebug(SurveyMissionItemLog) << "y:xLeft:xRight" << y << xLeft << xRight << "line(" << lineList.last().x1() << ", " << lineList.last().y1() << ")-(" << lineList.last().x2() <<", " << lineList.last().y2() << ")"; @@ -1010,8 +1015,8 @@ int SurveyMissionItem::_gridGenerator(const QList& polygonPoints, QLis qCDebug(SurveyMissionItemLog) << "Generate bottom to top"; float y = largeBoundRect.topLeft().y() - (gridSpacing / 2); while (y < largeBoundRect.bottomRight().y()) { - float xLeft = largeBoundRect.topLeft().x() - 100.0; - float xRight = largeBoundRect.bottomRight().x() + 100.0; + float xLeft = largeBoundRect.topLeft().x() - 10000.0; + float xRight = largeBoundRect.bottomRight().x() + 10000.0; lineList += QLineF(_rotatePoint(QPointF(xLeft, y), boundingCenter, gridAngle), _rotatePoint(QPointF(xRight, y), boundingCenter, gridAngle)); qCDebug(SurveyMissionItemLog) << "y:xLeft:xRight" << y << xLeft << xRight << "line(" << lineList.last().x1() << ", " << lineList.last().y1() << ")-(" << lineList.last().x2() <<", " << lineList.last().y2() << ")"; @@ -1133,9 +1138,11 @@ int SurveyMissionItem::_appendWaypointToMission(QList& items, int MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_FRAME_MISSION, cameraTrigger == CameraTriggerOn ? _triggerDistance() : 0, - 0, 0, 0, 0, 0, 0, // param 2-7 unused - true, // autoContinue - false, // isCurrentItem + 0, // shutter integration (ignore) + cameraTrigger == CameraTriggerOn ? 1 : 0, // trigger immediately when starting + 0, 0, 0, 0, // param 4-7 unused + true, // autoContinue + false, // isCurrentItem missionItemParent); items.append(item); break; @@ -1191,21 +1198,14 @@ bool SurveyMissionItem::_nextTransectCoord(const QList& transect /// @return false: Generation failed bool SurveyMissionItem::_appendMissionItemsWorker(QList& items, QObject* missionItemParent, int& seqNum, bool hasRefly, bool buildRefly) { + bool firstWaypointTrigger = false; + qCDebug(SurveyMissionItemLog) << "hasTurnaround:triggerCamera:hoverAndCapture:imagesEverywhere:hasRefly:buildRefly" << _hasTurnaround() << _triggerCamera() << _hoverAndCaptureEnabled() << _imagesEverywhere() << hasRefly << buildRefly; QList>& transectSegments = buildRefly ? _reflyTransectSegments : _transectSegments; if (!buildRefly && _imagesEverywhere()) { - // We are taking images in turnaround, so we start command once at beginning - MissionItem* item = new MissionItem(seqNum++, - MAV_CMD_DO_SET_CAM_TRIGG_DIST, - MAV_FRAME_MISSION, - _triggerDistance(), - 0, 0, 0, 0, 0, 0, // param 2-7 unused - true, // autoContinue - false, // isCurrentItem - missionItemParent); - items.append(item); + firstWaypointTrigger = true; } for (int segmentIndex=0; segmentIndex& items, QO if (!_nextTransectCoord(segment, pointIndex++, coord)) { return false; } - seqNum = _appendWaypointToMission(items, seqNum, coord, CameraTriggerNone, missionItemParent); + seqNum = _appendWaypointToMission(items, seqNum, coord, firstWaypointTrigger ? CameraTriggerOn : CameraTriggerNone, missionItemParent); + firstWaypointTrigger = false; } // Add polygon entry point if (!_nextTransectCoord(segment, pointIndex++, coord)) { return false; } - cameraTrigger = _imagesEverywhere() || !_triggerCamera() ? CameraTriggerNone : (_hoverAndCaptureEnabled() ? CameraTriggerHoverAndCapture : CameraTriggerOn); + if (firstWaypointTrigger) { + cameraTrigger = CameraTriggerOn; + } else { + cameraTrigger = _imagesEverywhere() || !_triggerCamera() ? CameraTriggerNone : (_hoverAndCaptureEnabled() ? CameraTriggerHoverAndCapture : CameraTriggerOn); + } seqNum = _appendWaypointToMission(items, seqNum, coord, cameraTrigger, missionItemParent); + firstWaypointTrigger = false; // Add internal hover and capture points if (_hoverAndCaptureEnabled()) { diff --git a/src/MissionManager/SurveyMissionItem.h b/src/MissionManager/SurveyMissionItem.h index cdf4d6acb787b090d683582c44a3bd28474ee6db..c3a02e012780bbe807fdb76c5e3ef27686de916c 100644 --- a/src/MissionManager/SurveyMissionItem.h +++ b/src/MissionManager/SurveyMissionItem.h @@ -43,14 +43,15 @@ public: Q_PROPERTY(Fact* cameraResolutionWidth READ cameraResolutionWidth CONSTANT) Q_PROPERTY(Fact* cameraResolutionHeight READ cameraResolutionHeight CONSTANT) Q_PROPERTY(Fact* cameraFocalLength READ cameraFocalLength CONSTANT) - Q_PROPERTY(Fact* fixedValueIsAltitude READ fixedValueIsAltitude CONSTANT) Q_PROPERTY(Fact* cameraOrientationLandscape READ cameraOrientationLandscape CONSTANT) + Q_PROPERTY(Fact* fixedValueIsAltitude READ fixedValueIsAltitude CONSTANT) Q_PROPERTY(Fact* manualGrid READ manualGrid CONSTANT) Q_PROPERTY(Fact* camera READ camera CONSTANT) Q_PROPERTY(bool cameraOrientationFixed MEMBER _cameraOrientationFixed NOTIFY cameraOrientationFixedChanged) Q_PROPERTY(bool hoverAndCaptureAllowed READ hoverAndCaptureAllowed CONSTANT) Q_PROPERTY(bool refly90Degrees READ refly90Degrees WRITE setRefly90Degrees NOTIFY refly90DegreesChanged) + Q_PROPERTY(double cameraMinTriggerInterval MEMBER _cameraMinTriggerInterval NOTIFY cameraMinTriggerIntervalChanged) Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY timeBetweenShotsChanged) Q_PROPERTY(QVariantList gridPoints READ gridPoints NOTIFY gridPointsChanged) @@ -165,14 +166,15 @@ public: static const char* cameraName; signals: - void gridPointsChanged (void); - void cameraShotsChanged (int cameraShots); - void coveredAreaChanged (double coveredArea); - void cameraValueChanged (void); - void gridTypeChanged (QString gridType); - void timeBetweenShotsChanged (void); - void cameraOrientationFixedChanged (bool cameraOrientationFixed); - void refly90DegreesChanged (bool refly90Degrees); + void gridPointsChanged (void); + void cameraShotsChanged (int cameraShots); + void coveredAreaChanged (double coveredArea); + void cameraValueChanged (void); + void gridTypeChanged (QString gridType); + void timeBetweenShotsChanged (void); + void cameraOrientationFixedChanged (bool cameraOrientationFixed); + void refly90DegreesChanged (bool refly90Degrees); + void cameraMinTriggerIntervalChanged (double cameraMinTriggerInterval); private slots: void _setDirty(void); @@ -233,6 +235,7 @@ private: int _missionCommandCount; bool _refly90Degrees; double _additionalFlightDelaySeconds; + double _cameraMinTriggerInterval; bool _ignoreRecalc; double _surveyDistance; @@ -283,6 +286,7 @@ private: static const char* _jsonCameraResolutionWidthKey; static const char* _jsonCameraResolutionHeightKey; static const char* _jsonCameraFocalLengthKey; + static const char* _jsonCameraMinTriggerIntervalKey; static const char* _jsonManualGridKey; static const char* _jsonCameraObjectKey; static const char* _jsonCameraNameKey; diff --git a/src/PlanView/SurveyItemEditor.qml b/src/PlanView/SurveyItemEditor.qml index 53b6f3e1e1eae921e33556f439244332128ba027..d8409d3b5e8ab9f770a84ed2e96e712a8260e49c 100644 --- a/src/PlanView/SurveyItemEditor.qml +++ b/src/PlanView/SurveyItemEditor.qml @@ -57,7 +57,9 @@ Rectangle { gridTypeCombo.currentIndex = index if (index != 1) { // Specific camera is selected - missionItem.cameraOrientationFixed = _vehicleCameraList[index - _gridTypeCamera].fixedOrientation + var camera = _vehicleCameraList[index - _gridTypeCamera] + missionItem.cameraOrientationFixed = camera.fixedOrientation + missionItem.cameraMinTriggerInterval = camera.minTriggerInterval } } } @@ -181,6 +183,15 @@ Rectangle { anchors.right: parent.right spacing: _margin + QGCLabel { + anchors.left: parent.left + anchors.right: parent.right + text: qsTr("WARNING: Photo interval is below minimum interval (%1 secs) supported by camera.").arg(missionItem.cameraMinTriggerInterval.toFixed(1)) + wrapMode: Text.WordWrap + color: qgcPal.warningText + visible: missionItem.manualGrid.value !== true && missionItem.cameraShots > 0 && missionItem.cameraMinTriggerInterval !== 0 && missionItem.cameraMinTriggerInterval > missionItem.timeBetweenShots + } + SectionHeader { id: cameraHeader text: qsTr("Camera") @@ -207,6 +218,7 @@ Rectangle { missionItem.manualGrid.value = false missionItem.camera.value = gridTypeCombo.textAt(index) missionItem.cameraOrientationFixed = false + missionItem.cameraMinTriggerInterval = 0 } else { missionItem.manualGrid.value = false missionItem.camera.value = gridTypeCombo.textAt(index) @@ -219,6 +231,7 @@ Rectangle { missionItem.cameraFocalLength.rawValue = _vehicleCameraList[listIndex].focalLength missionItem.cameraOrientationLandscape.rawValue = _vehicleCameraList[listIndex].landscape ? 1 : 0 missionItem.cameraOrientationFixed = _vehicleCameraList[listIndex].fixedOrientation + missionItem.cameraMinTriggerInterval = _vehicleCameraList[listIndex].minTriggerInterval _noCameraValueRecalc = false recalcFromCameraValues() } @@ -252,12 +265,6 @@ Rectangle { enabled: cameraTriggerDistanceCheckBox.checked } } - - FactCheckBox { - text: qsTr("Hover and capture image") - fact: missionItem.hoverAndCapture - visible: missionItem.hoverAndCaptureAllowed - } } // Camera based grid ui @@ -387,6 +394,23 @@ Rectangle { } } + FactCheckBox { + text: qsTr("Hover and capture image") + fact: missionItem.hoverAndCapture + visible: missionItem.hoverAndCaptureAllowed + onClicked: { + if (checked) { + missionItem.cameraTriggerInTurnaround.rawValue = false + } + } + } + + FactCheckBox { + text: qsTr("Take images in turnarounds") + fact: missionItem.cameraTriggerInTurnaround + enabled: !missionItem.hoverAndCapture.rawValue + } + SectionHeader { id: gridHeader text: qsTr("Grid") @@ -418,7 +442,8 @@ Rectangle { id: windRoseButton anchors.verticalCenter: angleText.verticalCenter iconSource: qgcPal.globalTheme === QGCPalette.Light ? "/res/wind-roseBlack.svg" : "/res/wind-rose.svg" - visible: _vehicle.fixedWing + // Wind Rose is temporarily turned off until bugs are fixed + visible: false//_vehicle.fixedWing onClicked: { var cords = windRoseButton.mapToItem(_root, 0, 0) @@ -519,7 +544,8 @@ Rectangle { anchors.verticalCenter: manualAngleText.verticalCenter Layout.columnSpan: 1 iconSource: qgcPal.globalTheme === QGCPalette.Light ? "/res/wind-roseBlack.svg" : "/res/wind-rose.svg" - visible: _vehicle.fixedWing + // Wind Rose is temporarily turned off until bugs are fixed + visible: false//_vehicle.fixedWing onClicked: { var cords = manualWindRoseButton.mapToItem(_root, 0, 0) diff --git a/src/QmlControls/MissionItemIndexLabel.qml b/src/QmlControls/MissionItemIndexLabel.qml index ee16f25ea61fc788c2357d12db9afcf6404a3dc5..2b226e4be58145799cdf1e15b9471016c6a60e0a 100644 --- a/src/QmlControls/MissionItemIndexLabel.qml +++ b/src/QmlControls/MissionItemIndexLabel.qml @@ -13,7 +13,7 @@ Canvas { signal clicked property string label ///< Label to show to the side of the index indicator - property int index: 0 ///< Index to show in the indicator, 0 will show label instead + property int index: 0 ///< Index to show in the indicator, 0 will show single char label instead, -1 first char of label in indicator full label to the side property bool checked: false property bool small: false property var color: checked ? "green" : qgcPal.mapButtonHighlight @@ -33,7 +33,7 @@ Canvas { property real _labelMargin: 2 property real _labelRadius: _indicatorRadius + _labelMargin property string _label: index === 0 ? "" : label - property string _index: index === 0 ? label : index + property string _index: index === 0 || index === -1 ? label.charAt(0) : index onColorChanged: requestPaint() onShowGimbalYawChanged: requestPaint() diff --git a/src/QmlControls/NoMouseThroughRectangle.qml b/src/QmlControls/NoMouseThroughRectangle.qml new file mode 100644 index 0000000000000000000000000000000000000000..295f6e3c6d32be13989425702da3643b0638a117 --- /dev/null +++ b/src/QmlControls/NoMouseThroughRectangle.qml @@ -0,0 +1,14 @@ +import QtQuick 2.3 +import QtQuick.Controls 1.2 + +/// This control is used to create a Rectangle control which does not allow mouse events to bleed through to the control +/// which is beneath it. +Rectangle { + MouseArea { + anchors.fill: parent + preventStealing: true + onWheel: { wheel.accepted = true; } + onPressed: { mouse.accepted = true; } + onReleased: { mouse.accepted = true; } + } +} diff --git a/src/QmlControls/QGroundControl.Controls.qmldir b/src/QmlControls/QGroundControl.Controls.qmldir index 64be6551d20ea30d1b50b80ddf39a67d11eeb37f..b16c14e3478ed1842e80666dac1510735b5eda31 100644 --- a/src/QmlControls/QGroundControl.Controls.qmldir +++ b/src/QmlControls/QGroundControl.Controls.qmldir @@ -25,6 +25,7 @@ MissionItemMapVisual 1.0 MissionItemMapVisual.qml MissionItemStatus 1.0 MissionItemStatus.qml ModeSwitchDisplay 1.0 ModeSwitchDisplay.qml MultiRotorMotorDisplay 1.0 MultiRotorMotorDisplay.qml +NoMouseThroughRectangle 1.0 NoMouseThroughRectangle.qml ParameterEditor 1.0 ParameterEditor.qml ParameterEditorDialog 1.0 ParameterEditorDialog.qml PlanToolBar 1.0 PlanToolBar.qml diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index e0f3e48701d0dfdd783f4a01ca16ea5e400178be..b7e7998598c3632e900ac9c2128702a38bbe87b1 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -688,8 +688,8 @@ void Vehicle::_handleGlobalPositionInt(mavlink_message_t& message) mavlink_global_position_int_t globalPositionInt; mavlink_msg_global_position_int_decode(&message, &globalPositionInt); - // ArduPilot sends bogus GLOBAL_POSITION_INT messages with lat/lat/alt 0/0/0 even when it has not gps signal - if (globalPositionInt.lat == 0 && globalPositionInt.lon == 0 && globalPositionInt.alt == 0) { + // ArduPilot sends bogus GLOBAL_POSITION_INT messages with lat/lat 0/0 even when it has not gps signal + if (globalPositionInt.lat == 0 && globalPositionInt.lon == 0) { return; } @@ -723,6 +723,7 @@ void Vehicle::_setCapabilities(uint64_t capabilityBits) _supportsMissionItemInt = true; } _vehicleCapabilitiesKnown = true; + emit capabilitiesKnownChanged(true); qCDebug(VehicleLog) << QString("Vehicle %1 MISSION_ITEM_INT").arg(_supportsMissionItemInt ? QStringLiteral("supports") : QStringLiteral("does not support")); } @@ -795,7 +796,7 @@ void Vehicle::_handleHilActuatorControls(mavlink_message_t &message) void Vehicle::_handleCommandAck(mavlink_message_t& message) { - bool showError = true; + bool showError = false; mavlink_command_ack_t ack; mavlink_msg_command_ack_decode(&message, &ack); diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 692a3d5d8bb6f1924ce4c5f26b813e452cb9a8ad..15e0e4cfb5d58b8f6276f0a7d38d0a81125f0914 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -677,6 +677,7 @@ public: QGCCameraManager* dynamicCameras () { return _cameras; } + bool capabilitiesKnown(void) const { return _vehicleCapabilitiesKnown; } bool supportsMissionItemInt(void) const { return _supportsMissionItemInt; } /// @true: When flying a mission the vehicle is always facing towards the next waypoint @@ -686,6 +687,8 @@ public: /// @return: true: initial request is complete, false: initial request is still in progress; bool initialPlanRequestComplete(void) const { return _initialPlanRequestComplete; } + void forceInitialPlanRequestComplete(void) { _initialPlanRequestComplete = true; } + void _setFlying(bool flying); void _setLanding(bool landing); void _setHomePosition(QGeoCoordinate& homeCoord); @@ -717,6 +720,7 @@ signals: void firmwareTypeChanged(void); void vehicleTypeChanged(void); void dynamicCamerasChanged(); + void capabilitiesKnownChanged(bool capabilitiesKnown); void messagesReceivedChanged (); void messagesSentChanged (); diff --git a/src/VehicleSetup/FirmwareUpgradeController.cc b/src/VehicleSetup/FirmwareUpgradeController.cc index 69f8050e56b454a13bc957c8b82192fa4a5b06b4..a86b87a21974b82bb28dfde96697a78e3bdc936f 100644 --- a/src/VehicleSetup/FirmwareUpgradeController.cc +++ b/src/VehicleSetup/FirmwareUpgradeController.cc @@ -211,12 +211,7 @@ void FirmwareUpgradeController::_initFirmwareHash() { AutoPilotStackPX4, StableFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/stable/px4fmu-v4_default.px4"}, { AutoPilotStackPX4, BetaFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/beta/px4fmu-v4_default.px4"}, { AutoPilotStackPX4, DeveloperFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/master/px4fmu-v4_default.px4"}, - { AutoPilotStackAPM, StableFirmware, QuadFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-quad/ArduCopter-v4.px4"}, - { AutoPilotStackAPM, StableFirmware, X8Firmware, "http://firmware.ardupilot.org/Copter/stable/PX4-octa-quad/ArduCopter-v4.px4"}, - { AutoPilotStackAPM, StableFirmware, HexaFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-hexa/ArduCopter-v4.px4"}, - { AutoPilotStackAPM, StableFirmware, OctoFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-octa/ArduCopter-v4.px4"}, - { AutoPilotStackAPM, StableFirmware, YFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-tri/ArduCopter-v4.px4"}, - { AutoPilotStackAPM, StableFirmware, Y6Firmware, "http://firmware.ardupilot.org/Copter/stable/PX4-y6/ArduCopter-v4.px4"}, + { AutoPilotStackAPM, StableFirmware, CopterFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4/ArduCopter-v4.px4"}, { AutoPilotStackAPM, StableFirmware, HeliFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-heli/ArduCopter-v4.px4"}, { AutoPilotStackAPM, StableFirmware, PlaneFirmware, "http://firmware.ardupilot.org/Plane/stable/PX4/ArduPlane-v4.px4"}, { AutoPilotStackAPM, StableFirmware, RoverFirmware, "http://firmware.ardupilot.org/Rover/stable/PX4/APMrover2-v4.px4"}, @@ -232,18 +227,12 @@ void FirmwareUpgradeController::_initFirmwareHash() }; //////////////////////////////////// PX4FMUV3 firmwares ////////////////////////////////////////////////// - // Note: ArduPilot stable does not yet support V3 firmwares, so fall back to V2 FirmwareToUrlElement_t rgPX4FMV3FirmwareArray[] = { { AutoPilotStackPX4, StableFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/stable/px4fmu-v3_default.px4"}, { AutoPilotStackPX4, BetaFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/beta/px4fmu-v3_default.px4"}, { AutoPilotStackPX4, DeveloperFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/master/px4fmu-v3_default.px4"}, - { AutoPilotStackAPM, StableFirmware, QuadFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-quad/ArduCopter-v2.px4"}, - { AutoPilotStackAPM, StableFirmware, X8Firmware, "http://firmware.ardupilot.org/Copter/stable/PX4-octa-quad/ArduCopter-v2.px4"}, - { AutoPilotStackAPM, StableFirmware, HexaFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-hexa/ArduCopter-v2.px4"}, - { AutoPilotStackAPM, StableFirmware, OctoFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-octa/ArduCopter-v2.px4"}, - { AutoPilotStackAPM, StableFirmware, YFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-tri/ArduCopter-v2.px4"}, - { AutoPilotStackAPM, StableFirmware, Y6Firmware, "http://firmware.ardupilot.org/Copter/stable/PX4-y6/ArduCopter-v2.px4"}, - { AutoPilotStackAPM, StableFirmware, HeliFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-heli/ArduCopter-v2.px4"}, + { AutoPilotStackAPM, StableFirmware, CopterFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4/ArduCopter-v3.px4"}, + { AutoPilotStackAPM, StableFirmware, HeliFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-heli/ArduCopter-v3.px4"}, { AutoPilotStackAPM, StableFirmware, PlaneFirmware, "http://firmware.ardupilot.org/Plane/stable/PX4/ArduPlane-v2.px4"}, { AutoPilotStackAPM, StableFirmware, RoverFirmware, "http://firmware.ardupilot.org/Rover/stable/PX4/APMrover2-v2.px4"}, { AutoPilotStackAPM, StableFirmware, SubFirmware, "http://firmware.ardupilot.org/Sub/stable/PX4/ArduSub-v2.px4"}, @@ -265,12 +254,7 @@ void FirmwareUpgradeController::_initFirmwareHash() { AutoPilotStackPX4, StableFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/stable/px4fmu-v2_default.px4"}, { AutoPilotStackPX4, BetaFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/beta/px4fmu-v2_default.px4"}, { AutoPilotStackPX4, DeveloperFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/master/px4fmu-v2_default.px4"}, - { AutoPilotStackAPM, StableFirmware, QuadFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-quad/ArduCopter-v2.px4"}, - { AutoPilotStackAPM, StableFirmware, X8Firmware, "http://firmware.ardupilot.org/Copter/stable/PX4-octa-quad/ArduCopter-v2.px4"}, - { AutoPilotStackAPM, StableFirmware, HexaFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-hexa/ArduCopter-v2.px4"}, - { AutoPilotStackAPM, StableFirmware, OctoFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-octa/ArduCopter-v2.px4"}, - { AutoPilotStackAPM, StableFirmware, YFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-tri/ArduCopter-v2.px4"}, - { AutoPilotStackAPM, StableFirmware, Y6Firmware, "http://firmware.ardupilot.org/Copter/stable/PX4-y6/ArduCopter-v2.px4"}, + { AutoPilotStackAPM, StableFirmware, CopterFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4/ArduCopter-v2.px4"}, { AutoPilotStackAPM, StableFirmware, HeliFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-heli/ArduCopter-v2.px4"}, { AutoPilotStackAPM, StableFirmware, PlaneFirmware, "http://firmware.ardupilot.org/Plane/stable/PX4/ArduPlane-v2.px4"}, { AutoPilotStackAPM, StableFirmware, RoverFirmware, "http://firmware.ardupilot.org/Rover/stable/PX4/APMrover2-v2.px4"}, @@ -322,12 +306,7 @@ void FirmwareUpgradeController::_initFirmwareHash() { AutoPilotStackPX4, StableFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/stable/px4fmu-v1_default.px4"}, { AutoPilotStackPX4, BetaFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/beta/px4fmu-v1_default.px4"}, { AutoPilotStackPX4, DeveloperFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/master/px4fmu-v1_default.px4"}, - { AutoPilotStackAPM, StableFirmware, QuadFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-quad/ArduCopter-v1.px4"}, - { AutoPilotStackAPM, StableFirmware, X8Firmware, "http://firmware.ardupilot.org/Copter/stable/PX4-octa-quad/ArduCopter-v1.px4"}, - { AutoPilotStackAPM, StableFirmware, HexaFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-hexa/ArduCopter-v1.px4"}, - { AutoPilotStackAPM, StableFirmware, OctoFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-octa/ArduCopter-v1.px4"}, - { AutoPilotStackAPM, StableFirmware, YFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-tri/ArduCopter-v1.px4"}, - { AutoPilotStackAPM, StableFirmware, Y6Firmware, "http://firmware.ardupilot.org/Copter/stable/PX4-y6/ArduCopter-v1.px4"}, + { AutoPilotStackAPM, StableFirmware, CopterFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4/ArduCopter-v1.px4"}, { AutoPilotStackAPM, StableFirmware, HeliFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-heli/ArduCopter-v1.px4"}, { AutoPilotStackAPM, StableFirmware, PlaneFirmware, "http://firmware.ardupilot.org/Plane/stable/PX4/ArduPlane-v1.px4"}, { AutoPilotStackAPM, StableFirmware, RoverFirmware, "http://firmware.ardupilot.org/Rover/stable/PX4/APMrover2-v1.px4"}, @@ -530,9 +509,9 @@ void FirmwareUpgradeController::_getFirmwareFile(FirmwareIdentifier firmwareId) if (firmwareId.firmwareType == CustomFirmware) { _firmwareFilename = QGCQFileDialog::getOpenFileName(NULL, // Parent to main window - "Select Firmware File", // Dialog Caption - QStandardPaths::writableLocation(QStandardPaths::DocumentsLocation), // Initial directory - "Firmware Files (*.px4 *.bin *.ihx)"); // File filter + "Select Firmware File", // Dialog Caption + QStandardPaths::writableLocation(QStandardPaths::DocumentsLocation), // Initial directory + "Firmware Files (*.px4 *.bin *.ihx)"); // File filter } else { if (prgFirmware->contains(firmwareId)) { _firmwareFilename = prgFirmware->value(firmwareId); @@ -774,51 +753,57 @@ void FirmwareUpgradeController::setSelectedFirmwareType(FirmwareType_t firmwareT QStringList FirmwareUpgradeController::apmAvailableVersions(void) { - QStringList list; + QStringList list; + QList vehicleTypes; + + // This allows up to force the order of the combo box display + vehicleTypes << CopterFirmware << HeliFirmware << PlaneFirmware << RoverFirmware << SubFirmware; _apmVehicleTypeFromCurrentVersionList.clear(); - foreach (FirmwareVehicleType_t vehicleType, _apmVersionMap[_selectedFirmwareType].keys()) { - QString version; - - switch (vehicleType) { - case QuadFirmware: - version = "Quad - "; - break; - case X8Firmware: - version = "X8 - "; - break; - case HexaFirmware: - version = "Hexa - "; - break; - case OctoFirmware: - version = "Octo - "; - break; - case YFirmware: - version = "Y - "; - break; - case Y6Firmware: - version = "Y6 - "; - break; - case HeliFirmware: - version = "Heli - "; - break; - case CopterFirmware: - version = "MultiRotor - "; - break; - case SubFirmware: - version = "Sub - "; - break; - case PlaneFirmware: - case RoverFirmware: - case DefaultVehicleFirmware: - break; + foreach (FirmwareVehicleType_t vehicleType, vehicleTypes) { + if (_apmVersionMap[_selectedFirmwareType].contains(vehicleType)) { + QString version; + + switch (vehicleType) { + case QuadFirmware: + version = "Quad - "; + break; + case X8Firmware: + version = "X8 - "; + break; + case HexaFirmware: + version = "Hexa - "; + break; + case OctoFirmware: + version = "Octo - "; + break; + case YFirmware: + version = "Y - "; + break; + case Y6Firmware: + version = "Y6 - "; + break; + case HeliFirmware: + version = "Heli - "; + break; + case CopterFirmware: + version = "MultiRotor - "; + break; + case SubFirmware: + version = "Sub - "; + break; + case PlaneFirmware: + case RoverFirmware: + case DefaultVehicleFirmware: + break; + } + + version += _apmVersionMap[_selectedFirmwareType][vehicleType]; + _apmVehicleTypeFromCurrentVersionList.append(vehicleType); + + list << version; } - - version += _apmVersionMap[_selectedFirmwareType][vehicleType]; - _apmVehicleTypeFromCurrentVersionList.append(vehicleType); - - list << version; } return list; diff --git a/src/api/QGCCorePlugin.cc b/src/api/QGCCorePlugin.cc index f40fe3d9267a48b764cbcd021d2e9165be2d483f..a427bacadf27ec3dcd24d52acfbed275fe6e55da 100644 --- a/src/api/QGCCorePlugin.cc +++ b/src/api/QGCCorePlugin.cc @@ -175,6 +175,13 @@ bool QGCCorePlugin::adjustSettingMetaData(FactMetaData& metaData) #else metaData.setRawDefaultValue(true); return true; +#endif +#if defined(__ios__) + } else if (metaData.name() == AppSettings::savePathName) { + QString appName = qgcApp()->applicationName(); + QDir rootDir = QDir(QStandardPaths::writableLocation(QStandardPaths::DocumentsLocation)); + metaData.setRawDefaultValue(rootDir.filePath(appName)); + return false; #endif } return true; // Show setting in ui diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 0ffbf4df14837c0bc4afebeac25cc927a21f622c..19c006ea3faed58641d5d03481f029bdd01f5eb5 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -108,10 +108,11 @@ void MainWindow::deleteInstance(void) /// by MainWindow::_create method. Hence no other code should have access to /// constructor. MainWindow::MainWindow() - : _lowPowerMode(false) - , _showStatusBar(false) - , _mainQmlWidgetHolder(NULL) - , _forceClose(false) + : _mavlinkDecoder (NULL) + , _lowPowerMode (false) + , _showStatusBar (false) + , _mainQmlWidgetHolder (NULL) + , _forceClose (false) { _instance = this; @@ -272,10 +273,13 @@ MainWindow::MainWindow() MainWindow::~MainWindow() { - // Enforce thread-safe shutdown of the mavlink decoder - mavlinkDecoder->finish(); - mavlinkDecoder->wait(1000); - mavlinkDecoder->deleteLater(); + if (_mavlinkDecoder) { + // Enforce thread-safe shutdown of the mavlink decoder + _mavlinkDecoder->finish(); + _mavlinkDecoder->wait(1000); + _mavlinkDecoder->deleteLater(); + _mavlinkDecoder = NULL; + } // This needs to happen before we get into the QWidget dtor // otherwise the QML engine reads freed data and tries to @@ -290,12 +294,18 @@ QString MainWindow::_getWindowGeometryKey() } #ifndef __mobile__ -void MainWindow::_buildCommonWidgets(void) +MAVLinkDecoder* MainWindow::_mavLinkDecoderInstance(void) { - // Add generic MAVLink decoder - mavlinkDecoder = new MAVLinkDecoder(qgcApp()->toolbox()->mavlinkProtocol()); - connect(mavlinkDecoder.data(), &MAVLinkDecoder::valueChanged, this, &MainWindow::valueChanged); + if (!_mavlinkDecoder) { + _mavlinkDecoder = new MAVLinkDecoder(qgcApp()->toolbox()->mavlinkProtocol()); + connect(_mavlinkDecoder, &MAVLinkDecoder::valueChanged, this, &MainWindow::valueChanged); + } + return _mavlinkDecoder; +} + +void MainWindow::_buildCommonWidgets(void) +{ // Log player // TODO: Make this optional with a preferences setting or under a "View" menu logPlayer = new QGCMAVLinkLogPlayer(statusBar()); @@ -363,7 +373,7 @@ bool MainWindow::_createInnerDockWidget(const QString& widgetName) widget = new HILDockWidget(widgetName, action, this); break; case ANALYZE: - widget = new Linecharts(widgetName, action, mavlinkDecoder, this); + widget = new Linecharts(widgetName, action, _mavLinkDecoderInstance(), this); break; } if(widget) { diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index aee454a76418a3acc6cd5e44bad96fea4ffd9ad1..5efc40ab718daa6dcd436883de8ae1883c73779f 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -127,7 +127,6 @@ protected: QSettings settings; - QPointer mavlinkDecoder; QGCMAVLinkLogPlayer* logPlayer; #ifdef QGC_MOUSE_ENABLED_WIN /** @brief 3d Mouse support (WIN only) */ @@ -181,7 +180,9 @@ private: void _showDockWidget(const QString &name, bool show); void _loadVisibleWidgetsSettings(void); void _storeVisibleWidgetsSettings(void); + MAVLinkDecoder* _mavLinkDecoderInstance(void); + MAVLinkDecoder* _mavlinkDecoder; bool _lowPowerMode; ///< If enabled, QGC reduces the update rates of all widgets bool _showStatusBar; QVBoxLayout* _centralLayout;