diff --git a/.travis.yml b/.travis.yml index a87e984ec72da807ed970d0b66ad1a61b21ee191..5030b4b913019611c898f13dd2ea380f6313a2b7 100644 --- a/.travis.yml +++ b/.travis.yml @@ -5,7 +5,8 @@ language: cpp env: global: - JOBS=4 - - QT_FATAL_WARNINGS=1 + # QT_FATAL_WARNINGS is turned off because Qt 5.11.3 throws a speech dispatcher not working warning when running unit tests + #- QT_FATAL_WARNINGS=1 - SHADOW_BUILD_DIR=/tmp/shadow_build_dir # ANDROID_STOREPASS - secure: RGovyUnMw3fp/bHZi058JvANT1rYmNqrsuSYew0cIgirO6YbMHr/rsjwCm1FTYpBl8s1zgr+u2b8ftYnfnCz2YT+Aip4NWrVYpVU0FEmfytGILrnUS0pjlt8m7fU9AKR1ElOSll7yw7e1kftynN39Q321etvwbLZcXon6zz0suE= @@ -14,12 +15,13 @@ matrix: fast_finish: true include: - os: linux - dist: trusty + dist: xenial env: SPEC=linux-g++-64 CONFIG=installer sudo: required - os: linux - dist: trusty + dist: xenial env: SPEC=linux-g++-64 CONFIG=debug + services: xvfb sudo: required - os: android language: android @@ -35,7 +37,7 @@ matrix: sudo: false # OSX builds pared back to installer only since travis sucks so bad we can't afford more than one' # - os: osx -# osx_image: xcode8 +# osx_image: xcode10.1 # env: SPEC=macx-clang CONFIG=debug # sudo: required @@ -48,8 +50,7 @@ android: addons: apt: packages: - - espeak - - libespeak-dev + - speech-dispatcher - libgstreamer-plugins-base1.0-dev - libgstreamer1.0-0:amd64 - libgstreamer1.0-dev @@ -73,11 +74,9 @@ before_install: install: # linux dependencies: qt - if [ "${SPEC}" = "linux-g++-64" ]; then - wget --quiet https://s3-us-west-2.amazonaws.com/qgroundcontrol/dependencies/Qt5.11.0-gcc_64-min.tar.bz2 && - tar jxf Qt5.11.0-gcc_64-min.tar.bz2 -C /tmp && - export PATH=/tmp/Qt5.11-gcc_64/5.11.0/gcc_64/bin:$PATH && - export DISPLAY=:99.0 && - sh -e /etc/init.d/xvfb start + wget --quiet https://s3-us-west-2.amazonaws.com/qgroundcontrol/dependencies/Qt5.11.3-gcc_64-min.tar.bz2 && + tar jxf Qt5.11.3-gcc_64-min.tar.bz2 -C /tmp && + export PATH=/tmp/Qt5.11-gcc_64/5.11.3/gcc_64/bin:$PATH ; fi @@ -164,8 +163,9 @@ script: # unit tests linux - if [[ "${SPEC}" = "linux-g++-64" && "${CONFIG}" = "debug" ]]; then - mkdir -p ~/.config/QtProject/ && cp ${TRAVIS_BUILD_DIR}/test/qtlogging.ini ~/.config/QtProject/ && - ./debug/qgroundcontrol-start.sh --unittest; + mkdir -p ~/.config/QtProject/ && + cp ${TRAVIS_BUILD_DIR}/test/qtlogging.ini ~/.config/QtProject/ && + ./debug/qgroundcontrol-start.sh --unittest; fi after_success: diff --git a/ChangeLog.md b/ChangeLog.md index d26fcf89766caa1803a412acf3c9554d43a1e919..f091c94c7475de889d22e014cde87be375655a1b 100644 --- a/ChangeLog.md +++ b/ChangeLog.md @@ -2,9 +2,18 @@ Note: This file only contains high level features or important fixes. -## 3.5 +## 3.6 -### 3.5.0 - Daily Build +### 3.6.0 - Daily Build + +* No changes yet + +### 3.5.0 - Stable +* Plan GeoFence: Fix loading of fence from intermediate 3.4 code +* Structure Scan: Fix loading of structure scan height +* ArduPilot: Fix location of planned home position when not connected to vehicle. Issue #6840. +* Fix loading of parameters from multiple components. Would report download complete too early, thus missing all default component params. +* Fix file delete in mobile file dialogs * Add support for specifying fixed RTK based station location in Settings/General. * Added Airmap integration to QGC * Added ESTIMATOR_STATUS values to new estimatorStatus Vehicle FactGroup. These are now available to display in instrument panel. @@ -13,23 +22,15 @@ Note: This file only contains high level features or important fixes. * Make Heading to Home available for display from instrument panel. * Edit Position dialog available on polygon vertices. * Fixed Wing Landing Pattern: Add stop photo/video support. Defaults to on such that doing an RTL will stop camera. -* Survey Planning: add mode that supports concave polygons * Support loading polygons from SHP files * Bumped settings version (now 8). This will cause all settings to be reset to defaults. * Orbit visuals support changing rotation direction * Added support for the Taisync 2.4GHz ViUlinx digital HD wireless link. +* Added UDP Port option for NMEA GPS Device. ## 3.4 -### 3.4.5 - Not yet released -* Plan GeoFence: Fix loading of fence from intermediate 3.4 code -* Orbit: Turn off for PX4 since still not supported -* Structure Scan: Fix loading of structure scan height -* ArduPilot: Fix location of planned home position when not connected to vehicle. Issue #6840. -* Fix loading of parameters from multiple components. Would report download complete too early, thus missing all default component params. -* Fix file delete in mobile file dialogs - -### 3.4.4 - Stable +### 3.4.4 * Stable desktop versions now inform user at boot if newer version is available. * Multi-Vehicle Start Mission and Pause now work correctly. Issue #6864. diff --git a/Jenkinsfile b/Jenkinsfile index 859166b7866ec51bdf51d9d490770f5c66593b72..3582d500094dade7a8873d1e869c65891b7edc5b 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -13,7 +13,7 @@ pipeline { } agent { docker { - image 'mavlink/qgc-build-android:2018-06-08' + image 'mavlink/qgc-build-android:2019-02-03' args '-v ${CCACHE_DIR}:${CCACHE_DIR}:rw' } } @@ -42,7 +42,7 @@ pipeline { } agent { docker { - image 'mavlink/qgc-build-linux:2018-06-08' + image 'mavlink/qgc-build-linux:2019-02-03' args '-v ${CCACHE_DIR}:${CCACHE_DIR}:rw' } } @@ -72,7 +72,7 @@ pipeline { } agent { docker { - image 'mavlink/qgc-build-linux:2018-06-07' + image 'mavlink/qgc-build-linux:2019-02-03' args '-v ${CCACHE_DIR}:${CCACHE_DIR}:rw' } } @@ -101,7 +101,7 @@ pipeline { } agent { docker { - image 'mavlink/qgc-build-linux:2018-06-08' + image 'mavlink/qgc-build-linux:2019-02-03' args '-v ${CCACHE_DIR}:${CCACHE_DIR}:rw' } } @@ -134,7 +134,7 @@ pipeline { } agent { docker { - image 'mavlink/qgc-build-linux:2018-06-07' + image 'mavlink/qgc-build-linux:2019-02-03' args '-v ${CCACHE_DIR}:${CCACHE_DIR}:rw' } } diff --git a/QGCExternalLibs.pri b/QGCExternalLibs.pri index 0c9fc138827a5d1a33f70fa9b519c68ace018bd3..dc0afe4b499cf576fdd42301701b3f4cebe320dd 100644 --- a/QGCExternalLibs.pri +++ b/QGCExternalLibs.pri @@ -170,20 +170,22 @@ contains (DEFINES, DISABLE_AIRMAP) { message("Skipping support for AirMap (manual override from user_config.pri)") } else { AIRMAPD_PATH = $$PWD/libs/airmapd - MacBuild { - exists($${AIRMAPD_PATH}/macOS/Qt.5.11.0) { - message("Including support for AirMap for macOS") - LIBS += -L$${AIRMAPD_PATH}/macOS/Qt.5.11.0 -lairmap-qt - DEFINES += QGC_AIRMAP_ENABLED - } - } else:LinuxBuild { - exists($${AIRMAPD_PATH}/linux/Qt.5.11.0) { - message("Including support for AirMap for Linux") - LIBS += -L$${AIRMAPD_PATH}/linux/Qt.5.11.0 -lairmap-qt - DEFINES += QGC_AIRMAP_ENABLED + contains(QT_VERSION, ˆ5\\.11\..*) { + MacBuild { + exists($${AIRMAPD_PATH}/macOS/Qt.5.11.0) { + message("Including support for AirMap for macOS") + LIBS += -L$${AIRMAPD_PATH}/macOS/Qt.5.11.0 -lairmap-qt + DEFINES += QGC_AIRMAP_ENABLED + } + } else:LinuxBuild { + exists($${AIRMAPD_PATH}/linux/Qt.5.11.0) { + message("Including support for AirMap for Linux") + LIBS += -L$${AIRMAPD_PATH}/linux/Qt.5.11.0 -lairmap-qt + DEFINES += QGC_AIRMAP_ENABLED + } + } else { + message("Skipping support for Airmap (unsupported platform)") } - } else { - message("Skipping support for Airmap (unsupported platform)") } contains (DEFINES, QGC_AIRMAP_ENABLED) { INCLUDEPATH += \ diff --git a/android/AndroidManifest.xml b/android/AndroidManifest.xml index b696cd71962d92d408efa6679437f250db30a301..49581f61050e4c8ec5fc6946ab805384f7cbcd9c 100644 --- a/android/AndroidManifest.xml +++ b/android/AndroidManifest.xml @@ -72,6 +72,8 @@ + + diff --git a/android/src/com/hoho/android/usbserial/driver/CdcAcmSerialDriver.java b/android/src/com/hoho/android/usbserial/driver/CdcAcmSerialDriver.java index 80893367180a38269f91f4e20d1af6fa8d11c207..880df09b06697ddfd274274f1b4a549ecdcae668 100644 --- a/android/src/com/hoho/android/usbserial/driver/CdcAcmSerialDriver.java +++ b/android/src/com/hoho/android/usbserial/driver/CdcAcmSerialDriver.java @@ -41,8 +41,8 @@ public class CdcAcmSerialDriver extends CommonUsbSerialDriver { private static final int SET_CONTROL_LINE_STATE = 0x22; private static final int SEND_BREAK = 0x23; - public CdcAcmSerialDriver(UsbDevice device, UsbDeviceConnection connection) { - super(device, connection); + public CdcAcmSerialDriver(UsbDevice device) { + super(device); } @Override @@ -304,6 +304,18 @@ public class CdcAcmSerialDriver extends CommonUsbSerialDriver { UsbId.DEVICE_SPARKY2, UsbId.DEVICE_OPLINK, }); + supportedDevices.put(Integer.valueOf(UsbId.VENDOR_ARDUPILOT_CHIBIOS1), + new int[] { + UsbId.DEVICE_ARDUPILOT_CHIBIOS, + }); + supportedDevices.put(Integer.valueOf(UsbId.VENDOR_ARDUPILOT_CHIBIOS2), + new int[] { + UsbId.DEVICE_ARDUPILOT_CHIBIOS, + }); + supportedDevices.put(Integer.valueOf(UsbId.VENDOR_DRAGONLINK), + new int[] { + UsbId.DEVICE_DRAGONLINK, + }); return supportedDevices; } diff --git a/android/src/com/hoho/android/usbserial/driver/CommonUsbSerialDriver.java b/android/src/com/hoho/android/usbserial/driver/CommonUsbSerialDriver.java index 734933a22238264aa766ab39ec4365b3b4b0f50e..0facbdf1c783cad0d2cf5ca3890dd1335313e85c 100644 --- a/android/src/com/hoho/android/usbserial/driver/CommonUsbSerialDriver.java +++ b/android/src/com/hoho/android/usbserial/driver/CommonUsbSerialDriver.java @@ -35,11 +35,13 @@ abstract class CommonUsbSerialDriver implements UsbSerialDriver { public static final int DEFAULT_READ_BUFFER_SIZE = 16 * 1024; public static final int DEFAULT_WRITE_BUFFER_SIZE = 16 * 1024; - protected final UsbDevice mDevice; - protected final UsbDeviceConnection mConnection; + protected final UsbDevice mDevice; + protected final Object mReadBufferLock = new Object(); + protected final Object mWriteBufferLock = new Object(); - protected final Object mReadBufferLock = new Object(); - protected final Object mWriteBufferLock = new Object(); + protected UsbDeviceConnection mConnection = null; + + private int _permissionStatus = permissionStatusRequestRequired; /** Internal read buffer. Guarded by {@link #mReadBufferLock}. */ protected byte[] mReadBuffer; @@ -47,14 +49,28 @@ abstract class CommonUsbSerialDriver implements UsbSerialDriver { /** Internal write buffer. Guarded by {@link #mWriteBufferLock}. */ protected byte[] mWriteBuffer; - public CommonUsbSerialDriver(UsbDevice device, UsbDeviceConnection connection) { + public CommonUsbSerialDriver(UsbDevice device) { mDevice = device; - mConnection = connection; mReadBuffer = new byte[DEFAULT_READ_BUFFER_SIZE]; mWriteBuffer = new byte[DEFAULT_WRITE_BUFFER_SIZE]; } + @Override + public void setConnection(UsbDeviceConnection connection) { + mConnection = connection; + } + + @Override + public int permissionStatus() { + return _permissionStatus; + } + + @Override + public void setPermissionStatus(int permissionStatus) { + _permissionStatus = permissionStatus; + } + /** * Returns the currently-bound USB device. * diff --git a/android/src/com/hoho/android/usbserial/driver/Cp2102SerialDriver.java b/android/src/com/hoho/android/usbserial/driver/Cp2102SerialDriver.java index aa151ba1a0e6887ea4b7985a43044dd4eb6fcbd2..679b719c9fc301d336b4f14f1591556857e94e2b 100644 --- a/android/src/com/hoho/android/usbserial/driver/Cp2102SerialDriver.java +++ b/android/src/com/hoho/android/usbserial/driver/Cp2102SerialDriver.java @@ -61,8 +61,8 @@ public class Cp2102SerialDriver extends CommonUsbSerialDriver { private UsbEndpoint mReadEndpoint; private UsbEndpoint mWriteEndpoint; - public Cp2102SerialDriver(UsbDevice device, UsbDeviceConnection connection) { - super(device, connection); + public Cp2102SerialDriver(UsbDevice device) { + super(device); } private int setConfigSingle(int request, int value) { diff --git a/android/src/com/hoho/android/usbserial/driver/FtdiSerialDriver.java b/android/src/com/hoho/android/usbserial/driver/FtdiSerialDriver.java index 4d13b5cd8b86506fc78c6512e7c73e563c52c73e..549bdf8e26c7ee44281a6173b21b7d659eaa21ef 100644 --- a/android/src/com/hoho/android/usbserial/driver/FtdiSerialDriver.java +++ b/android/src/com/hoho/android/usbserial/driver/FtdiSerialDriver.java @@ -211,8 +211,8 @@ public class FtdiSerialDriver extends CommonUsbSerialDriver { * @throws UsbSerialRuntimeException if the given device is incompatible * with this driver */ - public FtdiSerialDriver(UsbDevice usbDevice, UsbDeviceConnection usbConnection) { - super(usbDevice, usbConnection); + public FtdiSerialDriver(UsbDevice usbDevice) { + super(usbDevice); mType = null; } diff --git a/android/src/com/hoho/android/usbserial/driver/ProlificSerialDriver.java b/android/src/com/hoho/android/usbserial/driver/ProlificSerialDriver.java index 7c4c0a7f30136065fd71c16224de6ff8682ead0a..bde3c3807e1ad1fa64cefceb444816b0e5d74646 100644 --- a/android/src/com/hoho/android/usbserial/driver/ProlificSerialDriver.java +++ b/android/src/com/hoho/android/usbserial/driver/ProlificSerialDriver.java @@ -231,8 +231,8 @@ public class ProlificSerialDriver extends CommonUsbSerialDriver { return ((getStatus() & flag) == flag); } - public ProlificSerialDriver(UsbDevice device, UsbDeviceConnection connection) { - super(device, connection); + public ProlificSerialDriver(UsbDevice device) { + super(device); } @Override diff --git a/android/src/com/hoho/android/usbserial/driver/UsbId.java b/android/src/com/hoho/android/usbserial/driver/UsbId.java index ef2acf7ee998f125294eb758a0569fca937e78e1..8e5eba048b216fd89f02019bba1e6e4f993f94d9 100644 --- a/android/src/com/hoho/android/usbserial/driver/UsbId.java +++ b/android/src/com/hoho/android/usbserial/driver/UsbId.java @@ -74,6 +74,13 @@ public final class UsbId { public static final int DEVICE_SPARKY2 = 0x41D0; public static final int DEVICE_CC3D = 0x415D; + public static final int VENDOR_ARDUPILOT_CHIBIOS1 = 0x0483; + public static final int VENDOR_ARDUPILOT_CHIBIOS2 = 0x1209; + public static final int DEVICE_ARDUPILOT_CHIBIOS = 0x5740; + + public static final int VENDOR_DRAGONLINK = 0x1FC9; + public static final int DEVICE_DRAGONLINK = 0x0083; + private UsbId() { throw new IllegalAccessError("Non-instantiable class."); } diff --git a/android/src/com/hoho/android/usbserial/driver/UsbSerialDriver.java b/android/src/com/hoho/android/usbserial/driver/UsbSerialDriver.java index ed4426fc4d540238fc2cae9706adb41602a3a7a4..48ea197e1bdff3936eebb63995f9a03bc28c9876 100644 --- a/android/src/com/hoho/android/usbserial/driver/UsbSerialDriver.java +++ b/android/src/com/hoho/android/usbserial/driver/UsbSerialDriver.java @@ -83,6 +83,16 @@ public interface UsbSerialDriver { /** 2 stop bits. */ public static final int STOPBITS_2 = 2; + public static final int permissionStatusSuccess = 0; + public static final int permissionStatusDenied = 1; + public static final int permissionStatusRequested = 2; + public static final int permissionStatusRequestRequired = 3; + public static final int permissionStatusOpen = 4; + public int permissionStatus(); + public void setPermissionStatus(int permissionStatus); + + public void setConnection(UsbDeviceConnection connection); + /** * Returns the currently-bound USB device. * diff --git a/android/src/com/hoho/android/usbserial/driver/UsbSerialProber.java b/android/src/com/hoho/android/usbserial/driver/UsbSerialProber.java index b689ccc7c28e1b47c05c41a016bfe9567ffcdd5a..d01755a4f597a9eabd6c57f1b0657956b5622e84 100644 --- a/android/src/com/hoho/android/usbserial/driver/UsbSerialProber.java +++ b/android/src/com/hoho/android/usbserial/driver/UsbSerialProber.java @@ -65,11 +65,7 @@ public enum UsbSerialProber { if (!testIfSupported(usbDevice, FtdiSerialDriver.getSupportedDevices())) { return Collections.emptyList(); } - final UsbDeviceConnection connection = manager.openDevice(usbDevice); - if (connection == null) { - return Collections.emptyList(); - } - final UsbSerialDriver driver = new FtdiSerialDriver(usbDevice, connection); + final UsbSerialDriver driver = new FtdiSerialDriver(usbDevice); return Collections.singletonList(driver); } }, @@ -80,11 +76,7 @@ public enum UsbSerialProber { if (!testIfSupported(usbDevice, CdcAcmSerialDriver.getSupportedDevices())) { return Collections.emptyList(); } - final UsbDeviceConnection connection = manager.openDevice(usbDevice); - if (connection == null) { - return Collections.emptyList(); - } - final UsbSerialDriver driver = new CdcAcmSerialDriver(usbDevice, connection); + final UsbSerialDriver driver = new CdcAcmSerialDriver(usbDevice); return Collections.singletonList(driver); } }, @@ -95,11 +87,7 @@ public enum UsbSerialProber { if (!testIfSupported(usbDevice, Cp2102SerialDriver.getSupportedDevices())) { return Collections.emptyList(); } - final UsbDeviceConnection connection = manager.openDevice(usbDevice); - if (connection == null) { - return Collections.emptyList(); - } - final UsbSerialDriver driver = new Cp2102SerialDriver(usbDevice, connection); + final UsbSerialDriver driver = new Cp2102SerialDriver(usbDevice); return Collections.singletonList(driver); } }, @@ -110,11 +98,7 @@ public enum UsbSerialProber { if (!testIfSupported(usbDevice, ProlificSerialDriver.getSupportedDevices())) { return Collections.emptyList(); } - final UsbDeviceConnection connection = manager.openDevice(usbDevice); - if (connection == null) { - return Collections.emptyList(); - } - final UsbSerialDriver driver = new ProlificSerialDriver(usbDevice, connection); + final UsbSerialDriver driver = new ProlificSerialDriver(usbDevice); return Collections.singletonList(driver); } }; diff --git a/android/src/org/mavlink/qgroundcontrol/QGCActivity.java b/android/src/org/mavlink/qgroundcontrol/QGCActivity.java index 756597b29dc0b521e7047f5021e3bd72489bf894..70db6c08d60892f8dce8a781e307b4aa29c7c9d2 100644 --- a/android/src/org/mavlink/qgroundcontrol/QGCActivity.java +++ b/android/src/org/mavlink/qgroundcontrol/QGCActivity.java @@ -1,4 +1,4 @@ -package org.mavlink.qgroundcontrol; + /* Copyright 2013 Google Inc. * @@ -32,6 +32,7 @@ package org.mavlink.qgroundcontrol; import java.util.ArrayList; import java.util.HashMap; import java.util.List; +import java.util.ArrayList; import java.util.concurrent.ExecutorService; import java.util.concurrent.Executors; import java.util.Timer; @@ -39,6 +40,7 @@ import java.util.TimerTask; import java.io.IOException; import android.app.Activity; +import android.app.PendingIntent; import android.content.BroadcastReceiver; import android.content.Context; import android.content.Intent; @@ -72,35 +74,51 @@ public class QGCActivity extends QtActivity private final static ExecutorService m_Executor = Executors.newSingleThreadExecutor(); private static final String TAG = "QGC_QGCActivity"; private static PowerManager.WakeLock m_wl; - private static String USB_ACTION = "org.mavlink.qgroundcontrol.action.USB_PERMISSION"; - private TaiSync taiSync = null; + public static int BAD_DEVICE_ID = 0; + private static QGCActivity _instance = null; + private static UsbManager _usbManager = null; + private static List _drivers; + private static HashMap m_ioManager; + private static HashMap _userDataHashByDeviceId; + private static final String TAG = "QGC_QGCActivity"; + private static PowerManager.WakeLock _wakeLock; +// private static final String ACTION_USB_PERMISSION = "com.android.example.USB_PERMISSION"; + private static final String ACTION_USB_PERMISSION = "org.mavlink.qgroundcontrol.action.USB_PERMISSION"; + private static PendingIntent _usbPermissionIntent = null; + private TaiSync taiSync = null; public static Context m_context; + private final static ExecutorService m_Executor = Executors.newSingleThreadExecutor(); + private final static UsbIoManager.Listener m_Listener = new UsbIoManager.Listener() { @Override - public void onRunError(Exception eA, int userDataA) + public void onRunError(Exception eA, int userData) { Log.e(TAG, "onRunError Exception"); - nativeDeviceException(userDataA, eA.getMessage()); + nativeDeviceException(userData, eA.getMessage()); } @Override - public void onNewData(final byte[] dataA, int userDataA) + public void onNewData(final byte[] dataA, int userData) { - nativeDeviceNewData(userDataA, dataA); + nativeDeviceNewData(userData, dataA); } }; + // NATIVE C++ FUNCTION THAT WILL BE CALLED IF THE DEVICE IS UNPLUGGED + private static native void nativeDeviceHasDisconnected(int userDataA); + private static native void nativeDeviceException(int userDataA, String messageA); + private static native void nativeDeviceNewData(int userDataA, byte[] dataA); private final BroadcastReceiver mOpenAccessoryReceiver = new BroadcastReceiver() { @Override public void onReceive(Context context, Intent intent) { String action = intent.getAction(); - if (USB_ACTION.equals(action)) { + if (ACTION_USB_PERMISSION.equals(action)) { UsbAccessory accessory = intent.getParcelableExtra(UsbManager.EXTRA_ACCESSORY); if (intent.getBooleanExtra(UsbManager.EXTRA_PERMISSION_GRANTED, false)) { openAccessory(accessory); @@ -114,48 +132,104 @@ public class QGCActivity extends QtActivity } }; - // NATIVE C++ FUNCTION THAT WILL BE CALLED IF THE DEVICE IS UNPLUGGED - private static native void nativeDeviceHasDisconnected(int userDataA); - private static native void nativeDeviceException(int userDataA, String messageA); - private static native void nativeDeviceNewData(int userDataA, byte[] dataA); + private static UsbSerialDriver _findDriverByDeviceId(int deviceId) { + for (UsbSerialDriver driver: _drivers) { + if (driver.getDevice().getDeviceId() == deviceId) { + return driver; + } + } + return null; + } + + private static UsbSerialDriver _findDriverByDeviceName(String deviceName) { + for (UsbSerialDriver driver: _drivers) { + if (driver.getDevice().getDeviceName().equals(deviceName)) { + return driver; + } + } + return null; + } + + private final static BroadcastReceiver _usbReceiver = new BroadcastReceiver() { + public void onReceive(Context context, Intent intent) { + String action = intent.getAction(); + Log.i(TAG, "BroadcastReceiver USB action " + action); + + if (ACTION_USB_PERMISSION.equals(action)) { + synchronized (_instance) { + UsbDevice device = (UsbDevice)intent.getParcelableExtra(UsbManager.EXTRA_DEVICE); + if (device != null) { + UsbSerialDriver driver = _findDriverByDeviceId(device.getDeviceId()); + + if (intent.getBooleanExtra(UsbManager.EXTRA_PERMISSION_GRANTED, false)) { + qgcLogDebug("Permission granted to " + device.getDeviceName()); + driver.setPermissionStatus(UsbSerialDriver.permissionStatusSuccess); + } else { + qgcLogDebug("Permission denied for " + device.getDeviceName()); + driver.setPermissionStatus(UsbSerialDriver.permissionStatusDenied); + } + } + } + } else if (UsbManager.ACTION_USB_DEVICE_DETACHED.equals(action)) { + UsbDevice device = (UsbDevice)intent.getParcelableExtra(UsbManager.EXTRA_DEVICE); + if (device != null) { + if (_userDataHashByDeviceId.containsKey(device.getDeviceId())) { + nativeDeviceHasDisconnected(_userDataHashByDeviceId.get(device.getDeviceId())); + } + } + } + } + }; + + // Native C++ functions which connect back to QSerialPort code + private static native void nativeDeviceHasDisconnected(int userData); + private static native void nativeDeviceException(int userData, String messageA); + private static native void nativeDeviceNewData(int userData, byte[] dataA); // Native C++ functions called to log output public static native void qgcLogDebug(String message); public static native void qgcLogWarning(String message); - //////////////////////////////////////////////////////////////////////////////////////////////// - // - // Constructor. Only used once to create the initial instance for the static functions. - // - //////////////////////////////////////////////////////////////////////////////////////////////// + // QGCActivity singleton public QGCActivity() { - m_instance = this; - m_openedDevices = new HashMap(); - m_userData = new HashMap(); - m_ioManager = new HashMap(); - Log.i(TAG, "Instance created"); + _instance = this; + _drivers = new ArrayList(); + _userDataHashByDeviceId = new HashMap(); + m_ioManager = new HashMap(); } @Override - public void onCreate(Bundle savedInstanceState) { + public void onCreate(Bundle savedInstanceState) + { super.onCreate(savedInstanceState); - PowerManager pm = (PowerManager)m_instance.getSystemService(Context.POWER_SERVICE); - m_wl = pm.newWakeLock(PowerManager.SCREEN_BRIGHT_WAKE_LOCK, "QGroundControl"); - if(m_wl != null) { - m_wl.acquire(); - Log.i(TAG, "SCREEN_BRIGHT_WAKE_LOCK acquired."); + PowerManager pm = (PowerManager)_instance.getSystemService(Context.POWER_SERVICE); + _wakeLock = pm.newWakeLock(PowerManager.SCREEN_BRIGHT_WAKE_LOCK, "QGroundControl"); + if(_wakeLock != null) { + _wakeLock.acquire(); } else { Log.i(TAG, "SCREEN_BRIGHT_WAKE_LOCK not acquired!!!"); } m_instance.getWindow().addFlags(WindowManager.LayoutParams.FLAG_KEEP_SCREEN_ON); + _instance.getWindow().addFlags(WindowManager.LayoutParams.FLAG_KEEP_SCREEN_ON); + + _usbManager = (UsbManager)_instance.getSystemService(Context.USB_SERVICE); + + // Register for USB Detach and USB Permission intent + IntentFilter filter = new IntentFilter(); + filter.addAction(UsbManager.ACTION_USB_DEVICE_DETACHED); + filter.addAction(ACTION_USB_PERMISSION); + _instance.registerReceiver(_instance._usbReceiver, filter); + + // Create intent for usb permission request + _usbPermissionIntent = PendingIntent.getBroadcast(_instance, 0, new Intent(ACTION_USB_PERMISSION), 0); if (m_manager == null) { try { m_manager = (UsbManager)m_instance.getSystemService(Context.USB_SERVICE); taiSync = new TaiSync(); - IntentFilter filter = new IntentFilter(USB_ACTION); + IntentFilter filter = new IntentFilter(ACTION_USB_PERMISSION); filter.addAction( UsbManager.ACTION_USB_ACCESSORY_DETACHED); registerReceiver(mOpenAccessoryReceiver, filter); @@ -167,13 +241,13 @@ public class QGCActivity extends QtActivity } @Override + protected void onDestroy() { protected void onDestroy() { unregisterReceiver(mOpenAccessoryReceiver); try { - if(m_wl != null) { - m_wl.release(); - Log.i(TAG, "SCREEN_BRIGHT_WAKE_LOCK released."); + if(_wakeLock != null) { + _wakeLock.release(); } } catch(Exception e) { Log.e(TAG, "Exception onDestroy()"); @@ -184,222 +258,168 @@ public class QGCActivity extends QtActivity public void onInit(int status) { } - ///////////////////////////////////////////////////////////////////////////////////////////////////////// - // - // Find all current devices that match the device filter described in the androidmanifest.xml and the - // device_filter.xml - // - ///////////////////////////////////////////////////////////////////////////////////////////////////////// - private static boolean getCurrentDevices() + /// Incrementally updates the list of drivers connected to the device + private static void updateCurrentDrivers() { - if (m_instance == null) - return false; + List currentDrivers = UsbSerialProber.findAllDevices(_usbManager); + + if (m_manager == null) + m_manager = (UsbManager)m_instance.getSystemService(Context.USB_SERVICE); if (m_devices != null) m_devices.clear(); + // Remove stale drivers + for (int i=_drivers.size()-1; i>=0; i--) { + boolean found = false; + for (UsbSerialDriver currentDriver: currentDrivers) { + if (_drivers.get(i).getDevice().getDeviceId() == currentDriver.getDevice().getDeviceId()) { + found = true; + break; + } + } - m_devices = UsbSerialProber.findAllDevices(m_manager); + if (!found) { + qgcLogDebug("Remove stale driver " + _drivers.get(i).getDevice().getDeviceName()); + _drivers.remove(i); + } + } - return true; + // Add new drivers + for (int i=0; i deviceInfoList = new ArrayList(); - int countL = 0; - int iL; + for (int i=0; i<_drivers.size(); i++) { + String deviceInfo; + UsbSerialDriver driver = _drivers.get(i); - // CHECK FOR ALREADY OPENED DEVICES AND DON'T INCLUDE THEM IN THE COUNT + // CHECK FOR ALREADY OPENED DEVICES AND DON"T INCLUDE THEM IN THE COUNT for (iL=0; iLsetError(QSerialPort::DeviceNotFoundError); return false; } diff --git a/qgcresources.qrc b/qgcresources.qrc index e87e4a066b91395b533b3d9914ee2a1b0f73f449..3a3f6767ed5a67b46a2f735c84e5b921047d4036 100644 --- a/qgcresources.qrc +++ b/qgcresources.qrc @@ -210,6 +210,7 @@ resources/QGCLogoBlack.svg resources/QGCLogoFull.svg resources/QGCLogoWhite.svg + resources/QGCLogoArrow.svg resources/QGroundControlConnect.svg resources/rtl.svg resources/SplashScreen.png diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 05b6447f69eb40a1a7dd2d63068ba470483fb72a..0197b2ce9fd8fd17da62f058cbbf91f36dd3b94b 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -405,7 +405,8 @@ HEADERS += \ src/api/QGCOptions.h \ src/api/QGCSettings.h \ src/api/QmlComponentInfo.h \ - src/comm/MavlinkMessagesTimer.h + src/comm/MavlinkMessagesTimer.h \ + src/GPS/Drivers/src/base_station.h SOURCES += \ src/api/QGCCorePlugin.cc \ @@ -620,6 +621,7 @@ HEADERS += \ src/comm/QGCMAVLink.h \ src/comm/TCPLink.h \ src/comm/UDPLink.h \ + src/comm/UdpIODevice.h \ src/uas/UAS.h \ src/uas/UASInterface.h \ src/uas/UASMessageHandler.h \ @@ -664,6 +666,7 @@ HEADERS += \ src/GPS/Drivers/src/rtcm.h \ src/GPS/Drivers/src/ashtech.h \ src/GPS/Drivers/src/ubx.h \ + src/GPS/Drivers/src/sbf.h \ src/GPS/GPSManager.h \ src/GPS/GPSPositionMessage.h \ src/GPS/GPSProvider.h \ @@ -820,6 +823,7 @@ SOURCES += \ src/comm/QGCMAVLink.cc \ src/comm/TCPLink.cc \ src/comm/UDPLink.cc \ + src/comm/UdpIODevice.cc \ src/main.cc \ src/uas/UAS.cc \ src/uas/UASMessageHandler.cc \ @@ -851,6 +855,7 @@ SOURCES += \ src/GPS/Drivers/src/rtcm.cpp \ src/GPS/Drivers/src/ashtech.cpp \ src/GPS/Drivers/src/ubx.cpp \ + src/GPS/Drivers/src/sbf.cpp \ src/GPS/GPSManager.cc \ src/GPS/GPSProvider.cc \ src/GPS/RTCM/RTCMMavlink.cc \ diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index 5143cec2e952cceb7b5d8772f88546b30d4a1a9d..e51d4ac77084d4af3bd03de92be6ef60c9696d3d 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -137,6 +137,7 @@ src/QmlControls/VehicleRotationCal.qml src/QmlControls/VehicleSummaryRow.qml src/ViewWidgets/ViewWidget.qml + src/FactSystem/FactControls/AltitudeFactTextField.qml src/FactSystem/FactControls/FactBitmask.qml src/FactSystem/FactControls/FactCheckBox.qml src/FactSystem/FactControls/FactComboBox.qml diff --git a/resources/QGCLogoArrow.svg b/resources/QGCLogoArrow.svg new file mode 100644 index 0000000000000000000000000000000000000000..89cc75ff697a298e6f8ba28d60bd462982425cf5 --- /dev/null +++ b/resources/QGCLogoArrow.svg @@ -0,0 +1,129 @@ + + + +image/svg+xml + + + + + + + + + + + + \ No newline at end of file diff --git a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml index 43387450579bc2bc5634e1e2279f8c939dedf892..6e079618645a977ca72f21411ee3e7a9f7145824 100644 --- a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml +++ b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml @@ -363,6 +363,12 @@ Lorenz Meier <lorenz@px4.io> Quadrotor x + + Copter + Beat Kueng <beat-kueng@gmx.net> + Quadrotor x + https://docs.px4.io/en/frames_multicopter/holybro_qav250_pixhawk4_mini.html + Copter James Goppert <james.goppert@gmail.com> diff --git a/src/Camera/QGCCameraControl.cc b/src/Camera/QGCCameraControl.cc index 39605d0901f7badd5a2923644f03a1345f3cbf22..49600b339bb21e519bcffcaf378757d882646df9 100644 --- a/src/Camera/QGCCameraControl.cc +++ b/src/Camera/QGCCameraControl.cc @@ -61,13 +61,13 @@ static const char* kPhotoLapseCount = "PhotoLapseCount"; //----------------------------------------------------------------------------- // Known Parameters -static const char *kCAM_EV = "CAM_EV"; -static const char *kCAM_EXPMODE = "CAM_EXPMODE"; -static const char *kCAM_ISO = "CAM_ISO"; -static const char* kCAM_SHUTTER = "CAM_SHUTTER"; -static const char* kCAM_APERTURE = "CAM_APERTURE"; -static const char* kCAM_WBMODE = "CAM_WBMODE"; -static const char* kCAM_MODE = "CAM_MODE"; +const char* QGCCameraControl::kCAM_EV = "CAM_EV"; +const char* QGCCameraControl::kCAM_EXPMODE = "CAM_EXPMODE"; +const char* QGCCameraControl::kCAM_ISO = "CAM_ISO"; +const char* QGCCameraControl::kCAM_SHUTTERSPD = "CAM_SHUTTERSPD"; +const char* QGCCameraControl::kCAM_APERTURE = "CAM_APERTURE"; +const char* QGCCameraControl::kCAM_WBMODE = "CAM_WBMODE"; +const char* QGCCameraControl::kCAM_MODE = "CAM_MODE"; //----------------------------------------------------------------------------- QGCCameraOptionExclusion::QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_) @@ -1928,13 +1928,16 @@ void QGCCameraControl::_checkForVideoStreams() { if(_info.flags & CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM) { - connect(&_streamInfoTimer, &QTimer::timeout, this, &QGCCameraControl::_streamTimeout); - _streamInfoTimer.setSingleShot(false); - connect(&_streamStatusTimer, &QTimer::timeout, this, &QGCCameraControl::_streamStatusTimeout); - _streamStatusTimer.setSingleShot(true); - //-- Request all streams - _requestStreamInfo(0); - _streamInfoTimer.start(2000); + //-- Skip it if using Taisync as it has its own video settings + if(!qgcApp()->toolbox()->videoManager()->isTaisync()) { + connect(&_streamInfoTimer, &QTimer::timeout, this, &QGCCameraControl::_streamTimeout); + _streamInfoTimer.setSingleShot(false); + connect(&_streamStatusTimer, &QTimer::timeout, this, &QGCCameraControl::_streamStatusTimeout); + _streamStatusTimer.setSingleShot(true); + //-- Request all streams + _requestStreamInfo(0); + _streamInfoTimer.start(2000); + } } } @@ -1987,9 +1990,9 @@ QGCCameraControl::iso() //----------------------------------------------------------------------------- Fact* -QGCCameraControl::shutter() +QGCCameraControl::shutterSpeed() { - return (_paramComplete && _activeSettings.contains(kCAM_SHUTTER)) ? getFact(kCAM_SHUTTER) : nullptr; + return (_paramComplete && _activeSettings.contains(kCAM_SHUTTERSPD)) ? getFact(kCAM_SHUTTERSPD) : nullptr; } //----------------------------------------------------------------------------- diff --git a/src/Camera/QGCCameraControl.h b/src/Camera/QGCCameraControl.h index 7255e1974bc58a6f61bc837a7d2c967308c7a103..8e06b63ef56bfb720d9c9dbee74cf844b6e45d95 100644 --- a/src/Camera/QGCCameraControl.h +++ b/src/Camera/QGCCameraControl.h @@ -144,7 +144,7 @@ public: Q_PROPERTY(Fact* exposureMode READ exposureMode NOTIFY parametersReady) Q_PROPERTY(Fact* ev READ ev NOTIFY parametersReady) Q_PROPERTY(Fact* iso READ iso NOTIFY parametersReady) - Q_PROPERTY(Fact* shutter READ shutter NOTIFY parametersReady) + Q_PROPERTY(Fact* shutterSpeed READ shutterSpeed NOTIFY parametersReady) Q_PROPERTY(Fact* aperture READ aperture NOTIFY parametersReady) Q_PROPERTY(Fact* wb READ wb NOTIFY parametersReady) Q_PROPERTY(Fact* mode READ mode NOTIFY parametersReady) @@ -222,7 +222,7 @@ public: virtual Fact* exposureMode (); virtual Fact* ev (); virtual Fact* iso (); - virtual Fact* shutter (); + virtual Fact* shutterSpeed (); virtual Fact* aperture (); virtual Fact* wb (); virtual Fact* mode (); @@ -249,6 +249,16 @@ public: //-- Allow controller to modify or invalidate parameter change virtual bool validateParameter (Fact* pFact, QVariant& newValue); + + // Known Parameters + static const char* kCAM_EV; + static const char* kCAM_EXPMODE; + static const char* kCAM_ISO; + static const char* kCAM_SHUTTERSPD; + static const char* kCAM_APERTURE; + static const char* kCAM_WBMODE; + static const char* kCAM_MODE; + signals: void infoChanged (); void videoStatusChanged (); diff --git a/src/Camera/QGCCameraManager.cc b/src/Camera/QGCCameraManager.cc index c6c0e3ec3074d9153d9a4512e6440c87d4dae008..bcf3cce4be8bd63b55f584c217c83fa2dc3ba6d2 100644 --- a/src/Camera/QGCCameraManager.cc +++ b/src/Camera/QGCCameraManager.cc @@ -109,32 +109,39 @@ QGCCameraManager::_handleHeartbeat(const mavlink_message_t &message) //-- If this heartbeat is from a different component within the vehicle if(_vehicleReadyState && _vehicle->id() == message.sysid && _vehicle->defaultComponentId() != message.compid) { //-- First time hearing from this one? - if(!_cameraInfoRequest.contains(message.compid)) { + QString sCompID = QString::number(message.compid); + if(!_cameraInfoRequest.contains(sCompID)) { + qCDebug(CameraManagerLog) << "Hearbeat from " << message.compid; CameraStruct* pInfo = new CameraStruct(this); pInfo->lastHeartbeat.start(); - _cameraInfoRequest[message.compid] = pInfo; + _cameraInfoRequest[sCompID] = pInfo; //-- Request camera info _requestCameraInfo(message.compid); } else { - //-- Check if we have indeed received the camera info - if(_cameraInfoRequest[message.compid]->infoReceived) { - //-- We have it. Just update the heartbeat timeout - _cameraInfoRequest[message.compid]->lastHeartbeat.start(); - } else { - //-- Try again. Maybe. - if(_cameraInfoRequest[message.compid]->lastHeartbeat.elapsed() > 2000) { - if(_cameraInfoRequest[message.compid]->tryCount > 3) { - if(!_cameraInfoRequest[message.compid]->gaveUp) { - _cameraInfoRequest[message.compid]->gaveUp = true; - qWarning() << "Giving up requesting camera info from" << _vehicle->id() << message.compid; + if(_cameraInfoRequest[sCompID]) { + CameraStruct* pInfo = _cameraInfoRequest[sCompID]; + //-- Check if we have indeed received the camera info + if(pInfo->infoReceived) { + //-- We have it. Just update the heartbeat timeout + pInfo->lastHeartbeat.start(); + } else { + //-- Try again. Maybe. + if(pInfo->lastHeartbeat.elapsed() > 2000) { + if(pInfo->tryCount > 3) { + if(!pInfo->gaveUp) { + pInfo->gaveUp = true; + qWarning() << "Giving up requesting camera info from" << _vehicle->id() << message.compid; + } + } else { + pInfo->tryCount++; + //-- Request camera info. Again. It could be something other than a camera, in which + // case, we won't ever receive it. + _requestCameraInfo(message.compid); } - } else { - _cameraInfoRequest[message.compid]->tryCount++; - //-- Request camera info. Again. It could be something other than a camera, in which - // case, we won't ever receive it. - _requestCameraInfo(message.compid); } } + } else { + qWarning() << "_cameraInfoRequest[" << sCompID << "] is null"; } } } @@ -188,9 +195,10 @@ void QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message) { //-- Have we requested it? - if(_cameraInfoRequest.contains(message.compid) && !_cameraInfoRequest[message.compid]->infoReceived) { + QString sCompID = QString::number(message.compid); + if(_cameraInfoRequest.contains(sCompID) && !_cameraInfoRequest[sCompID]->infoReceived) { //-- Flag it as done - _cameraInfoRequest[message.compid]->infoReceived = true; + _cameraInfoRequest[sCompID]->infoReceived = true; mavlink_camera_information_t info; mavlink_msg_camera_information_decode(&message, &info); qCDebug(CameraManagerLog) << "_handleCameraInfo:" << reinterpret_cast(info.model_name) << reinterpret_cast(info.vendor_name) << "Comp ID:" << message.compid; @@ -210,14 +218,15 @@ void QGCCameraManager::_cameraTimeout() { //-- Iterate cameras - for(int i = 0; i < _cameraInfoRequest.count(); i++) { - if(_cameraInfoRequest[i]) { + foreach(QString sCompID, _cameraInfoRequest.keys()) { + if(_cameraInfoRequest[sCompID]) { + CameraStruct* pInfo = _cameraInfoRequest[sCompID]; //-- Have we received a camera info message? - if(_cameraInfoRequest[i]->infoReceived) { + if(pInfo->infoReceived) { //-- Has the camera stopped talking to us? - if(_cameraInfoRequest[i]->lastHeartbeat.elapsed() > 5000) { + if(pInfo->lastHeartbeat.elapsed() > 5000) { //-- Camera is gone. Remove it. - QGCCameraControl* pCamera = _findCamera(i); + QGCCameraControl* pCamera = _findCamera(pInfo->compID); qWarning() << "Camera" << pCamera->modelName() << "stopped transmitting. Removing from list."; int idx = _cameraLabels.indexOf(pCamera->modelName()); if(idx >= 0) { @@ -229,8 +238,8 @@ QGCCameraManager::_cameraTimeout() } bool autoStream = pCamera->autoStream(); pCamera->deleteLater(); - delete _cameraInfoRequest[i]; - _cameraInfoRequest.remove(i); + delete pInfo; + _cameraInfoRequest.remove(sCompID); emit cameraLabelsChanged(); //-- If we have another camera, switch current camera. if(_cameras.count()) { diff --git a/src/Camera/QGCCameraManager.h b/src/Camera/QGCCameraManager.h index 6b882480cfc9ed0e34c11d88e72ed5eb7e921afc..8d52976d7a2359360401b2b1f0a0d48fce7c05ae 100644 --- a/src/Camera/QGCCameraManager.h +++ b/src/Camera/QGCCameraManager.h @@ -81,6 +81,7 @@ protected: bool infoReceived = false; bool gaveUp = false; int tryCount = 0; + uint8_t compID = 0; }; Vehicle* _vehicle = nullptr; @@ -93,5 +94,5 @@ protected: QTime _lastZoomChange; QTime _lastCameraChange; QTimer _cameraTimer; - QMap _cameraInfoRequest; + QMap _cameraInfoRequest; }; diff --git a/src/FactSystem/FactControls/AltitudeFactTextField.qml b/src/FactSystem/FactControls/AltitudeFactTextField.qml new file mode 100644 index 0000000000000000000000000000000000000000..11d287a8e41b6c48e1997dff0790d8f025db7781 --- /dev/null +++ b/src/FactSystem/FactControls/AltitudeFactTextField.qml @@ -0,0 +1,37 @@ +import QGroundControl 1.0 +import QGroundControl.FactSystem 1.0 + +FactTextField { + unitsLabel: fact ? fact.units + _altitudeModeExtraUnits : "" + showUnits: true + showHelp: true + + property int altitudeMode: QGroundControl.AltitudeModeNone + + readonly property string _altModeNoneExtraUnits: "" + readonly property string _altModeRelativeExtraUnits: qsTr(" (Rel)") + readonly property string _altModeAbsoluteExtraUnits: qsTr(" (AMSL)") + readonly property string _altModeAboveTerrainExtraUnits: qsTr(" (Abv Terr)") + readonly property string _altModeTerrainFrameExtraUnits: qsTr(" (TerrF)") + + property string _altitudeModeExtraUnits: _altModeRelativeExtraUnits + + function updateAltitudeModeExtraUnits() { + if (altitudeMode === QGroundControl.AltitudeModeNone) { + _altitudeModeExtraUnits = _altModeNoneExtraUnits + } else if (altitudeMode === QGroundControl.AltitudeModeRelative) { + _altitudeModeExtraUnits = _altModeRelativeExtraUnits + } else if (altitudeMode === QGroundControl.AltitudeModeAbsolute) { + _altitudeModeExtraUnits = _altModeAbsoluteExtraUnits + } else if (altitudeMode === QGroundControl.AltitudeModeAboveTerrain) { + _altitudeModeExtraUnits = _altModeAboveTerrainExtraUnits + } else if (missionItem.altitudeMode === QGroundControl.AltitudeModeTerrainFrame) { + _altitudeModeExtraUnits = _altModeTerrainFrameExtraUnits + } else { + console.log("AltitudeFactTextField Internal error: Unknown altitudeMode", altitudeMode) + _altitudeModeExtraUnits = "" + } + } + + onAltitudeModeChanged: updateAltitudeModeExtraUnits() +} diff --git a/src/FactSystem/FactControls/qmldir b/src/FactSystem/FactControls/qmldir index 698cc920ef07e39f9426c10c6f1d8d2d76fefaac..81e0178f85dfeed9f7472d3e4b26295bd94f2076 100644 --- a/src/FactSystem/FactControls/qmldir +++ b/src/FactSystem/FactControls/qmldir @@ -1,12 +1,13 @@ Module QGroundControl.FactControls -FactBitmask 1.0 FactBitmask.qml -FactCheckBox 1.0 FactCheckBox.qml -FactComboBox 1.0 FactComboBox.qml -FactLabel 1.0 FactLabel.qml -FactPanel 1.0 FactPanel.qml -FactTextField 1.0 FactTextField.qml -FactTextFieldGrid 1.0 FactTextFieldGrid.qml -FactTextFieldRow 1.0 FactTextFieldRow.qml -FactValueSlider 1.0 FactValueSlider.qml -FactTextFieldSlider 1.0 FactTextFieldSlider.qml +AltitudeFactTextField 1.0 AltitudeFactTextField.qml +FactBitmask 1.0 FactBitmask.qml +FactCheckBox 1.0 FactCheckBox.qml +FactComboBox 1.0 FactComboBox.qml +FactLabel 1.0 FactLabel.qml +FactPanel 1.0 FactPanel.qml +FactTextField 1.0 FactTextField.qml +FactTextFieldGrid 1.0 FactTextFieldGrid.qml +FactTextFieldRow 1.0 FactTextFieldRow.qml +FactValueSlider 1.0 FactValueSlider.qml +FactTextFieldSlider 1.0 FactTextFieldSlider.qml diff --git a/src/FactSystem/FactSystem.h b/src/FactSystem/FactSystem.h index 29089ceab3e25f62be9531ac1b39af08d2719113..2ca94973d093286e6792f285f60615c85c00f207 100644 --- a/src/FactSystem/FactSystem.h +++ b/src/FactSystem/FactSystem.h @@ -7,12 +7,7 @@ * ****************************************************************************/ - -/// @file -/// @author Don Gagne - -#ifndef FACTSYSTEM_H -#define FACTSYSTEM_H +#pragma once #include "Fact.h" #include "FactMetaData.h" @@ -26,7 +21,6 @@ class FactSystem : public QGCTool Q_OBJECT public: - /// All access to FactSystem is through FactSystem::instance, so constructor is private FactSystem(QGCApplication* app, QGCToolbox* toolbox); // Override from QGCTool @@ -41,5 +35,3 @@ public: private: static const char* _factSystemQmlUri; ///< URI for FactSystem QML imports }; - -#endif diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index df059a4fec4a1de9c5b3a740a2a1a1a3ecf2e036..68119e7ffcf0ba468f1dff1e788b441d3f50428e 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -325,16 +325,20 @@ void APMFirmwarePlugin::_handleOutgoingParamSet(Vehicle* vehicle, LinkInterface* mavlink_msg_param_set_encode_chan(message->sysid, message->compid, outgoingLink->mavlinkChannel(), message, ¶mSet); } -bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* vehicle, mavlink_message_t* message) +bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* vehicle, mavlink_message_t* message, bool longVersion) { QString messageText; APMFirmwarePluginInstanceData* instanceData = qobject_cast(vehicle->firmwarePluginInstanceData()); - mavlink_statustext_t statusText; - mavlink_msg_statustext_decode(message, &statusText); + int severity; + if (longVersion) { + severity = mavlink_msg_statustext_long_get_severity(message); + } else { + severity = mavlink_msg_statustext_get_severity(message); + } - if (vehicle->firmwareMajorVersion() == Vehicle::versionNotSetValue || statusText.severity < MAV_SEVERITY_NOTICE) { - messageText = _getMessageText(message); + if (vehicle->firmwareMajorVersion() == Vehicle::versionNotSetValue || severity < MAV_SEVERITY_NOTICE) { + messageText = _getMessageText(message, longVersion); qCDebug(APMFirmwarePluginLog) << messageText; if (!messageText.contains(APM_SOLO_REXP)) { @@ -400,14 +404,14 @@ bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* vehicle, mavlink_mess } if (messageText.isEmpty()) { - messageText = _getMessageText(message); + messageText = _getMessageText(message, longVersion); } // The following messages are incorrectly labeled as warning message. // Fixed in newer firmware (unreleased at this point), but still in older firmware. if (messageText.contains(APM_COPTER_REXP) || messageText.contains(APM_PLANE_REXP) || messageText.contains(APM_ROVER_REXP) || messageText.contains(APM_SUB_REXP) || messageText.contains(APM_PX4NUTTX_REXP) || messageText.contains(APM_FRAME_REXP) || messageText.contains(APM_SYSID_REXP)) { - _setInfoSeverity(message); + _setInfoSeverity(message, longVersion); } if (messageText.contains(APM_SOLO_REXP)) { @@ -415,7 +419,7 @@ bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* vehicle, mavlink_mess vehicle->setSoloFirmware(true); // Fix up severity - _setInfoSeverity(message); + _setInfoSeverity(message, longVersion); // Start TCP video handshake with ARTOO _soloVideoHandshake(vehicle, true /* originalSoloFirmware */); @@ -465,7 +469,9 @@ bool APMFirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_m _handleIncomingParamValue(vehicle, message); break; case MAVLINK_MSG_ID_STATUSTEXT: - return _handleIncomingStatusText(vehicle, message); + return _handleIncomingStatusText(vehicle, message, false /* longVersion */); + case MAVLINK_MSG_ID_STATUSTEXT_LONG: + return _handleIncomingStatusText(vehicle, message, true /* longVersion */); case MAVLINK_MSG_ID_HEARTBEAT: _handleIncomingHeartbeat(vehicle, message); break; @@ -494,12 +500,17 @@ void APMFirmwarePlugin::adjustOutgoingMavlinkMessage(Vehicle* vehicle, LinkInter } } -QString APMFirmwarePlugin::_getMessageText(mavlink_message_t* message) const +QString APMFirmwarePlugin::_getMessageText(mavlink_message_t* message, bool longVersion) const { QByteArray b; - b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1); - mavlink_msg_statustext_get_text(message, b.data()); + if (longVersion) { + b.resize(MAVLINK_MSG_STATUSTEXT_LONG_FIELD_TEXT_LEN+1); + mavlink_msg_statustext_long_get_text(message, b.data()); + } else { + b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1); + mavlink_msg_statustext_get_text(message, b.data()); + } // Ensure NUL-termination b[b.length()-1] = '\0'; @@ -561,20 +572,33 @@ void APMFirmwarePlugin::_adjustSeverity(mavlink_message_t* message) const &statusText); } -void APMFirmwarePlugin::_setInfoSeverity(mavlink_message_t* message) const +void APMFirmwarePlugin::_setInfoSeverity(mavlink_message_t* message, bool longVersion) const { - mavlink_statustext_t statusText; - mavlink_msg_statustext_decode(message, &statusText); - // Re-Encoding is always done using mavlink 1.0 mavlink_status_t* mavlinkStatusReEncode = mavlink_get_channel_status(0); mavlinkStatusReEncode->flags |= MAVLINK_STATUS_FLAG_IN_MAVLINK1; - statusText.severity = MAV_SEVERITY_INFO; - mavlink_msg_statustext_encode_chan(message->sysid, - message->compid, - 0, // Re-encoding uses reserved channel 0 - message, - &statusText); + + if (longVersion) { + mavlink_statustext_long_t statusTextLong; + mavlink_msg_statustext_long_decode(message, &statusTextLong); + + statusTextLong.severity = MAV_SEVERITY_INFO; + mavlink_msg_statustext_long_encode_chan(message->sysid, + message->compid, + 0, // Re-encoding uses reserved channel 0 + message, + &statusTextLong); + } else { + mavlink_statustext_t statusText; + mavlink_msg_statustext_decode(message, &statusText); + + statusText.severity = MAV_SEVERITY_INFO; + mavlink_msg_statustext_encode_chan(message->sysid, + message->compid, + 0, // Re-encoding uses reserved channel 0 + message, + &statusText); + } } void APMFirmwarePlugin::_adjustCalibrationMessageSeverity(mavlink_message_t* message) const diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h index 3abab25ee0976d6ab31f5cd4dd6f51926bf358cb..ddf754ed54ef60e4a2edc956c5a3e53b0a6ca31c 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h @@ -119,10 +119,10 @@ private: void _adjustSeverity(mavlink_message_t* message) const; void _adjustCalibrationMessageSeverity(mavlink_message_t* message) const; static bool _isTextSeverityAdjustmentNeeded(const APMFirmwareVersion& firmwareVersion); - void _setInfoSeverity(mavlink_message_t* message) const; - QString _getMessageText(mavlink_message_t* message) const; + void _setInfoSeverity(mavlink_message_t* message, bool longVersion) const; + QString _getMessageText(mavlink_message_t* message, bool longVersion) const; void _handleIncomingParamValue(Vehicle* vehicle, mavlink_message_t* message); - bool _handleIncomingStatusText(Vehicle* vehicle, mavlink_message_t* message); + bool _handleIncomingStatusText(Vehicle* vehicle, mavlink_message_t* message, bool longVersion); void _handleIncomingHeartbeat(Vehicle* vehicle, mavlink_message_t* message); void _handleOutgoingParamSet(Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message); void _soloVideoHandshake(Vehicle* vehicle, bool originalSoloFirmware); diff --git a/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.cc index eb0fe9378efb06a5c22f6313f47ef1df0ac48f73..b66df2fcc3c292e34a7319f1a6ea12b0c7aa8d72 100644 --- a/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.cc @@ -124,6 +124,12 @@ ArduSubFirmwarePlugin::ArduSubFirmwarePlugin(void): } _nameToFactGroupMap.insert("APMSubInfo", &_infoFactGroup); + + _factRenameMap[QStringLiteral("altitudeRelative")] = QStringLiteral("Depth"); + _factRenameMap[QStringLiteral("flightTime")] = QStringLiteral("Dive Time"); + _factRenameMap[QStringLiteral("altitudeAMSL")] = QStringLiteral(""); + _factRenameMap[QStringLiteral("hobbs")] = QStringLiteral(""); + _factRenameMap[QStringLiteral("airSpeed")] = QStringLiteral(""); } QList ArduSubFirmwarePlugin::supportedMissionCommands(void) @@ -310,3 +316,14 @@ QString ArduSubFirmwarePlugin::vehicleImageOutline(const Vehicle* vehicle) const { return vehicleImageOpaque(vehicle); } + +void ArduSubFirmwarePlugin::adjustMetaData(MAV_TYPE vehicleType, FactMetaData* metaData) +{ + Q_UNUSED(vehicleType); + if (!metaData) { + return; + } + if (_factRenameMap.contains(metaData->name())) { + metaData->setShortDescription(QString(_factRenameMap[metaData->name()])); + } +} diff --git a/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h index 6a356059a18728fc12bcbd658f61aa941da127eb..b826c1e0c92bd4bd505f93167962a20fbc9445d6 100644 --- a/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h @@ -137,11 +137,13 @@ public: const QVariantList& toolBarIndicators(const Vehicle* vehicle) final; bool adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) final; virtual QMap* factGroups(void) final; + void adjustMetaData(MAV_TYPE vehicleType, FactMetaData* metaData) override final; private: QVariantList _toolBarIndicators; static bool _remapParamNameIntialized; + QMap _factRenameMap; static FirmwarePlugin::remapParamNameMajorVersionMap_t _remapParamName; void _handleNamedValueFloat(mavlink_message_t* message); void _handleMavlinkMessage(mavlink_message_t* message); diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index bcae4c08b7d33b688987469028e945fff0ca98bf..57006f56826d286e3e0bb46359e925534748ed96 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -309,6 +309,11 @@ public: int versionCompare(Vehicle* vehicle, QString& compare); int versionCompare(Vehicle* vehicle, int major, int minor, int patch); + /// Allows the Firmware plugin to override the facts meta data. + /// @param vehicleType - Type of current vehicle + /// @param metaData - MetaData for fact + virtual void adjustMetaData(MAV_TYPE vehicleType, FactMetaData* metaData) {Q_UNUSED(vehicleType); Q_UNUSED(metaData);}; + // FIXME: Hack workaround for non pluginize FollowMe support static const QString px4FollowMeFlightMode; diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index 44eb73ff104ccf7c074ddc815264a15a20bb8c8d..9b5f3f56825c56bf368e6decbd6a48301387b9b6 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -425,7 +425,7 @@ void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord return; } - if (vehicle->capabilityBits() && MAV_PROTOCOL_CAPABILITY_COMMAND_INT) { + if (vehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) { vehicle->sendMavCommandInt(vehicle->defaultComponentId(), MAV_CMD_DO_REPOSITION, MAV_FRAME_GLOBAL, diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 5e5a5ae14c77563e10188573cc99b6e0895fd74f..6ed43763edb6dd59f4fa417302b4e3c57f83f113 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -513,7 +513,7 @@ Set to 2 to use heading from motion capture * the MSB bit is not used to avoid problems in the conversion between int and uint Default value: (10 << 0 | 1000 << 8 | 0 << 24) = 256010 - authorizer system id = 10 - authentication method parameter = 10000msec of timeout - authentication method = during arm - + Maximum value of EKF accelerometer delta velocity bias estimate that will allow arming. Note: ekf2 will limit the delta velocity bias estimate magnitude to be less than EKF2_ABL_LIM * FILTER_UPDATE_PERIOD_MS * 0.001 so this parameter must be less than that to be useful 0.001 @@ -3845,7 +3845,7 @@ Used to calculate increased terrain random walk nosie due to movement Enable yaw control of the mount. (Only affects multicopters and ROI mission items) - If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading mode as specified by MIS_YAWMODE. If disabled, the vehicle will yaw towards the ROI. + If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading towards the flight direction. If disabled, the vehicle will yaw towards the ROI. 0 1 @@ -4524,13 +4524,6 @@ is 90 degrees. It should be lower than MPC_XY_CRUISE m/s 2 - - Delay from idle state to arming state - For altitude controlled modes, the transition from idle to armed state is delayed by MPC_IDLE_TKO time to ensure that the propellers have reached idle speed before attempting a takeoff. This delay is particularly useful for vehicles with large propellers. - 0 - 10 - sec - Maximum jerk limit Limit the maximum jerk of the vehicle (how fast the acceleration can change). A lower value leads to smoother vehicle motions, but it also limits its agility (how fast it can change directions or break). Setting this to the maximum value essentially disables the limit. Note: this is only used when MPC_POS_MODE is set to a smoothing mode. @@ -4609,6 +4602,13 @@ Temporary Parameter to enable interface testing Smooth position control (Velocity) + + Enforced delay between arming and takeoff + For altitude controlled modes the time from arming the motors until a takeoff is possible gets forced to be at least MPC_SPOOLUP_TIME seconds to ensure the motors and propellers can sppol up and reach idle speed before getting commanded to spin faster. This delay is particularly useful for vehicles with slow motor spin-up e.g. because of large propellers. + 0 + 10 + s + Thrust curve in Manual Mode This parameter defines how the throttle stick input is mapped to commanded thrust in Manual/Stabilized flight mode. In case the default is used ('Rescale to hover thrust'), the stick input is linearly rescaled, such that a centered stick corresponds to the hover throttle (see MPC_THR_HOVER). Select 'No Rescale' to directly map the stick 1:1 to the output. This can be useful in case the hover thrust is very low and the default would lead to too much distortion (e.g. if hover thrust is set to 20%, 80% of the upper thrust range is squeezed into the upper half of the stick range). Note: in case MPC_THR_HOVER is set to 50%, the modes 0 and 1 are the same. @@ -8708,15 +8708,6 @@ is less than 50% of this value Motor 4 Mapping - - - Interval of one subscriber in the example in ms - ms - - - Float Demonstration Parameter in the Example - - RGB Led brightness limit @@ -8789,7 +8780,7 @@ is less than 50% of this value TELEM2 as companion computer link (deprecated) - This parameter is deprecated. Do not change it, use the more generic serial configuration parameters instead. + This parameter is deprecated and will be removed after 1.9.0. Use the generic serial configuration parameters instead (e.g. MAV_0_CONFIG, MAV_0_MODE, etc.). 0 6460800 true diff --git a/src/FlightMap/FlightMap.qml b/src/FlightMap/FlightMap.qml index 635acab5fe063308633564e922362e8288b412ee..568b20f33bf724ca2b3896e2a1d0ce4d2b513ad0 100644 --- a/src/FlightMap/FlightMap.qml +++ b/src/FlightMap/FlightMap.qml @@ -35,6 +35,7 @@ Map { property string mapName: 'defaultMap' property bool isSatelliteMap: activeMapType.name.indexOf("Satellite") > -1 || activeMapType.name.indexOf("Hybrid") > -1 property var gcsPosition: QGroundControl.qgcPositionManger.gcsPosition + property var gcsHeading: QGroundControl.qgcPositionManger.gcsHeading property bool userPanned: false ///< true: the user has manually panned the map property bool allowGCSLocationCenter: false ///< true: map will center/zoom to gcs location one time property bool allowVehicleLocationCenter: false ///< true: map will center/zoom to vehicle location one time @@ -134,12 +135,18 @@ Map { coordinate: gcsPosition sourceItem: Image { - source: "/res/QGCLogoFull" + id: mapItemImage + source: isNaN(gcsHeading) ? "/res/QGCLogoFull" : "/res/QGCLogoArrow" mipmap: true antialiasing: true fillMode: Image.PreserveAspectFit - height: ScreenTools.defaultFontPixelHeight * 1.75 + height: ScreenTools.defaultFontPixelHeight * (isNaN(gcsHeading) ? 1.75 : 2.5 ) sourceSize.height: height + transform: Rotation { + origin.x: mapItemImage.width / 2 + origin.y: mapItemImage.height / 2 + angle: isNaN(gcsHeading) ? 0 : gcsHeading + } } } } // Map diff --git a/src/FlightMap/Widgets/ValuePageWidget.qml b/src/FlightMap/Widgets/ValuePageWidget.qml index 3a9b21f8e2dfcb5e74e1265e442f561b6eb50406..703dabac3366f8ee65268af7af3b0a0b3dac1d4d 100644 --- a/src/FlightMap/Widgets/ValuePageWidget.qml +++ b/src/FlightMap/Widgets/ValuePageWidget.qml @@ -222,6 +222,7 @@ Column { RowLayout { spacing: _margins + visible: factGroup.getFact(modelData).shortDescription !== "" property string propertyName: factGroupName + "." + modelData diff --git a/src/GPS/CMakeLists.txt b/src/GPS/CMakeLists.txt index 1d3dfab4deff1e78603aff914ee48a0dda7f6127..b72845780581dcb9082ca2af1d96e486c42205af 100644 --- a/src/GPS/CMakeLists.txt +++ b/src/GPS/CMakeLists.txt @@ -5,6 +5,7 @@ add_library(gps Drivers/src/gps_helper.cpp Drivers/src/mtk.cpp Drivers/src/rtcm.cpp + Drivers/src/sbf.cpp Drivers/src/ubx.cpp GPSManager.cc GPSProvider.cc diff --git a/src/GPS/Drivers b/src/GPS/Drivers index 8828fb9ad3a2cad568feac2b46de7d6d3af32ca8..2a4865adc3808687d6c6f550f497a02eb920c382 160000 --- a/src/GPS/Drivers +++ b/src/GPS/Drivers @@ -1 +1 @@ -Subproject commit 8828fb9ad3a2cad568feac2b46de7d6d3af32ca8 +Subproject commit 2a4865adc3808687d6c6f550f497a02eb920c382 diff --git a/src/GPS/GPSManager.cc b/src/GPS/GPSManager.cc index 6c71e0c490adc194941142eb15a7d5e8f3fa4542..4eea19b8e08e476d02598f3b6b0751d75e871f40 100644 --- a/src/GPS/GPSManager.cc +++ b/src/GPS/GPSManager.cc @@ -34,6 +34,9 @@ void GPSManager::connectGPS(const QString& device, const QString& gps_type) if (gps_type.contains("trimble", Qt::CaseInsensitive)) { type = GPSProvider::GPSType::trimble; qCDebug(RTKGPSLog) << "Connecting Trimble device"; + } else if (gps_type.contains("septentrio", Qt::CaseInsensitive)) { + type = GPSProvider::GPSType::septentrio; + qCDebug(RTKGPSLog) << "Connecting Septentrio device"; } else { type = GPSProvider::GPSType::u_blox; qCDebug(RTKGPSLog) << "Connecting U-blox device"; diff --git a/src/GPS/GPSProvider.cc b/src/GPS/GPSProvider.cc index 7f8433efdcc90463b5f7e25ac30fdc8c7f004d75..285f1b269c308e8346da4e19532bed2ff43db1df 100644 --- a/src/GPS/GPSProvider.cc +++ b/src/GPS/GPSProvider.cc @@ -18,6 +18,7 @@ #include #include "Drivers/src/ubx.h" +#include "Drivers/src/sbf.h" #include "Drivers/src/ashtech.h" #include "Drivers/src/base_station.h" #include "definitions.h" @@ -81,6 +82,9 @@ void GPSProvider::run() if (_type == GPSType::trimble) { gpsDriver = new GPSDriverAshtech(&callbackEntry, this, &_reportGpsPos, _pReportSatInfo); baudrate = 115200; + } else if (_type == GPSType::septentrio) { + gpsDriver = new GPSDriverSBF(&callbackEntry, this, &_reportGpsPos, _pReportSatInfo, 5); + baudrate = 0; // auto-configure } else { gpsDriver = new GPSDriverUBX(GPSDriverUBX::Interface::UART, &callbackEntry, this, &_reportGpsPos, _pReportSatInfo); baudrate = 0; // auto-configure diff --git a/src/GPS/GPSProvider.h b/src/GPS/GPSProvider.h index eabd08847e4eeb1bb25a0d3a54fc2b10826acadc..56e8d30b83ece9240bbf87ce142e49db34c662db 100644 --- a/src/GPS/GPSProvider.h +++ b/src/GPS/GPSProvider.h @@ -32,7 +32,8 @@ public: enum class GPSType { u_blox, - trimble + trimble, + septentrio }; GPSProvider(const QString& device, diff --git a/src/GPS/definitions.h b/src/GPS/definitions.h index 63fd2c2b100a1ae34a43f1eceb1dd25a30d23468..92675742c78c2fefe208d96ebd74a5acbf2bf05f 100644 --- a/src/GPS/definitions.h +++ b/src/GPS/definitions.h @@ -50,6 +50,8 @@ #include "vehicle_gps_position.h" #include "satellite_info.h" +#define M_DEG_TO_RAD (M_PI / 180.0) +#define M_RAD_TO_DEG (180.0 / M_PI) #define M_DEG_TO_RAD_F 0.01745329251994f #define M_RAD_TO_DEG_F 57.2957795130823f @@ -61,11 +63,10 @@ public: static void usleep(unsigned long usecs) { QThread::usleep(usecs); } }; -static inline void usleep(unsigned long usecs) { +static inline void gps_usleep(unsigned long usecs) { Sleeper::usleep(usecs); } - typedef uint64_t gps_abstime; #include diff --git a/src/Joystick/Joystick.cc b/src/Joystick/Joystick.cc index 6249995d1926c55dbd1a951158859ff886896898..c8d404ec4b5b4665f59a547d158446f99fa155a1 100644 --- a/src/Joystick/Joystick.cc +++ b/src/Joystick/Joystick.cc @@ -71,7 +71,7 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC , _rgCalibration(nullptr) , _rgButtonValues(nullptr) , _lastButtonBits(0) - , _throttleMode(ThrottleModeCenterZero) + , _throttleMode(ThrottleModeDownZero) , _negativeThrust(false) , _exponential(0) , _accumulator(false) @@ -140,7 +140,7 @@ void Joystick::_setDefaultCalibration(void) { _deadband = false; _circleCorrection = false; _frequency = 25.0f; - _throttleMode = ThrottleModeCenterZero; + _throttleMode = ThrottleModeDownZero; _calibrated = true; _saveSettings(); @@ -207,7 +207,7 @@ void Joystick::_loadSettings(void) _circleCorrection = settings.value(_circleCorrectionSettingsKey, false).toBool(); _frequency = settings.value(_frequencySettingsKey, 25.0f).toFloat(); - _throttleMode = (ThrottleMode_t)settings.value(_throttleModeSettingsKey, ThrottleModeCenterZero).toInt(&convertOk); + _throttleMode = (ThrottleMode_t)settings.value(_throttleModeSettingsKey, ThrottleModeDownZero).toInt(&convertOk); badSettings |= !convertOk; qCDebug(JoystickLog) << "_loadSettings calibrated:txmode:throttlemode:exponential:deadband:badsettings" << _calibrated << _transmitterMode << _throttleMode << _exponential << _deadband << badSettings; diff --git a/src/KMLFileHelper.cc b/src/KMLFileHelper.cc index b37c4e3fb033977b2e1f33dd7047739c3d159011..f6f2a0718ea76d9e14594490ad2547c41607347d 100644 --- a/src/KMLFileHelper.cc +++ b/src/KMLFileHelper.cc @@ -100,7 +100,7 @@ bool KMLFileHelper::loadPolygonFromFile(const QString& kmlFile, QListfirmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_SET_CAMERA_MODE); + return _specifyCameraMode || _vehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_SET_CAMERA_MODE); } void CameraSection::_dirtyIfSpecified(void) diff --git a/src/MissionManager/ComplexMissionItem.h b/src/MissionManager/ComplexMissionItem.h index 66209491ae760cf1755ff3b85a90d1ca19023d1f..71046d1d47d2508047f61a4927b846d723c2bb8d 100644 --- a/src/MissionManager/ComplexMissionItem.h +++ b/src/MissionManager/ComplexMissionItem.h @@ -44,10 +44,6 @@ public: /// This mission item attribute specifies the type of the complex item. static const char* jsonComplexItemTypeKey; - // Overrides from VisualMissionItem - double additionalTimeDelay(void) const final { return 0; } - - signals: void complexDistanceChanged (void); void boundingCubeChanged (void); diff --git a/src/MissionManager/CorridorScanComplexItem.cc b/src/MissionManager/CorridorScanComplexItem.cc index 7dcfec119f5553f40d8d7cb333f2113b6835eae2..2d165d16e1af03a5a6447055dd9f9412a8e3b325 100644 --- a/src/MissionManager/CorridorScanComplexItem.cc +++ b/src/MissionManager/CorridorScanComplexItem.cc @@ -124,10 +124,14 @@ bool CorridorScanComplexItem::load(const QJsonObject& complexObject, int sequenc _entryPoint = complexObject[_jsonEntryPointKey].toInt(); - _rebuildTransects(); - _ignoreRecalc = false; + _recalcComplexDistance(); + if (_cameraShots == 0) { + // Shot count was possibly not available from plan file + _recalcCameraShots(); + } + return true; } @@ -461,14 +465,17 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void) } } -void CorridorScanComplexItem::_rebuildTransectsPhase2(void) +void CorridorScanComplexItem::_recalcComplexDistance(void) { - // Calculate distance flown for complex item _complexDistance = 0; for (int i=0; i<_visualTransectPoints.count() - 1; i++) { _complexDistance += _visualTransectPoints[i].value().distanceTo(_visualTransectPoints[i+1].value()); } + emit complexDistanceChanged(); +} +void CorridorScanComplexItem::_recalcCameraShots(void) +{ double triggerDistance = _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble(); if (triggerDistance == 0) { _cameraShots = 0; @@ -480,14 +487,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase2(void) _cameraShots = singleTransectImageCount * _transectCount(); } } - - _coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value() : QGeoCoordinate(); - _exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value() : QGeoCoordinate(); - emit cameraShotsChanged(); - emit complexDistanceChanged(); - emit coordinateChanged(_coordinate); - emit exitCoordinateChanged(_exitCoordinate); } bool CorridorScanComplexItem::readyForSave(void) const diff --git a/src/MissionManager/CorridorScanComplexItem.h b/src/MissionManager/CorridorScanComplexItem.h index a5fe2cab8acee6a353cd838c2862545caa04bc86..d2b9006489de5ec7927f4f3f71e10c4b3c58b497 100644 --- a/src/MissionManager/CorridorScanComplexItem.h +++ b/src/MissionManager/CorridorScanComplexItem.h @@ -52,6 +52,7 @@ public: QString commandName (void) const final { return tr("Corridor Scan"); } QString abbreviation (void) const final { return tr("C"); } bool readyForSave (void) const; + double additionalTimeDelay (void) const final { return 0; } static const char* jsonComplexItemTypeValue; @@ -64,7 +65,8 @@ private slots: // Overrides from TransectStyleComplexItem void _rebuildTransectsPhase1 (void) final; - void _rebuildTransectsPhase2 (void) final; + void _recalcComplexDistance (void) final; + void _recalcCameraShots (void) final; private: int _transectCount (void) const; diff --git a/src/MissionManager/FWLandingPattern.FactMetaData.json b/src/MissionManager/FWLandingPattern.FactMetaData.json index 5605343e594a4341f131e76b659b7013ea4ba92c..1970cdbdf99856e0296c60f3f166c080af44ed3f 100644 --- a/src/MissionManager/FWLandingPattern.FactMetaData.json +++ b/src/MissionManager/FWLandingPattern.FactMetaData.json @@ -51,7 +51,13 @@ "min": 0.1, "max": 90, "decimalPlaces": 1, - "defaultValue": 12.0 + "defaultValue": 6.0 +}, +{ + "name": "ValueSetIsDistance", + "shortDescription": "Value controller loiter point is distance", + "type": "bool", + "defaultValue": false }, { "name": "StopTakingPhotos", diff --git a/src/MissionManager/FWLandingPatternTest.cc b/src/MissionManager/FWLandingPatternTest.cc index 5d8bec72181593928b94d0baed2cb27fa71af0a3..aa4399e5abb1d9e06bc4ec3c147af551717e58ea 100644 --- a/src/MissionManager/FWLandingPatternTest.cc +++ b/src/MissionManager/FWLandingPatternTest.cc @@ -149,7 +149,8 @@ void FWLandingPatternTest::_testDirty(void) << _fwItem->landingDistance() << _fwItem->glideSlope() << _fwItem->stopTakingPhotos() - << _fwItem->stopTakingVideo(); + << _fwItem->stopTakingVideo() + << _fwItem->valueSetIsDistance(); for(Fact* fact: rgFacts) { qDebug() << fact->name(); QVERIFY(!_fwItem->dirty()); @@ -167,8 +168,7 @@ void FWLandingPatternTest::_testDirty(void) // These bool properties should set dirty when changed QList rgBoolNames; - rgBoolNames << "valueSetIsDistance" - << "loiterClockwise" + rgBoolNames << "loiterClockwise" << "altitudesAreRelative"; const QMetaObject* metaObject = _fwItem->metaObject(); for(const char* boolName: rgBoolNames) { @@ -223,16 +223,16 @@ void FWLandingPatternTest::_validateItem(FixedWingLandingComplexItem* newItem) QVERIFY(fuzzyCompareLatLon(newItem->loiterTangentCoordinate(), _fwItem->loiterTangentCoordinate())); QVERIFY(fuzzyCompareLatLon(newItem->landingCoordinate(), _fwItem->landingCoordinate())); - QCOMPARE(newItem->stopTakingPhotos()->rawValue().toBool(), _fwItem->stopTakingPhotos()->rawValue().toBool()); - QCOMPARE(newItem->stopTakingVideo()->rawValue().toBool(), _fwItem->stopTakingVideo()->rawValue().toBool()); - QCOMPARE(newItem->loiterAltitude()->rawValue().toInt(), _fwItem->loiterAltitude()->rawValue().toInt()); - QCOMPARE(newItem->loiterRadius()->rawValue().toInt(), _fwItem->loiterRadius()->rawValue().toInt()); - QCOMPARE(newItem->landingAltitude()->rawValue().toInt(), _fwItem->landingAltitude()->rawValue().toInt()); - QCOMPARE(newItem->landingHeading()->rawValue().toInt(), _fwItem->landingHeading()->rawValue().toInt()); - QCOMPARE(newItem->landingDistance()->rawValue().toInt(), _fwItem->landingDistance()->rawValue().toInt()); - QCOMPARE(newItem->glideSlope()->rawValue().toInt(), _fwItem->glideSlope()->rawValue().toInt()); - QCOMPARE(newItem->_valueSetIsDistance, _fwItem->_valueSetIsDistance); - QCOMPARE(newItem->_loiterClockwise, _fwItem->_loiterClockwise); - QCOMPARE(newItem->_altitudesAreRelative, _fwItem->_altitudesAreRelative); - QCOMPARE(newItem->_landingCoordSet, _fwItem->_landingCoordSet); + QCOMPARE(newItem->stopTakingPhotos()->rawValue().toBool(), _fwItem->stopTakingPhotos()->rawValue().toBool()); + QCOMPARE(newItem->stopTakingVideo()->rawValue().toBool(), _fwItem->stopTakingVideo()->rawValue().toBool()); + QCOMPARE(newItem->loiterAltitude()->rawValue().toInt(), _fwItem->loiterAltitude()->rawValue().toInt()); + QCOMPARE(newItem->loiterRadius()->rawValue().toInt(), _fwItem->loiterRadius()->rawValue().toInt()); + QCOMPARE(newItem->landingAltitude()->rawValue().toInt(), _fwItem->landingAltitude()->rawValue().toInt()); + QCOMPARE(newItem->landingHeading()->rawValue().toInt(), _fwItem->landingHeading()->rawValue().toInt()); + QCOMPARE(newItem->landingDistance()->rawValue().toInt(), _fwItem->landingDistance()->rawValue().toInt()); + QCOMPARE(newItem->glideSlope()->rawValue().toInt(), _fwItem->glideSlope()->rawValue().toInt()); + QCOMPARE(newItem->valueSetIsDistance()->rawValue().toBool(), _fwItem->valueSetIsDistance()->rawValue().toBool()); + QCOMPARE(newItem->_loiterClockwise, _fwItem->_loiterClockwise); + QCOMPARE(newItem->_altitudesAreRelative, _fwItem->_altitudesAreRelative); + QCOMPARE(newItem->_landingCoordSet, _fwItem->_landingCoordSet); } diff --git a/src/MissionManager/FixedWingLandingComplexItem.cc b/src/MissionManager/FixedWingLandingComplexItem.cc index 813205af6c6bf11a3d9caf4a7a2d500d0d1794ec..db3ad990abe4aa4318b89a4eca11b1b112a89386 100644 --- a/src/MissionManager/FixedWingLandingComplexItem.cc +++ b/src/MissionManager/FixedWingLandingComplexItem.cc @@ -29,6 +29,7 @@ const char* FixedWingLandingComplexItem::landingAltitudeName = "LandingAlti const char* FixedWingLandingComplexItem::glideSlopeName = "GlideSlope"; const char* FixedWingLandingComplexItem::stopTakingPhotosName = "StopTakingPhotos"; const char* FixedWingLandingComplexItem::stopTakingVideoName = "StopTakingVideo"; +const char* FixedWingLandingComplexItem::valueSetIsDistanceName = "ValueSetIsDistance"; const char* FixedWingLandingComplexItem::_jsonLoiterCoordinateKey = "loiterCoordinate"; const char* FixedWingLandingComplexItem::_jsonLoiterRadiusKey = "loiterRadius"; @@ -59,9 +60,9 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, bool , _glideSlopeFact (settingsGroup, _metaDataMap[glideSlopeName]) , _stopTakingPhotosFact (settingsGroup, _metaDataMap[stopTakingPhotosName]) , _stopTakingVideoFact (settingsGroup, _metaDataMap[stopTakingVideoName]) + , _valueSetIsDistanceFact (settingsGroup, _metaDataMap[valueSetIsDistanceName]) , _loiterClockwise (true) , _altitudesAreRelative (true) - , _valueSetIsDistance (true) { _editorQml = "qrc:/qml/FWLandingPatternEditor.qml"; @@ -89,6 +90,7 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, bool connect(&_loiterRadiusFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_setDirty); connect(&_stopTakingPhotosFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_setDirty); connect(&_stopTakingVideoFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_setDirty); + connect(&_valueSetIsDistanceFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_setDirty); connect(this, &FixedWingLandingComplexItem::loiterCoordinateChanged, this, &FixedWingLandingComplexItem::_setDirty); connect(this, &FixedWingLandingComplexItem::landingCoordinateChanged, this, &FixedWingLandingComplexItem::_setDirty); connect(this, &FixedWingLandingComplexItem::loiterClockwiseChanged, this, &FixedWingLandingComplexItem::_setDirty); @@ -97,6 +99,13 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, bool connect(this, &FixedWingLandingComplexItem::altitudesAreRelativeChanged, this, &FixedWingLandingComplexItem::coordinateHasRelativeAltitudeChanged); connect(this, &FixedWingLandingComplexItem::altitudesAreRelativeChanged, this, &FixedWingLandingComplexItem::exitCoordinateHasRelativeAltitudeChanged); + + if (_valueSetIsDistanceFact.rawValue().toBool()) { + _recalcFromHeadingAndDistanceChange(); + } else { + _glideSlopeChanged(); + } + setDirty(false); } int FixedWingLandingComplexItem::lastSequenceNumber(void) const @@ -142,7 +151,7 @@ void FixedWingLandingComplexItem::save(QJsonArray& missionItems) saveObject[_jsonStopTakingVideoKey] = _stopTakingVideoFact.rawValue().toBool(); saveObject[_jsonLoiterClockwiseKey] = _loiterClockwise; saveObject[_jsonAltitudesAreRelativeKey] = _altitudesAreRelative; - saveObject[_jsonValueSetIsDistanceKey] = _valueSetIsDistance; + saveObject[_jsonValueSetIsDistanceKey] = _valueSetIsDistanceFact.rawValue().toBool(); missionItems.append(saveObject); } @@ -204,7 +213,7 @@ bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int seq } else { _altitudesAreRelative = loiterAltitudeRelative; } - _valueSetIsDistance = true; + _valueSetIsDistanceFact.setRawValue(true); } else if (version == 2) { QList v2KeyInfoList = { { _jsonAltitudesAreRelativeKey, QJsonValue::Bool, true }, @@ -216,7 +225,7 @@ bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int seq } _altitudesAreRelative = complexObject[_jsonAltitudesAreRelativeKey].toBool(); - _valueSetIsDistance = complexObject[_jsonValueSetIsDistanceKey].toBool(); + _valueSetIsDistanceFact.setRawValue(complexObject[_jsonValueSetIsDistanceKey].toBool()); } else { errorString = tr("%1 complex item version %2 not supported").arg(jsonComplexItemTypeValue).arg(version); _ignoreRecalcSignals = false; diff --git a/src/MissionManager/FixedWingLandingComplexItem.h b/src/MissionManager/FixedWingLandingComplexItem.h index 0b0af9d804a24fbab4000cc5e43d272ab2862528..9f81b56954c7f9cd53d9654ec6f38287eb0777d3 100644 --- a/src/MissionManager/FixedWingLandingComplexItem.h +++ b/src/MissionManager/FixedWingLandingComplexItem.h @@ -30,7 +30,7 @@ public: Q_PROPERTY(Fact* loiterRadius READ loiterRadius CONSTANT) Q_PROPERTY(Fact* landingAltitude READ landingAltitude CONSTANT) Q_PROPERTY(Fact* landingHeading READ landingHeading CONSTANT) - Q_PROPERTY(bool valueSetIsDistance MEMBER _valueSetIsDistance NOTIFY valueSetIsDistanceChanged) + Q_PROPERTY(Fact* valueSetIsDistance READ valueSetIsDistance CONSTANT) Q_PROPERTY(Fact* landingDistance READ landingDistance CONSTANT) Q_PROPERTY(Fact* glideSlope READ glideSlope CONSTANT) Q_PROPERTY(bool loiterClockwise MEMBER _loiterClockwise NOTIFY loiterClockwiseChanged) @@ -50,6 +50,7 @@ public: Fact* glideSlope (void) { return &_glideSlopeFact; } Fact* stopTakingPhotos (void) { return &_stopTakingPhotosFact; } Fact* stopTakingVideo (void) { return &_stopTakingVideoFact; } + Fact* valueSetIsDistance (void) { return &_valueSetIsDistanceFact; } QGeoCoordinate landingCoordinate (void) const { return _landingCoordinate; } QGeoCoordinate loiterCoordinate (void) const { return _loiterCoordinate; } QGeoCoordinate loiterTangentCoordinate (void) const { return _loiterTangentCoordinate; } @@ -90,6 +91,7 @@ public: double specifiedGimbalPitch (void) final { return std::numeric_limits::quiet_NaN(); } void appendMissionItems (QList& items, QObject* missionItemParent) final; void applyNewAltitude (double newAltitude) final; + double additionalTimeDelay (void) const final { return 0; } bool coordinateHasRelativeAltitude (void) const final { return _altitudesAreRelative; } bool exitCoordinateHasRelativeAltitude (void) const final { return _altitudesAreRelative; } @@ -102,6 +104,7 @@ public: static const char* jsonComplexItemTypeValue; + static const char* settingsGroup; static const char* loiterToLandDistanceName; static const char* loiterAltitudeName; static const char* loiterRadiusName; @@ -110,6 +113,7 @@ public: static const char* glideSlopeName; static const char* stopTakingPhotosName; static const char* stopTakingVideoName; + static const char* valueSetIsDistanceName; signals: void loiterCoordinateChanged (QGeoCoordinate coordinate); @@ -154,12 +158,11 @@ private: Fact _glideSlopeFact; Fact _stopTakingPhotosFact; Fact _stopTakingVideoFact; + Fact _valueSetIsDistanceFact; bool _loiterClockwise; bool _altitudesAreRelative; - bool _valueSetIsDistance; - static const char* settingsGroup; static const char* _jsonLoiterCoordinateKey; static const char* _jsonLoiterRadiusKey; static const char* _jsonLoiterClockwiseKey; diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 90bebf479071fd73593f1c01c367a7eece4486fa..c1e3fd48ea33552415dd483a7f402be2df20d2df 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -56,9 +56,9 @@ const char* MissionController::_jsonMavAutopilotKey = "MAV_AUTOPILOT"; const int MissionController::_missionFileVersion = 2; -const QString MissionController::patternFWLandingName (tr("Fixed Wing Landing")); -const QString MissionController::patternStructureScanName (tr("Structure Scan")); -const QString MissionController::patternCorridorScanName (tr("Corridor Scan")); +const QString MissionController::patternFWLandingName (QT_TRANSLATE_NOOP("MissionController", "Fixed Wing Landing")); +const QString MissionController::patternStructureScanName (QT_TRANSLATE_NOOP("MissionController", "Structure Scan")); +const QString MissionController::patternCorridorScanName (QT_TRANSLATE_NOOP("MissionController", "Corridor Scan")); MissionController::MissionController(PlanMasterController* masterController, QObject *parent) : PlanElementController (masterController, parent) @@ -226,7 +226,7 @@ void MissionController::_warnIfTerrainFrameUsed(void) { for (int i=1; i<_visualItems->count(); i++) { SimpleMissionItem* simpleItem = qobject_cast(_visualItems->get(i)); - if (simpleItem && simpleItem->altitudeMode() == SimpleMissionItem::AltitudeTerrainFrame) { + if (simpleItem && simpleItem->altitudeMode() == QGroundControlQmlGlobal::AltitudeModeTerrainFrame) { qgcApp()->showMessage(tr("Warning: You are using MAV_FRAME_GLOBAL_TERRAIN_ALT in a mission. %1 does not support sending terrain tiles to vehicle.").arg(qgcApp()->applicationName())); break; } @@ -371,7 +371,7 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i) if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) { newItem->altitude()->setRawValue(prevAltitude); - newItem->setAltitudeMode(static_cast(prevAltitudeMode)); + newItem->setAltitudeMode(static_cast(prevAltitudeMode)); } } newItem->setMissionFlightStatus(_missionFlightStatus); @@ -399,7 +399,7 @@ int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i) if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) { newItem->altitude()->setRawValue(prevAltitude); - newItem->setAltitudeMode(static_cast(prevAltitudeMode)); + newItem->setAltitudeMode(static_cast(prevAltitudeMode)); } _visualItems->insert(i, newItem); diff --git a/src/MissionManager/MissionSettingsItem.h b/src/MissionManager/MissionSettingsItem.h index 2a031217578ecdc357eef70e1ee778e6ab1336bc..935cade386139205839ffd1b49258fa32ccf6e31 100644 --- a/src/MissionManager/MissionSettingsItem.h +++ b/src/MissionManager/MissionSettingsItem.h @@ -77,6 +77,7 @@ public: void appendMissionItems (QList& items, QObject* missionItemParent) final; void applyNewAltitude (double newAltitude) final { Q_UNUSED(newAltitude); /* no action */ } double specifiedFlightSpeed (void) final; + double additionalTimeDelay (void) const final { return 0; } bool coordinateHasRelativeAltitude (void) const final { return false; } bool exitCoordinateHasRelativeAltitude (void) const final { return false; } diff --git a/src/MissionManager/QGCMapPolygon.cc b/src/MissionManager/QGCMapPolygon.cc index 8d0e3ca6a4552157fc7efe81a1aa209b3bfc077b..d3111ac123ba9e758a532a5267865319b10cca15 100644 --- a/src/MissionManager/QGCMapPolygon.cc +++ b/src/MissionManager/QGCMapPolygon.cc @@ -94,7 +94,7 @@ void QGCMapPolygon::adjustVertex(int vertexIndex, const QGeoCoordinate coordinat _polygonPath[vertexIndex] = QVariant::fromValue(coordinate); _polygonModel.value(vertexIndex)->setCoordinate(coordinate); if (!_centerDrag) { - // When dragging center we don't signal path changed until add vertices are updated + // When dragging center we don't signal path changed until all vertices are updated emit pathChanged(); } setDirty(true); @@ -340,7 +340,7 @@ void QGCMapPolygon::setCenter(QGeoCoordinate newCenter) } if (_centerDrag) { - // When center dragging signals are delayed until all vertices are updated + // When center dragging, signals from adjustVertext are not sent. So we need to signal here when all adjusting is complete. emit pathChanged(); } @@ -486,3 +486,30 @@ double QGCMapPolygon::area(void) const } return 0.5 * fabs(coveredArea); } + +void QGCMapPolygon::verifyClockwiseWinding(void) +{ + if (_polygonPath.count() <= 2) { + return; + } + + double sum = 0; + for (int i=0; i<_polygonPath.count(); i++) { + QGeoCoordinate coord1 = _polygonPath[i].value(); + QGeoCoordinate coord2 = (i == _polygonPath.count() - 1) ? _polygonPath[0].value() : _polygonPath[i+1].value(); + + sum += (coord2.longitude() - coord1.longitude()) * (coord2.latitude() + coord1.latitude()); + } + + if (sum < 0.0) { + // Winding is counter-clockwise and needs reversal + + QList rgReversed; + for (const QVariant& varCoord: _polygonPath) { + rgReversed.prepend(varCoord.value()); + } + + clear(); + appendVertices(rgReversed); + } +} diff --git a/src/MissionManager/QGCMapPolygon.h b/src/MissionManager/QGCMapPolygon.h index 68dc0145e98451078387058575ebed43bfa6a0a9..d112a58d2ef0f86c35ae55783a33a0d1d7a54023 100644 --- a/src/MissionManager/QGCMapPolygon.h +++ b/src/MissionManager/QGCMapPolygon.h @@ -66,6 +66,9 @@ public: /// Returns the QGeoCoordinate for the vertex specified Q_INVOKABLE QGeoCoordinate vertexCoordinate(int vertex) const; + /// Adjust polygon winding order to be clockwise (if needed) + Q_INVOKABLE void verifyClockwiseWinding(void); + /// Saves the polygon to the json object. /// @param json Json object to save to void saveToJson(QJsonObject& json); diff --git a/src/MissionManager/QGCMapPolygonVisuals.qml b/src/MissionManager/QGCMapPolygonVisuals.qml index c4f9da4a8afc54025de0754e8f9d015104795ad1..8c9a093fb6bf20cc6ed38f7c22ca368f642b1e3c 100644 --- a/src/MissionManager/QGCMapPolygonVisuals.qml +++ b/src/MissionManager/QGCMapPolygonVisuals.qml @@ -344,6 +344,7 @@ Item { mapControl: _root.mapControl z: _zorderDragHandle visible: !_circle + onDragStop: mapPolygon.verifyClockwiseWinding() property int polygonVertex @@ -466,7 +467,10 @@ Item { EditPositionDialog { coordinate: mapPolygon.vertexCoordinate(menu._editingVertexIndex) - onCoordinateChanged: mapPolygon.adjustVertex(menu._editingVertexIndex, coordinate) + onCoordinateChanged: { + mapPolygon.adjustVertex(menu._editingVertexIndex, coordinate) + mapPolygon.verifyClockwiseWinding() + } } } diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc index 40ca7d04e159647b2ac9fcd26a325ed04c44e88a..74a9e7f5b6da288e17aed91e53c8c5485a74dbf6 100644 --- a/src/MissionManager/SimpleMissionItem.cc +++ b/src/MissionManager/SimpleMissionItem.cc @@ -56,11 +56,11 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* pa , _rawEdit (false) , _dirty (false) , _ignoreDirtyChangeSignals (false) - , _speedSection (NULL) - , _cameraSection (NULL) + , _speedSection (nullptr) + , _cameraSection (nullptr) , _commandTree (qgcApp()->toolbox()->missionCommandTree()) , _supportedCommandFact (0, "Command:", FactMetaData::valueTypeUint32) - , _altitudeMode (AltitudeRelative) + , _altitudeMode (QGroundControlQmlGlobal::AltitudeModeRelative) , _altitudeFact (0, "Altitude", FactMetaData::valueTypeDouble) , _amslAltAboveTerrainFact (0, "Alt above terrain", FactMetaData::valueTypeDouble) , _param1MetaData (FactMetaData::valueTypeDouble) @@ -90,8 +90,8 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, const Missi , _rawEdit (false) , _dirty (false) , _ignoreDirtyChangeSignals (false) - , _speedSection (NULL) - , _cameraSection (NULL) + , _speedSection (nullptr) + , _cameraSection (nullptr) , _commandTree (qgcApp()->toolbox()->missionCommandTree()) , _supportedCommandFact (0, "Command:", FactMetaData::valueTypeUint32) , _altitudeFact (0, "Altitude", FactMetaData::valueTypeDouble) @@ -108,16 +108,16 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, const Missi _editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml"); struct MavFrame2AltMode_s { - MAV_FRAME mavFrame; - AltitudeMode altMode; + MAV_FRAME mavFrame; + QGroundControlQmlGlobal::AltitudeMode altMode; }; const struct MavFrame2AltMode_s rgMavFrame2AltMode[] = { - { MAV_FRAME_GLOBAL_TERRAIN_ALT, AltitudeTerrainFrame }, - { MAV_FRAME_GLOBAL, AltitudeAbsolute }, - { MAV_FRAME_GLOBAL_RELATIVE_ALT, AltitudeRelative }, + { MAV_FRAME_GLOBAL_TERRAIN_ALT, QGroundControlQmlGlobal::AltitudeModeTerrainFrame }, + { MAV_FRAME_GLOBAL, QGroundControlQmlGlobal::AltitudeModeAbsolute }, + { MAV_FRAME_GLOBAL_RELATIVE_ALT, QGroundControlQmlGlobal::AltitudeModeRelative }, }; - _altitudeMode = AltitudeRelative; + _altitudeMode = QGroundControlQmlGlobal::AltitudeModeRelative; for (size_t i=0; isupportsTerrainFrame(); } @@ -84,7 +76,7 @@ public: QmlObjectListModel* comboboxFacts (void) { return &_comboboxFacts; } void setRawEdit(bool rawEdit); - void setAltitudeMode(AltitudeMode altitudeMode); + void setAltitudeMode(QGroundControlQmlGlobal::AltitudeMode altitudeMode); void setCommandByIndex(int index); @@ -178,9 +170,9 @@ private: Fact _supportedCommandFact; - AltitudeMode _altitudeMode; - Fact _altitudeFact; - Fact _amslAltAboveTerrainFact; + QGroundControlQmlGlobal::AltitudeMode _altitudeMode; + Fact _altitudeFact; + Fact _amslAltAboveTerrainFact; QmlObjectListModel _textFieldFacts; QmlObjectListModel _nanFacts; diff --git a/src/MissionManager/SimpleMissionItemTest.cc b/src/MissionManager/SimpleMissionItemTest.cc index 9fd0828e9300941c0e3af3446d23c92f7d5a057d..c3948f16d01722722389f5071d93c5ca996189eb 100644 --- a/src/MissionManager/SimpleMissionItemTest.cc +++ b/src/MissionManager/SimpleMissionItemTest.cc @@ -52,17 +52,17 @@ const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesDoJ const SimpleMissionItemTest::ItemExpected_t SimpleMissionItemTest::_rgItemExpected[] = { // Text field facts count Fact Values Altitude Altitude Mode - { sizeof(SimpleMissionItemTest::_rgFactValuesWaypoint)/sizeof(SimpleMissionItemTest::_rgFactValuesWaypoint[0]), SimpleMissionItemTest::_rgFactValuesWaypoint, 70.1234567, SimpleMissionItem::AltitudeRelative }, - { sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim[0]), SimpleMissionItemTest::_rgFactValuesLoiterUnlim, 70.1234567, SimpleMissionItem::AltitudeAbsolute }, - { sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTurns)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTurns[0]), SimpleMissionItemTest::_rgFactValuesLoiterTurns, 70.1234567, SimpleMissionItem::AltitudeRelative }, - { sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime[0]), SimpleMissionItemTest::_rgFactValuesLoiterTime, 70.1234567, SimpleMissionItem::AltitudeAbsolute }, - { 0, NULL, 70.1234567, SimpleMissionItem::AltitudeRelative }, - { sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff)/sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff[0]), SimpleMissionItemTest::_rgFactValuesTakeoff, 70.1234567, SimpleMissionItem::AltitudeAbsolute }, - { sizeof(SimpleMissionItemTest::_rgFactValuesDoJump)/sizeof(SimpleMissionItemTest::_rgFactValuesDoJump[0]), SimpleMissionItemTest::_rgFactValuesDoJump, qQNaN(), SimpleMissionItem::AltitudeRelative }, + { sizeof(SimpleMissionItemTest::_rgFactValuesWaypoint)/sizeof(SimpleMissionItemTest::_rgFactValuesWaypoint[0]), SimpleMissionItemTest::_rgFactValuesWaypoint, 70.1234567, QGroundControlQmlGlobal::AltitudeModeRelative }, + { sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim[0]), SimpleMissionItemTest::_rgFactValuesLoiterUnlim, 70.1234567, QGroundControlQmlGlobal::AltitudeModeAbsolute }, + { sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTurns)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTurns[0]), SimpleMissionItemTest::_rgFactValuesLoiterTurns, 70.1234567, QGroundControlQmlGlobal::AltitudeModeRelative }, + { sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime[0]), SimpleMissionItemTest::_rgFactValuesLoiterTime, 70.1234567, QGroundControlQmlGlobal::AltitudeModeAbsolute }, + { 0, nullptr, 70.1234567, QGroundControlQmlGlobal::AltitudeModeRelative }, + { sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff)/sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff[0]), SimpleMissionItemTest::_rgFactValuesTakeoff, 70.1234567, QGroundControlQmlGlobal::AltitudeModeAbsolute }, + { sizeof(SimpleMissionItemTest::_rgFactValuesDoJump)/sizeof(SimpleMissionItemTest::_rgFactValuesDoJump[0]), SimpleMissionItemTest::_rgFactValuesDoJump, qQNaN(), QGroundControlQmlGlobal::AltitudeModeRelative }, }; SimpleMissionItemTest::SimpleMissionItemTest(void) - : _simpleItem(NULL) + : _simpleItem(nullptr) { } @@ -131,7 +131,7 @@ void SimpleMissionItemTest::_testEditorFacts(void) 70.1234567, true, // autoContinue false); // isCurrentItem - SimpleMissionItem simpleMissionItem(vehicle, false /* flyView */, missionItem, NULL); + SimpleMissionItem simpleMissionItem(vehicle, false /* flyView */, missionItem, nullptr); // Validate that the fact values are correctly returned @@ -167,7 +167,7 @@ void SimpleMissionItemTest::_testEditorFacts(void) void SimpleMissionItemTest::_testDefaultValues(void) { - SimpleMissionItem item(_offlineVehicle, false /* flyView */, NULL); + SimpleMissionItem item(_offlineVehicle, false /* flyView */, nullptr); item.missionItem().setCommand(MAV_CMD_NAV_WAYPOINT); item.missionItem().setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT); @@ -225,7 +225,7 @@ void SimpleMissionItemTest::_testSignals(void) QVERIFY(_spyVisualItem->checkOnlySignalByMask(dirtyChangedMask)); _spyVisualItem->clearAllSignals(); - _simpleItem->setAltitudeMode(_simpleItem->altitudeMode() == SimpleMissionItem::AltitudeRelative ? SimpleMissionItem::AltitudeAbsolute : SimpleMissionItem::AltitudeRelative); + _simpleItem->setAltitudeMode(_simpleItem->altitudeMode() == QGroundControlQmlGlobal::AltitudeModeRelative ? QGroundControlQmlGlobal::AltitudeModeAbsolute : QGroundControlQmlGlobal::AltitudeModeRelative); QVERIFY(_spySimpleItem->checkOnlySignalByMask(dirtyChangedMask | friendlyEditAllowedChangedMask | altitudeModeChangedMask | coordinateHasRelativeAltitudeChangedMask)); _spySimpleItem->clearAllSignals(); _spyVisualItem->clearAllSignals(); @@ -312,12 +312,12 @@ void SimpleMissionItemTest::_testAltitudePropogation(void) { // Make sure that changes to altitude propogate to param 7 of the mission item - _simpleItem->setAltitudeMode(SimpleMissionItem::AltitudeRelative); + _simpleItem->setAltitudeMode(QGroundControlQmlGlobal::AltitudeModeRelative); _simpleItem->altitude()->setRawValue(_simpleItem->altitude()->rawValue().toDouble() + 1); QCOMPARE(_simpleItem->altitude()->rawValue().toDouble(), _simpleItem->missionItem().param7()); QCOMPARE(_simpleItem->missionItem().frame(), MAV_FRAME_GLOBAL_RELATIVE_ALT); - _simpleItem->setAltitudeMode(SimpleMissionItem::AltitudeAbsolute); + _simpleItem->setAltitudeMode(QGroundControlQmlGlobal::AltitudeModeAbsolute); _simpleItem->altitude()->setRawValue(_simpleItem->altitude()->rawValue().toDouble() + 1); QCOMPARE(_simpleItem->altitude()->rawValue().toDouble(), _simpleItem->missionItem().param7()); QCOMPARE(_simpleItem->missionItem().frame(), MAV_FRAME_GLOBAL); diff --git a/src/MissionManager/SimpleMissionItemTest.h b/src/MissionManager/SimpleMissionItemTest.h index db67cb4f66ade37a685febc08e8e5502649910d2..19f9afe27dd601dc4a7a804c9cc14f10bd433acc 100644 --- a/src/MissionManager/SimpleMissionItemTest.h +++ b/src/MissionManager/SimpleMissionItemTest.h @@ -74,7 +74,7 @@ private: size_t cFactValues; const FactValue_t* rgFactValues; double altValue; - SimpleMissionItem::AltitudeMode altMode; + QGroundControlQmlGlobal::AltitudeMode altMode; } ItemExpected_t; SimpleMissionItem* _simpleItem; diff --git a/src/MissionManager/StructureScanComplexItem.h b/src/MissionManager/StructureScanComplexItem.h index 5f38be25f6b81c3a2004874ce6db56be9098b170..9b8b09d4c0f88611acee601fa6bb96b9839eee8b 100644 --- a/src/MissionManager/StructureScanComplexItem.h +++ b/src/MissionManager/StructureScanComplexItem.h @@ -84,6 +84,7 @@ public: void appendMissionItems (QList& items, QObject* missionItemParent) final; void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final; void applyNewAltitude (double newAltitude) final; + double additionalTimeDelay (void) const final { return 0; } bool coordinateHasRelativeAltitude (void) const final { return _altitudeRelative; } bool exitCoordinateHasRelativeAltitude (void) const final { return _altitudeRelative; } diff --git a/src/MissionManager/SurveyComplexItem.cc b/src/MissionManager/SurveyComplexItem.cc index 8a0fac3786b69fa41c5ab6894c7ebd99db34e3e6..b26ab892b3e288fa62743c2c7d9bbedb008e9be3 100644 --- a/src/MissionManager/SurveyComplexItem.cc +++ b/src/MissionManager/SurveyComplexItem.cc @@ -144,6 +144,12 @@ bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumbe if (!_loadV4V5(complexObject, sequenceNumber, errorString, version)) { return false; } + + _recalcComplexDistance(); + if (_cameraShots == 0) { + // Shot count was possibly not available from plan file + _recalcCameraShots(); + } } else { // Must be v2 or v3 QJsonObject v3ComplexObject = complexObject; @@ -157,9 +163,10 @@ bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumbe if (!_loadV3(complexObject, sequenceNumber, errorString)) { return false; } - } - _rebuildTransects(); + // V2/3 doesn't include individual items so we need to rebuild manually + _rebuildTransects(); + } return true; } @@ -1384,42 +1391,78 @@ void SurveyComplexItem::_rebuildTransectsFromPolygon(bool refly, const QPolygonF qCDebug(SurveyComplexItemLog) << "_transects.size() " << _transects.size(); } -void SurveyComplexItem::_rebuildTransectsPhase2(void) +void SurveyComplexItem::_recalcComplexDistance(void) { - // Calculate distance flown for complex item _complexDistance = 0; for (int i=0; i<_visualTransectPoints.count() - 1; i++) { _complexDistance += _visualTransectPoints[i].value().distanceTo(_visualTransectPoints[i+1].value()); } + emit complexDistanceChanged(); +} - if (triggerDistance() == 0) { +void SurveyComplexItem::_recalcCameraShots(void) +{ + double triggerDistance = this->triggerDistance(); + + if (triggerDistance == 0) { _cameraShots = 0; } else { if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) { - _cameraShots = qCeil(_complexDistance / triggerDistance()); + _cameraShots = qCeil(_complexDistance / triggerDistance); } else { _cameraShots = 0; - for (const QList& transect: _transects) { - QGeoCoordinate firstCameraCoord, lastCameraCoord; - if (_hasTurnaround()) { - firstCameraCoord = transect[1].coord; - lastCameraCoord = transect[transect.count() - 2].coord; + + if (_loadedMissionItemsParent) { + // We have to do it the hard way based on the mission items themselves + if (hoverAndCaptureEnabled()) { + // Count the number of camera triggers in the mission items + for (const MissionItem* missionItem: _loadedMissionItems) { + _cameraShots += missionItem->command() == MAV_CMD_IMAGE_START_CAPTURE ? 1 : 0; + } } else { - firstCameraCoord = transect.first().coord; - lastCameraCoord = transect.last().coord; + bool waitingForTriggerStop = false; + QGeoCoordinate distanceStartCoord; + QGeoCoordinate distanceEndCoord; + for (const MissionItem* missionItem: _loadedMissionItems) { + if (missionItem->command() == MAV_CMD_NAV_WAYPOINT) { + if (waitingForTriggerStop) { + distanceEndCoord = QGeoCoordinate(missionItem->param5(), missionItem->param6()); + } else { + distanceStartCoord = QGeoCoordinate(missionItem->param5(), missionItem->param6()); + } + } else if (missionItem->command() == MAV_CMD_DO_SET_CAM_TRIGG_DIST) { + if (missionItem->param1() > 0) { + // Trigger start + waitingForTriggerStop = true; + } else { + // Trigger stop + waitingForTriggerStop = false; + _cameraShots += qCeil(distanceEndCoord.distanceTo(distanceStartCoord) / triggerDistance); + distanceStartCoord = QGeoCoordinate(); + distanceEndCoord = QGeoCoordinate(); + } + } + } + + } + } else { + // We have transects available, calc from those + for (const QList& transect: _transects) { + QGeoCoordinate firstCameraCoord, lastCameraCoord; + if (_hasTurnaround() && !hoverAndCaptureEnabled()) { + firstCameraCoord = transect[1].coord; + lastCameraCoord = transect[transect.count() - 2].coord; + } else { + firstCameraCoord = transect.first().coord; + lastCameraCoord = transect.last().coord; + } + _cameraShots += qCeil(firstCameraCoord.distanceTo(lastCameraCoord) / triggerDistance); } - _cameraShots += qCeil(firstCameraCoord.distanceTo(lastCameraCoord) / triggerDistance()); } } } - _coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value() : QGeoCoordinate(); - _exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value() : QGeoCoordinate(); - emit cameraShotsChanged(); - emit complexDistanceChanged(); - emit coordinateChanged(_coordinate); - emit exitCoordinateChanged(_exitCoordinate); } // FIXME: This same exact code is in Corridor Scan. Move to TransectStyleComplex? @@ -1476,3 +1519,16 @@ double SurveyComplexItem::timeBetweenShots(void) { return _cruiseSpeed == 0 ? 0 : triggerDistance() / _cruiseSpeed; } + +double SurveyComplexItem::additionalTimeDelay (void) const +{ + double hoverTime = 0; + + if (hoverAndCaptureEnabled()) { + for (const QList& transect: _transects) { + hoverTime += _hoverAndCaptureDelaySeconds * transect.count(); + } + } + + return hoverTime; +} diff --git a/src/MissionManager/SurveyComplexItem.h b/src/MissionManager/SurveyComplexItem.h index 01248446c647e1650007322e1ee20fa99dd3622b..eda8ef30b5956fa63592b1f51710616bbcb70fa2 100644 --- a/src/MissionManager/SurveyComplexItem.h +++ b/src/MissionManager/SurveyComplexItem.h @@ -52,6 +52,7 @@ public: QString commandName (void) const final { return tr("Survey"); } QString abbreviation (void) const final { return tr("S"); } bool readyForSave (void) const final; + double additionalTimeDelay (void) const final; // Must match json spec for GridEntryLocation enum EntryLocation { @@ -77,8 +78,9 @@ signals: private slots: // Overrides from TransectStyleComplexItem - void _rebuildTransectsPhase1(void) final; - void _rebuildTransectsPhase2(void) final; + void _rebuildTransectsPhase1 (void) final; + void _recalcComplexDistance (void) final; + void _recalcCameraShots (void) final; private: enum CameraTriggerCode { diff --git a/src/MissionManager/TransectStyleComplexItem.cc b/src/MissionManager/TransectStyleComplexItem.cc index d616d75152e8570fe9e384a4eb817b21207a9e87..156818403f047e31ea17807fb6b567ca7f8877f7 100644 --- a/src/MissionManager/TransectStyleComplexItem.cc +++ b/src/MissionManager/TransectStyleComplexItem.cc @@ -35,6 +35,7 @@ const char* TransectStyleComplexItem::_jsonCameraCalcKey = "Cam const char* TransectStyleComplexItem::_jsonVisualTransectPointsKey = "VisualTransectPoints"; const char* TransectStyleComplexItem::_jsonItemsKey = "Items"; const char* TransectStyleComplexItem::_jsonFollowTerrainKey = "FollowTerrain"; +const char* TransectStyleComplexItem::_jsonCameraShotsKey = "CameraShots"; const int TransectStyleComplexItem::_terrainQueryTimeoutMsecs = 1000; @@ -139,6 +140,7 @@ void TransectStyleComplexItem::_save(QJsonObject& complexObject) innerObject[hoverAndCaptureName] = _hoverAndCaptureFact.rawValue().toBool(); innerObject[refly90DegreesName] = _refly90DegreesFact.rawValue().toBool(); innerObject[_jsonFollowTerrainKey] = _followTerrain; + innerObject[_jsonCameraShotsKey] = _cameraShots; if (_followTerrain) { innerObject[terrainAdjustToleranceName] = _terrainAdjustToleranceFact.rawValue().toDouble(); @@ -209,9 +211,10 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString& { hoverAndCaptureName, QJsonValue::Bool, true }, { refly90DegreesName, QJsonValue::Bool, true }, { _jsonCameraCalcKey, QJsonValue::Object, true }, - { _jsonVisualTransectPointsKey, QJsonValue::Array, true }, + { _jsonVisualTransectPointsKey, QJsonValue::Array, true }, { _jsonItemsKey, QJsonValue::Array, true }, { _jsonFollowTerrainKey, QJsonValue::Bool, true }, + { _jsonCameraShotsKey, QJsonValue::Double, false }, // Not required since it was missing from initial implementation }; if (!JsonHelper::validateKeys(innerObject, innerKeyInfoList, errorString)) { return false; @@ -249,6 +252,12 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString& _refly90DegreesFact.setRawValue (innerObject[refly90DegreesName].toBool()); _followTerrain = innerObject[_jsonFollowTerrainKey].toBool(); + // These two keys where not included in initial implementation so they are optional. Without them the values will be + // incorrect when loaded though. + if (innerObject.contains(_jsonCameraShotsKey)) { + _cameraShots = innerObject[_jsonCameraShotsKey].toInt(); + } + if (_followTerrain) { QList followTerrainKeyInfoList = { { terrainAdjustToleranceName, QJsonValue::Double, true }, @@ -394,10 +403,12 @@ void TransectStyleComplexItem::_rebuildTransects(void) emit coordinateChanged(_coordinate); emit exitCoordinateChanged(_exitCoordinate); - _rebuildTransectsPhase2(); + _recalcComplexDistance(); + _recalcCameraShots(); emit lastSequenceNumberChanged(lastSequenceNumber()); emit timeBetweenShotsChanged(); + emit additionalTimeDelayChanged(); } void TransectStyleComplexItem::_queryTransectsPathHeightInfo(void) diff --git a/src/MissionManager/TransectStyleComplexItem.h b/src/MissionManager/TransectStyleComplexItem.h index d392f6ea73e8fda9aa452965b2ada203308a3d82..977f1228e29d464f86cac19df4f6774ecfec87e0 100644 --- a/src/MissionManager/TransectStyleComplexItem.h +++ b/src/MissionManager/TransectStyleComplexItem.h @@ -129,9 +129,6 @@ signals: void followTerrainChanged (bool followTerrain); protected slots: - virtual void _rebuildTransectsPhase1 (void) = 0; ///< Rebuilds the _transects array - virtual void _rebuildTransectsPhase2 (void) = 0; ///< Adjust values associated with _transects array - void _setDirty (void); void _setIfDirty (bool dirty); void _updateCoordinateAltitudes (void); @@ -139,6 +136,10 @@ protected slots: void _rebuildTransects (void); protected: + virtual void _rebuildTransectsPhase1 (void) = 0; ///< Rebuilds the _transects array + virtual void _recalcComplexDistance (void) = 0; + virtual void _recalcCameraShots (void) = 0; + void _save (QJsonObject& saveObject); bool _load (const QJsonObject& complexObject, QString& errorString); void _setExitCoordinate (const QGeoCoordinate& coordinate); @@ -197,6 +198,7 @@ protected: static const char* _jsonVisualTransectPointsKey; static const char* _jsonItemsKey; static const char* _jsonFollowTerrainKey; + static const char* _jsonCameraShotsKey; static const int _terrainQueryTimeoutMsecs; diff --git a/src/MissionManager/TransectStyleComplexItemTest.cc b/src/MissionManager/TransectStyleComplexItemTest.cc index 97242c6e7882a5bcabf8bc89b099860d64ce7753..e2ccd5bd3b289de391971c109faa667ece710660 100644 --- a/src/MissionManager/TransectStyleComplexItemTest.cc +++ b/src/MissionManager/TransectStyleComplexItemTest.cc @@ -115,10 +115,12 @@ void TransectStyleComplexItemTest::_testRebuildTransects(void) // lastSequenceNumberChanged signal _adjustSurveAreaPolygon(); QVERIFY(_transectStyleItem->rebuildTransectsPhase1Called); - QVERIFY(_transectStyleItem->rebuildTransectsPhase2Called); + QVERIFY(_transectStyleItem->recalcCameraShotsCalled); + QVERIFY(_transectStyleItem->recalcComplexDistanceCalled); QVERIFY(_multiSpy->checkSignalsByMask(coveredAreaChangedMask | lastSequenceNumberChangedMask)); _transectStyleItem->rebuildTransectsPhase1Called = false; - _transectStyleItem->rebuildTransectsPhase2Called = false; + _transectStyleItem->recalcCameraShotsCalled = false; + _transectStyleItem->recalcComplexDistanceCalled = false; _transectStyleItem->setDirty(false); _multiSpy->clearAllSignals(); @@ -136,30 +138,36 @@ void TransectStyleComplexItemTest::_testRebuildTransects(void) qDebug() << fact->name(); changeFactValue(fact); QVERIFY(_transectStyleItem->rebuildTransectsPhase1Called); - QVERIFY(_transectStyleItem->rebuildTransectsPhase2Called); + QVERIFY(_transectStyleItem->recalcCameraShotsCalled); + QVERIFY(_transectStyleItem->recalcComplexDistanceCalled); QVERIFY(_multiSpy->checkSignalsByMask(lastSequenceNumberChangedMask)); _transectStyleItem->setDirty(false); _multiSpy->clearAllSignals(); _transectStyleItem->rebuildTransectsPhase1Called = false; - _transectStyleItem->rebuildTransectsPhase2Called = false; + _transectStyleItem->recalcCameraShotsCalled = false; + _transectStyleItem->recalcComplexDistanceCalled = false; } rgFacts.clear(); _transectStyleItem->cameraCalc()->valueSetIsDistance()->setRawValue(false); _transectStyleItem->rebuildTransectsPhase1Called = false; - _transectStyleItem->rebuildTransectsPhase2Called = false; + _transectStyleItem->recalcCameraShotsCalled = false; + _transectStyleItem->recalcComplexDistanceCalled = false; changeFactValue(_transectStyleItem->cameraCalc()->imageDensity()); QVERIFY(_transectStyleItem->rebuildTransectsPhase1Called); - QVERIFY(_transectStyleItem->rebuildTransectsPhase2Called); + QVERIFY(_transectStyleItem->recalcCameraShotsCalled); + QVERIFY(_transectStyleItem->recalcComplexDistanceCalled); QVERIFY(_multiSpy->checkSignalsByMask(lastSequenceNumberChangedMask)); _multiSpy->clearAllSignals(); _transectStyleItem->cameraCalc()->valueSetIsDistance()->setRawValue(true); _transectStyleItem->rebuildTransectsPhase1Called = false; - _transectStyleItem->rebuildTransectsPhase2Called = false; + _transectStyleItem->recalcCameraShotsCalled = false; + _transectStyleItem->recalcComplexDistanceCalled = false; changeFactValue(_transectStyleItem->cameraCalc()->distanceToSurface()); QVERIFY(_transectStyleItem->rebuildTransectsPhase1Called); - QVERIFY(_transectStyleItem->rebuildTransectsPhase2Called); + QVERIFY(_transectStyleItem->recalcCameraShotsCalled); + QVERIFY(_transectStyleItem->recalcComplexDistanceCalled); QVERIFY(_multiSpy->checkSignalsByMask(lastSequenceNumberChangedMask)); _multiSpy->clearAllSignals(); } @@ -219,7 +227,8 @@ void TransectStyleComplexItemTest::_testAltMode(void) TransectStyleItem::TransectStyleItem(Vehicle* vehicle, QObject* parent) : TransectStyleComplexItem (vehicle, false /* flyView */, QStringLiteral("UnitTestTransect"), parent) , rebuildTransectsPhase1Called (false) - , rebuildTransectsPhase2Called (false) + , recalcComplexDistanceCalled (false) + , recalcCameraShotsCalled (false) { } @@ -229,7 +238,12 @@ void TransectStyleItem::_rebuildTransectsPhase1(void) rebuildTransectsPhase1Called = true; } -void TransectStyleItem::_rebuildTransectsPhase2(void) +void TransectStyleItem::_recalcComplexDistance(void) { - rebuildTransectsPhase2Called = true; + recalcComplexDistanceCalled = true; +} + +void TransectStyleItem::_recalcCameraShots(void) +{ + recalcCameraShotsCalled = true; } diff --git a/src/MissionManager/TransectStyleComplexItemTest.h b/src/MissionManager/TransectStyleComplexItemTest.h index dac201cf7094ab41616f67ee51b06910df3ff926..b85cb478658c559d63aa29663c91a09ecd0df411 100644 --- a/src/MissionManager/TransectStyleComplexItemTest.h +++ b/src/MissionManager/TransectStyleComplexItemTest.h @@ -94,12 +94,15 @@ public: bool specifiesCoordinate (void) const final { return true; } void appendMissionItems (QList& items, QObject* missionItemParent) final { Q_UNUSED(items); Q_UNUSED(missionItemParent); } void applyNewAltitude (double newAltitude) final { Q_UNUSED(newAltitude); } + double additionalTimeDelay (void) const final { return 0; } bool rebuildTransectsPhase1Called; - bool rebuildTransectsPhase2Called; + bool recalcComplexDistanceCalled; + bool recalcCameraShotsCalled; private slots: // Overrides from TransectStyleComplexItem - void _rebuildTransectsPhase1(void) final; - void _rebuildTransectsPhase2(void) final; + void _rebuildTransectsPhase1 (void) final; + void _recalcComplexDistance (void) final; + void _recalcCameraShots (void) final; }; diff --git a/src/PlanView/FWLandingPatternEditor.qml b/src/PlanView/FWLandingPatternEditor.qml index fcd56385d3f0ec456b3953b12789a223eea1cd7c..2bfbd1e70830991878e371d14e02e15478a9ca8d 100644 --- a/src/PlanView/FWLandingPatternEditor.qml +++ b/src/PlanView/FWLandingPatternEditor.qml @@ -119,9 +119,9 @@ Rectangle { QGCRadioButton { id: specifyLandingDistance text: qsTr("Landing Dist") - checked: missionItem.valueSetIsDistance + checked: missionItem.valueSetIsDistance.rawValue exclusiveGroup: distanceGlideGroup - onClicked: missionItem.valueSetIsDistance = checked + onClicked: missionItem.valueSetIsDistance.rawValue = checked Layout.fillWidth: true } @@ -134,9 +134,9 @@ Rectangle { QGCRadioButton { id: specifyGlideSlope text: qsTr("Glide Slope") - checked: !missionItem.valueSetIsDistance + checked: !missionItem.valueSetIsDistance.rawValue exclusiveGroup: distanceGlideGroup - onClicked: missionItem.valueSetIsDistance = !checked + onClicked: missionItem.valueSetIsDistance.rawValue = !checked Layout.fillWidth: true } diff --git a/src/PlanView/MissionSettingsEditor.qml b/src/PlanView/MissionSettingsEditor.qml index 265ba3cb4b37541030611f34a214dc9be5a456c3..9c9bffeb05c947141e46f1b5a4a2c82cd01ad24c 100644 --- a/src/PlanView/MissionSettingsEditor.qml +++ b/src/PlanView/MissionSettingsEditor.qml @@ -36,7 +36,7 @@ Rectangle { property var _fileExtension: QGroundControl.settingsManager.appSettings.missionFileExtension property var _appSettings: QGroundControl.settingsManager.appSettings property bool _waypointsOnlyMode: QGroundControl.corePlugin.options.missionWaypointsOnly - property bool _showCameraSection: (!_waypointsOnlyMode || QGroundControl.corePlugin.showAdvancedUI) && !_missionVehicle.apmFirmware + property bool _showCameraSection: (_waypointsOnlyMode || QGroundControl.corePlugin.showAdvancedUI) && !_missionVehicle.apmFirmware property bool _simpleMissionStart: QGroundControl.corePlugin.options.showSimpleMissionStart property bool _showFlightSpeed: !_missionVehicle.vtol && !_simpleMissionStart && !_missionVehicle.apmFirmware @@ -93,7 +93,7 @@ Rectangle { CameraSection { id: cameraSection - checked: missionItem.cameraSection.settingsSpecified + checked: !_waypointsOnlyMode && missionItem.cameraSection.settingsSpecified visible: _showCameraSection } diff --git a/src/PlanView/SimpleItemEditor.qml b/src/PlanView/SimpleItemEditor.qml index 8c765710cde9cbff90c65cbaa8ab2082b6866222..7ee452e8665f6c37deefdcbad2e1736388e10c91 100644 --- a/src/PlanView/SimpleItemEditor.qml +++ b/src/PlanView/SimpleItemEditor.qml @@ -18,11 +18,6 @@ Rectangle { color: qgcPal.windowShadeDark radius: _radius - readonly property int _altModeRelative: 0 - readonly property int _altModeAbsolute: 1 - readonly property int _altModeAboveTerrain: 2 - readonly property int _altModeTerrainFrame: 3 - property bool _specifiesAltitude: missionItem.specifiesAltitude property real _margin: ScreenTools.defaultFontPixelHeight / 2 property bool _supportsTerrainFrame: missionItem @@ -32,32 +27,22 @@ Rectangle { property string _altModeAboveTerrainHelpText: qsTr("Altitude above terrain\nActual AMSL altitude: %1 %2").arg(missionItem.amslAltAboveTerrain.valueString).arg(missionItem.amslAltAboveTerrain.units) property string _altModeTerrainFrameHelpText: qsTr("Using terrain reference frame") - readonly property string _altModeRelativeExtraUnits: qsTr(" (Rel)") - readonly property string _altModeAbsoluteExtraUnits: qsTr(" (AMSL)") - readonly property string _altModeAboveTerrainExtraUnits: qsTr(" (Abv Terr)") - readonly property string _altModeTerrainFrameExtraUnits: qsTr(" (TerrF)") - function updateAltitudeModeText() { - if (missionItem.altitudeMode === _altModeRelative) { + if (missionItem.altitudeMode === QGroundControl.AltitudeModeRelative) { altModeLabel.text = qsTr("Altitude") altModeHelp.text = _altModeRelativeHelpText - altField.extraUnits = _altModeRelativeExtraUnits - } else if (missionItem.altitudeMode === _altModeAbsolute) { + } else if (missionItem.altitudeMode === QGroundControl.AltitudeModeAbsolute) { altModeLabel.text = qsTr("Above Mean Sea Level") altModeHelp.text = _altModeAbsoluteHelpText - altField.extraUnits = _altModeAbsoluteExtraUnits - } else if (missionItem.altitudeMode === _altModeAboveTerrain) { + } else if (missionItem.altitudeMode === QGroundControl.AltitudeModeAboveTerrain) { altModeLabel.text = qsTr("Above Terrain") altModeHelp.text = Qt.binding(function() { return _altModeAboveTerrainHelpText }) - altField.extraUnits = _altModeAboveTerrainExtraUnits - } else if (missionItem.altitudeMode === _altModeTerrainFrame) { + } else if (missionItem.altitudeMode === QGroundControl.AltitudeModeTerrainFrame) { altModeLabel.text = qsTr("Terrain Frame") altModeHelp.text = _altModeTerrainFrameHelpText - altField.extraUnits = _altModeTerrainFrameExtraUnits } else { altModeLabel.text = qsTr("Internal Error") altModeHelp.text = "" - altField.extraUnits = "" } } @@ -159,44 +144,42 @@ Rectangle { MenuItem { text: qsTr("Altitude Relative To Home") checkable: true - checked: missionItem.altitudeMode === _altModeRelative - onTriggered: missionItem.altitudeMode = _altModeRelative + checked: missionItem.altitudeMode === QGroundControl.AltitudeModeRelative + onTriggered: missionItem.altitudeMode = QGroundControl.AltitudeModeRelative } MenuItem { text: qsTr("Altitude Above Mean Sea Level") checkable: true - checked: missionItem.altitudeMode === _altModeAbsolute + checked: missionItem.altitudeMode === QGroundControl.AltitudeModeAbsolute visible: QGroundControl.corePlugin.options.showMissionAbsoluteAltitude - onTriggered: missionItem.altitudeMode = _altModeAbsolute + onTriggered: missionItem.altitudeMode = QGroundControl.AltitudeModeAbsolute } MenuItem { text: qsTr("Altitude Above Terrain") checkable: true - checked: missionItem.altitudeMode === _altModeAboveTerrain - onTriggered: missionItem.altitudeMode = _altModeAboveTerrain + checked: missionItem.altitudeMode === QGroundControl.AltitudeModeAboveTerrain + onTriggered: missionItem.altitudeMode = QGroundControl.AltitudeModeAboveTerrain visible: missionItem.specifiesCoordinate } MenuItem { text: qsTr("Terrain Frame") checkable: true - checked: missionItem.altitudeMode === _altModeTerrainFrame - visible: missionItem.altitudeMode === _altModeTerrainFrame - onTriggered: missionItem.altitudeMode = _altModeTerrainFrame + checked: missionItem.altitudeMode === QGroundControl.AltitudeModeTerrainFrame + visible: missionItem.altitudeMode === QGroundControl.AltitudeModeTerrainFrame + onTriggered: missionItem.altitudeMode = QGroundControl.AltitudeModeTerrainFrame } } } - FactTextField { + AltitudeFactTextField { id: altField fact: missionItem.altitude - unitsLabel: fact.units + extraUnits + altitudeMode: missionItem.altitudeMode anchors.left: parent.left anchors.right: parent.right - - property string extraUnits } QGCLabel { diff --git a/src/PlanView/SurveyItemEditor.qml b/src/PlanView/SurveyItemEditor.qml index bb16c8a1218021d7c5bc04b6c6d70f88830cd28c..183dc259e000d7d0699846b569c4771942e56abf 100644 --- a/src/PlanView/SurveyItemEditor.qml +++ b/src/PlanView/SurveyItemEditor.qml @@ -126,12 +126,15 @@ Rectangle { onClicked: missionItem.rotateEntryPoint(); } + /* + Temporarily removed due to bug https://github.com/mavlink/qgroundcontrol/issues/7005 FactCheckBox { text: qsTr("Split concave polygons") fact: _splitConcave visible: _splitConcave.visible property Fact _splitConcave: missionItem.splitConcavePolygons } + */ FactCheckBox { text: qsTr("Hover and capture image") diff --git a/src/PositionManager/PositionManager.cpp b/src/PositionManager/PositionManager.cpp index 09f485142162f1ca634be70045d1fec08b4edda7..5de73d0f6e715a455e19de612c91dfbc486469e6 100644 --- a/src/PositionManager/PositionManager.cpp +++ b/src/PositionManager/PositionManager.cpp @@ -14,6 +14,7 @@ QGCPositionManager::QGCPositionManager(QGCApplication* app, QGCToolbox* toolbox) : QGCTool (app, toolbox) , _updateInterval (0) + , _gcsHeading (NAN) , _currentSource (NULL) , _defaultSource (NULL) , _nmeaSource (NULL) @@ -49,8 +50,19 @@ void QGCPositionManager::setToolbox(QGCToolbox *toolbox) void QGCPositionManager::setNmeaSourceDevice(QIODevice* device) { + // stop and release _nmeaSource if (_nmeaSource) { + _nmeaSource->stopUpdates(); + disconnect(_nmeaSource); + + // if _currentSource is pointing there, point to null + if (_currentSource == _nmeaSource){ + _currentSource = nullptr; + } + delete _nmeaSource; + _nmeaSource = nullptr; + } _nmeaSource = new QNmeaPositionInfoSource(QNmeaPositionInfoSource::RealTimeMode, this); _nmeaSource->setDevice(device); @@ -60,6 +72,7 @@ void QGCPositionManager::setNmeaSourceDevice(QIODevice* device) void QGCPositionManager::_positionUpdated(const QGeoPositionInfo &update) { QGeoCoordinate newGCSPosition = QGeoCoordinate(); + qreal newGCSHeading = update.attribute(QGeoPositionInfo::Direction); if (update.isValid()) { // Note that gcsPosition filters out possible crap values @@ -71,6 +84,10 @@ void QGCPositionManager::_positionUpdated(const QGeoPositionInfo &update) _gcsPosition = newGCSPosition; emit gcsPositionChanged(_gcsPosition); } + if (newGCSHeading != _gcsHeading) { + _gcsHeading = newGCSHeading; + emit gcsHeadingChanged(_gcsHeading); + } emit positionInfoUpdated(update); } diff --git a/src/PositionManager/PositionManager.h b/src/PositionManager/PositionManager.h index 692ae2324e2b71ada38798ca4aaeb0d9717a9778..30c39f363a208bde826bab11895813d48035e8ef 100644 --- a/src/PositionManager/PositionManager.h +++ b/src/PositionManager/PositionManager.h @@ -25,7 +25,8 @@ public: QGCPositionManager(QGCApplication* app, QGCToolbox* toolbox); ~QGCPositionManager(); - Q_PROPERTY(QGeoCoordinate gcsPosition READ gcsPosition NOTIFY gcsPositionChanged) + Q_PROPERTY(QGeoCoordinate gcsPosition READ gcsPosition NOTIFY gcsPositionChanged) + Q_PROPERTY(qreal gcsHeading READ gcsHeading NOTIFY gcsHeadingChanged) enum QGCPositionSource { Simulated, @@ -36,6 +37,8 @@ public: QGeoCoordinate gcsPosition(void) { return _gcsPosition; } + qreal gcsHeading() { return _gcsHeading; } + void setPositionSource(QGCPositionSource source); int updateInterval() const; @@ -50,11 +53,13 @@ private slots: signals: void gcsPositionChanged(QGeoCoordinate gcsPosition); + void gcsHeadingChanged(qreal gcsHeading); void positionInfoUpdated(QGeoPositionInfo update); private: int _updateInterval; QGeoCoordinate _gcsPosition; + qreal _gcsHeading; QGeoPositionInfoSource* _currentSource; QGeoPositionInfoSource* _defaultSource; diff --git a/src/QmlControls/AppMessages.cc b/src/QmlControls/AppMessages.cc index fab8b7bd6e1fbaf012b66a9006b70f4da313d2d8..0b7bcf4588eebef402d351b0b889eeedc7551f72 100644 --- a/src/QmlControls/AppMessages.cc +++ b/src/QmlControls/AppMessages.cc @@ -76,6 +76,8 @@ void AppLogModel::writeMessages(const QString dest_file) QTextStream out(&file); out << writebuffer; success = out.status() == QTextStream::Ok; + } else { + qWarning() << "AppLogModel::writeMessages write failed:" << file.errorString(); } emit debug_model->writeFinished(success); }); diff --git a/src/QmlControls/AppMessages.qml b/src/QmlControls/AppMessages.qml index af00cceeddd7ca1220090f31e243351e2306e1ae..600a812d1b4f3bc1c468a5ce00fe10a276822ec4 100644 --- a/src/QmlControls/AppMessages.qml +++ b/src/QmlControls/AppMessages.qml @@ -133,6 +133,7 @@ QGCView { id: writeDialog folder: QGroundControl.settingsManager.appSettings.logSavePath nameFilters: [qsTr("Log files (*.txt)"), qsTr("All Files (*)")] + fileExtension: qsTr("txt") selectExisting: false title: qsTr("Select log save file") qgcView: _qgcView @@ -157,31 +158,23 @@ QGCView { } QGCLabel { - id: gstLabel - anchors.baseline: gstCombo.baseline - anchors.right: gstCombo.left - anchors.rightMargin: ScreenTools.defaultFontPixelWidth - text: qsTr("GStreamer Debug Level:") - visible: QGroundControl.settingsManager.appSettings.gstDebugLevel.visible + id: gstLabel + anchors.left: writeButton.right + anchors.leftMargin: ScreenTools.defaultFontPixelWidth + anchors.baseline: gstCombo.baseline + text: qsTr("GStreamer Debug") + visible: QGroundControl.settingsManager.appSettings.gstDebugLevel.visible } FactComboBox { - id: gstCombo - anchors.right: followTail.left - anchors.rightMargin: ScreenTools.defaultFontPixelWidth*20 - anchors.bottom: parent.bottom - width: ScreenTools.defaultFontPixelWidth*20 - model: ["disabled", "1", "2", "3", "4", "5", "6", "7", "8"] - fact: QGroundControl.settingsManager.appSettings.gstDebugLevel - visible: QGroundControl.settingsManager.appSettings.gstDebugLevel.visible - } - - BusyIndicator { - id: writeBusy - anchors.bottom: writeButton.bottom - anchors.left: writeButton.right - height: writeButton.height - visible: !writeButton.enabled + id: gstCombo + anchors.left: gstLabel.right + anchors.leftMargin: ScreenTools.defaultFontPixelWidth / 2 + anchors.bottom: parent.bottom + width: ScreenTools.defaultFontPixelWidth * 10 + model: ["Disabled", "1", "2", "3", "4", "5", "6", "7", "8"] + fact: QGroundControl.settingsManager.appSettings.gstDebugLevel + visible: QGroundControl.settingsManager.appSettings.gstDebugLevel.visible } QGCButton { @@ -204,7 +197,7 @@ QGCView { id: filterButton anchors.bottom: parent.bottom anchors.right: parent.right - text: qsTr("Set logging") + text: qsTr("Set Logging") onClicked: showDialog(filtersDialogComponent, qsTr("Turn on logging categories"), qgcView.showDialogDefaultWidth, StandardButton.Close) } } diff --git a/src/QmlControls/QGCTextField.qml b/src/QmlControls/QGCTextField.qml index d8043b4fc0c675f1be73492c9d830af129336013..4e132f5e7c43fc8dc122bca1ec377a0be5e4d43c 100644 --- a/src/QmlControls/QGCTextField.qml +++ b/src/QmlControls/QGCTextField.qml @@ -11,6 +11,7 @@ TextField { textColor: qgcPal.textFieldText implicitHeight: ScreenTools.implicitTextFieldHeight activeFocusOnPress: true + antialiasing: true property bool showUnits: false property bool showHelp: false @@ -47,7 +48,11 @@ TextField { } style: TextFieldStyle { + id: tfs font.pointSize: ScreenTools.defaultFontPointSize + font.family: ScreenTools.normalFontFamily + renderType: ScreenTools.isWindows ? Text.QtRendering : tfs.renderType // This works around font rendering problems on windows + background: Item { id: backgroundItem diff --git a/src/QmlControls/QGroundControlQmlGlobal.h b/src/QmlControls/QGroundControlQmlGlobal.h index c4b29999833128ec9ee53908083d480221281675..e49ace26cf725b6131f8fabe2def0869a9a3e803 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.h +++ b/src/QmlControls/QGroundControlQmlGlobal.h @@ -43,6 +43,15 @@ public: QGroundControlQmlGlobal(QGCApplication* app, QGCToolbox* toolbox); ~QGroundControlQmlGlobal(); + enum AltitudeMode { + AltitudeModeNone, // Being used as distance value unrelated to ground (for example distance to structure) + AltitudeModeRelative, // MAV_FRAME_GLOBAL_RELATIVE_ALT + AltitudeModeAbsolute, // MAV_FRAME_GLOBAL + AltitudeModeAboveTerrain, // Absolute altitude above terrain calculated from terrain data + AltitudeModeTerrainFrame // MAV_FRAME_GLOBAL_TERRAIN_ALT + }; + Q_ENUM(AltitudeMode) + Q_PROPERTY(QString appName READ appName CONSTANT) Q_PROPERTY(LinkManager* linkManager READ linkManager CONSTANT) diff --git a/src/Settings/AutoConnect.SettingsGroup.json b/src/Settings/AutoConnect.SettingsGroup.json index ce5c7ca154454be9dd39e9f8bdc2e3a8d450f260..abbec2da6b32272a373d5376cf831c21706f87c4 100644 --- a/src/Settings/AutoConnect.SettingsGroup.json +++ b/src/Settings/AutoConnect.SettingsGroup.json @@ -46,7 +46,7 @@ "shortDescription": "NMEA GPS device for GCS position", "longDescription": "NMEA GPS device for GCS position", "type": "string", - "defaultValue": "disabled" + "defaultValue": "Disabled" }, { "name": "autoConnectNmeaBaud", @@ -72,5 +72,11 @@ "shortDescription": "UDP target host port for autoconnect", "type": "uint32", "defaultValue": 14550 +}, +{ + "name": "nmeaUdpPort", + "shortDescription": "Udp port to receive NMEA streams", + "type": "uint32", + "defaultValue": 14401 } ] diff --git a/src/Settings/AutoConnectSettings.cc b/src/Settings/AutoConnectSettings.cc index 23c576acacf4bbd9b1b18db9917144ac10ad66f1..c539a1aed19c2282c7303b9cfb43bb637a101220 100644 --- a/src/Settings/AutoConnectSettings.cc +++ b/src/Settings/AutoConnectSettings.cc @@ -23,6 +23,7 @@ DECLARE_SETTINGSFACT(AutoConnectSettings, autoConnectUDP) DECLARE_SETTINGSFACT(AutoConnectSettings, udpListenPort) DECLARE_SETTINGSFACT(AutoConnectSettings, udpTargetHostIP) DECLARE_SETTINGSFACT(AutoConnectSettings, udpTargetHostPort) +DECLARE_SETTINGSFACT(AutoConnectSettings, nmeaUdpPort) DECLARE_SETTINGSFACT_NO_FUNC(AutoConnectSettings, autoConnectPixhawk) { diff --git a/src/Settings/AutoConnectSettings.h b/src/Settings/AutoConnectSettings.h index 9f96d38ff0fb10db1ac78f5e1370c0832a623f5a..65716520daacfad255baad1e57c09af3c38704fd 100644 --- a/src/Settings/AutoConnectSettings.h +++ b/src/Settings/AutoConnectSettings.h @@ -31,5 +31,5 @@ public: DEFINE_SETTINGFACT(udpListenPort) DEFINE_SETTINGFACT(udpTargetHostIP) DEFINE_SETTINGFACT(udpTargetHostPort) - + DEFINE_SETTINGFACT(nmeaUdpPort) }; diff --git a/src/Taisync/TaisyncSettings.qml b/src/Taisync/TaisyncSettings.qml index a002b84e443de488f67534a42a69b358623969fa..82513fa9bce6514cf743fdf2e98819f43be1471a 100644 --- a/src/Taisync/TaisyncSettings.qml +++ b/src/Taisync/TaisyncSettings.qml @@ -438,7 +438,7 @@ QGCView { height: ipSettingsLabel.height anchors.margins: ScreenTools.defaultFontPixelWidth anchors.horizontalCenter: parent.horizontalCenter - visible: _taisyncEnabled + visible: _taisyncEnabled && (!ScreenTools.isiOS && !ScreenTools.isAndroid) QGCLabel { id: ipSettingsLabel text: qsTr("Network Settings") @@ -449,7 +449,7 @@ QGCView { height: ipSettingsCol.height + (ScreenTools.defaultFontPixelHeight * 2) width: _panelWidth color: qgcPal.windowShade - visible: _taisyncEnabled + visible: _taisyncEnabled && (!ScreenTools.isiOS && !ScreenTools.isAndroid) anchors.margins: ScreenTools.defaultFontPixelWidth anchors.horizontalCenter: parent.horizontalCenter Column { diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 56a2762fc6705f9ed94a1cc9eb9b5658dd70fe0f..9f540b7fc56959c81724739fc555a40d91a64ea0 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -278,6 +278,9 @@ Vehicle::Vehicle(LinkInterface* link, } _firmwarePlugin->initializeVehicle(this); + for(auto& factName: factNames()) { + _firmwarePlugin->adjustMetaData(vehicleType, getFact(factName)->metaData()); + } _sendMultipleTimer.start(_sendMessageMultipleIntraMessageDelay); connect(&_sendMultipleTimer, &QTimer::timeout, this, &Vehicle::_sendMessageMultipleNext); @@ -783,7 +786,10 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes _handleEstimatorStatus(message); break; case MAVLINK_MSG_ID_STATUSTEXT: - _handleStatusText(message); + _handleStatusText(message, false /* longVersion */); + break; + case MAVLINK_MSG_ID_STATUSTEXT_LONG: + _handleStatusText(message, true /* longVersion */); break; case MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS: _handleOrbitExecutionStatus(message); @@ -881,15 +887,23 @@ void Vehicle::_handleCameraImageCaptured(const mavlink_message_t& message) } } -void Vehicle::_handleStatusText(mavlink_message_t& message) +void Vehicle::_handleStatusText(mavlink_message_t& message, bool longVersion) { - QByteArray b; + QByteArray b; + QString messageText; + int severity; - b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1); - mavlink_msg_statustext_get_text(&message, b.data()); + if (longVersion) { + b.resize(MAVLINK_MSG_STATUSTEXT_LONG_FIELD_TEXT_LEN+1); + mavlink_msg_statustext_long_get_text(&message, b.data()); + severity = mavlink_msg_statustext_long_get_severity(&message); + } else { + b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1); + mavlink_msg_statustext_get_text(&message, b.data()); + severity = mavlink_msg_statustext_get_severity(&message); + } b[b.length()-1] = '\0'; - QString messageText = QString(b); - int severity = mavlink_msg_statustext_get_severity(&message); + messageText = QString(b); bool skipSpoken = false; bool ardupilotPrearm = messageText.startsWith(QStringLiteral("PreArm")); @@ -2287,6 +2301,7 @@ bool Vehicle::joystickEnabled(void) void Vehicle::setJoystickEnabled(bool enabled) { _joystickEnabled = enabled; + _startJoystick(_joystickEnabled); _saveSettings(); emit joystickEnabledChanged(_joystickEnabled); } diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 7bb9072a0340612f06fbf07e6ad4cc195e424c59..cba6240ea911692c2e6e05377215bd9268b7e120 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -1255,7 +1255,7 @@ private: void _handleAttitudeTarget(mavlink_message_t& message); void _handleDistanceSensor(mavlink_message_t& message); void _handleEstimatorStatus(mavlink_message_t& message); - void _handleStatusText(mavlink_message_t& message); + void _handleStatusText(mavlink_message_t& message, bool longVersion); void _handleOrbitExecutionStatus(const mavlink_message_t& message); // ArduPilot dialect messages #if !defined(NO_ARDUPILOT_DIALECT) diff --git a/src/comm/CMakeLists.txt b/src/comm/CMakeLists.txt index 315774cc9e3c6f45acb7a6019ddf5d0a336707ed..4a5fa752f30a0f68dd47e66d6cf98c94ba46d60c 100644 --- a/src/comm/CMakeLists.txt +++ b/src/comm/CMakeLists.txt @@ -24,6 +24,7 @@ add_library(comm SerialLink.cc TCPLink.cc UDPLink.cc + UdpIODevice.cc ${EXTRA_SRC} diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc index 036441a4b5514a54a54ed14ae5e766aaa1e7719c..957af8c6456d70201cf814281ded11343c0c2ed3 100644 --- a/src/comm/LinkManager.cc +++ b/src/comm/LinkManager.cc @@ -479,6 +479,29 @@ void LinkManager::_updateAutoConnectLinks(void) createConnectedLink(config); emit linkConfigurationsChanged(); } +#ifndef __mobile__ +#ifndef NO_SERIAL_LINK + // check to see if nmea gps is configured for UDP input, if so, set it up to connect + if (_autoConnectSettings->autoConnectNmeaPort()->cookedValueString() == "UDP Port") { + if (_nmeaSocket.localPort() != _autoConnectSettings->nmeaUdpPort()->rawValue().toUInt() + || _nmeaSocket.state() != UdpIODevice::BoundState) { + qCDebug(LinkManagerLog) << "Changing port for UDP NMEA stream"; + _nmeaSocket.close(); + _nmeaSocket.bind(QHostAddress::AnyIPv4, _autoConnectSettings->nmeaUdpPort()->rawValue().toUInt()); + _toolbox->qgcPositionManager()->setNmeaSourceDevice(&_nmeaSocket); + } + //close serial port + if (_nmeaPort) { + _nmeaPort->close(); + delete _nmeaPort; + _nmeaPort = nullptr; + _nmeaDeviceName = ""; + } + } else { + _nmeaSocket.close(); + } +#endif +#endif #ifndef NO_SERIAL_LINK QStringList currentPorts; @@ -513,6 +536,7 @@ void LinkManager::_updateAutoConnectLinks(void) #ifndef NO_SERIAL_LINK #ifndef __mobile__ + // check to see if nmea gps is configured for current Serial port, if so, set it up to connect if (portInfo.systemLocation().trimmed() == _autoConnectSettings->autoConnectNmeaPort()->cookedValueString()) { if (portInfo.systemLocation().trimmed() != _nmeaDeviceName) { _nmeaDeviceName = portInfo.systemLocation().trimmed(); diff --git a/src/comm/LinkManager.h b/src/comm/LinkManager.h index f09360142d62835a478973acdb0c28a1b9fba5f0..8322e1c6f593296ac3e64155226efa060ada8706 100644 --- a/src/comm/LinkManager.h +++ b/src/comm/LinkManager.h @@ -25,6 +25,7 @@ #include "MAVLinkProtocol.h" #if !defined(__mobile__) #include "LogReplayLink.h" +#include "UdpIODevice.h" #endif #include "QmlObjectListModel.h" @@ -241,6 +242,7 @@ private: QString _nmeaDeviceName; QSerialPort* _nmeaPort; uint32_t _nmeaBaud; + UdpIODevice _nmeaSocket; #endif #endif }; diff --git a/src/comm/MockLink.cc b/src/comm/MockLink.cc index 9eee0deed51211b332c28917e1a420286ac012af..9edc2f30c3ed36b27b2783023e1283dc29053343 100644 --- a/src/comm/MockLink.cc +++ b/src/comm/MockLink.cc @@ -1065,6 +1065,14 @@ void MockLink::_sendStatusTextMessages(void) status->severity, status->msg); respondWithMavlinkMessage(msg); + + mavlink_msg_statustext_long_pack_chan(_vehicleSystemId, + _vehicleComponentId, + _mavlinkChannel, + &msg, + status->severity, + status->msg); + respondWithMavlinkMessage(msg); } } diff --git a/src/comm/USBBoardInfo.json b/src/comm/USBBoardInfo.json index 42a00bcdfd8e138adb4b094934dceed48f44c45c..358480fa476eb5e10e025c8588636a58a130bbf0 100644 --- a/src/comm/USBBoardInfo.json +++ b/src/comm/USBBoardInfo.json @@ -29,10 +29,10 @@ { "vendorID": 1027, "productID": 24577, "boardClass": "SiK Radio", "name": "SiK Radio", "comment": "3DR Radio on FTDI" }, { "vendorID": 4292, "productID": 60000, "boardClass": "SiK Radio", "name": "SiK Radio", "comment": "SILabs Radio" }, - { "vendorID": 5446, "productID": 424, "boardClass": "RTK GPS", "name": "U-blox RTK GPS", "comment": "U-blox RTK GPS (M8P)" }, - { "vendorID": 5446, "productID": 425, "boardClass": "RTK GPS", "name": "U-blox RTK GPS", "comment": "U-blox RTK GPS (F9P)" }, - { "vendorID": 1317, "productID": 42151, "boardClass": "RTK GPS", "name": "Trimble RTK GPS", "comment": "Trimble RTK GPS" }, - + { "vendorID": 5446, "productID": 424, "boardClass": "RTK GPS", "name": "U-blox RTK GPS", "comment": "U-blox RTK GPS (M8P)" }, + { "vendorID": 5446, "productID": 425, "boardClass": "RTK GPS", "name": "U-blox RTK GPS", "comment": "U-blox RTK GPS (F9P)" }, + { "vendorID": 1317, "productID": 42151, "boardClass": "RTK GPS", "name": "Trimble RTK GPS", "comment": "Trimble RTK GPS" }, + { "vendorID": 5418, "productID": 34240, "boardClass": "RTK GPS", "name": "Septentrio RTK GPS", "comment": "Septentrio RTK GPS" }, { "vendorID": 8352, "productID": 16732, "boardClass": "OpenPilot", "name": "OpenPilot OPLink" }, { "vendorID": 8352, "productID": 16733, "boardClass": "OpenPilot", "name": "OpenPilot CC3D" }, { "vendorID": 8352, "productID": 16734, "boardClass": "OpenPilot", "name": "OpenPilot Revolution" }, diff --git a/src/comm/UdpIODevice.cc b/src/comm/UdpIODevice.cc new file mode 100644 index 0000000000000000000000000000000000000000..7f85dd6017167350a369791e4f2082772e0789ec --- /dev/null +++ b/src/comm/UdpIODevice.cc @@ -0,0 +1,45 @@ +/**************************************************************************** + * + * (c) 2009-2018 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#include "UdpIODevice.h" +#include + +UdpIODevice::UdpIODevice(QObject *parent) : QUdpSocket(parent) +{ + // this might cause data to be available only after a second readyRead() signal + connect(this, &QUdpSocket::readyRead, this, &UdpIODevice::_readAvailableData); +} + +bool UdpIODevice::canReadLine() const +{ + return _buffer.indexOf('\n') > -1; +} + +qint64 UdpIODevice::readLineData(char *data, qint64 maxSize) +{ + int length = _buffer.indexOf('\n') + 1; // add 1 to include the '\n' + if (length == 0) { + return 0; + } + length = std::min(length, static_cast(maxSize)); + // copy lines to output + std::copy(_buffer.data(), _buffer.data() + length, data); + // trim buffer to remove consumed line + _buffer = _buffer.right(_buffer.size() - length); + // return number of bytes read + return length; +} + +void UdpIODevice::_readAvailableData() { + while (hasPendingDatagrams()) { + int previousSize = _buffer.size(); + _buffer.resize(static_cast(_buffer.size() + pendingDatagramSize())); + readDatagram((_buffer.data() + previousSize), pendingDatagramSize()); + } +} diff --git a/src/comm/UdpIODevice.h b/src/comm/UdpIODevice.h new file mode 100644 index 0000000000000000000000000000000000000000..2ccd8a8afb4a0e374e001ef82db06b1211043b2b --- /dev/null +++ b/src/comm/UdpIODevice.h @@ -0,0 +1,35 @@ +/**************************************************************************** + * + * (c) 2009-2018 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ +#pragma once + +#include + +/** + * @brief QUdpSocket implementation of canReadLine() readLineData() in server mode. + * The UdpIODevice class works almost exactly as a QUdpSocket, but + * also implements canReadLine() and readLineData() while in the bound state. + * Regular QUdpSocket only allows to use these QIODevice interfaces when using + * connectToHost(), which means it is working as a client instead of server. + * + **/ + +class UdpIODevice: public QUdpSocket +{ + Q_OBJECT +public: + UdpIODevice(QObject *parent = nullptr); + bool canReadLine() const; + qint64 readLineData(char *data, qint64 maxSize); + +private slots: + void _readAvailableData(); + +private: + QByteArray _buffer; +}; diff --git a/src/main.cc b/src/main.cc index 62457d0149adf48fbbf431d4e84818df5b479816..62012d36cdc3379274959f9dab23c6a4233a46cf 100644 --- a/src/main.cc +++ b/src/main.cc @@ -97,6 +97,21 @@ jint JNI_OnLoad(JavaVM* vm, void* reserved) } #endif +#ifdef __android__ +#include +bool checkAndroidWritePermission() { + QtAndroid::PermissionResult r = QtAndroid::checkPermission("android.permission.WRITE_EXTERNAL_STORAGE"); + if(r == QtAndroid::PermissionResult::Denied) { + QtAndroid::requestPermissionsSync( QStringList() << "android.permission.WRITE_EXTERNAL_STORAGE" ); + r = QtAndroid::checkPermission("android.permission.WRITE_EXTERNAL_STORAGE"); + if(r == QtAndroid::PermissionResult::Denied) { + return false; + } + } + return true; +} +#endif + /** * @brief Starts the application * @@ -254,6 +269,10 @@ int main(int argc, char *argv[]) } else #endif { + +#ifdef __android__ + checkAndroidWritePermission(); +#endif if (!app->_initForNormalAppBoot()) { return -1; } diff --git a/src/ui/MAVLinkDecoder.cc b/src/ui/MAVLinkDecoder.cc index 53381f8dd7e0cac3fc83bede9b592a924f05d51b..9c2152396c2aacff3de78ec053fcb6b5edd44952 100644 --- a/src/ui/MAVLinkDecoder.cc +++ b/src/ui/MAVLinkDecoder.cc @@ -15,6 +15,7 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol) : // messageFilter.insert(MAVLINK_MSG_ID_HEARTBEAT, false); // messageFilter.insert(MAVLINK_MSG_ID_SYS_STATUS, false); messageFilter.insert(MAVLINK_MSG_ID_STATUSTEXT, false); + messageFilter.insert(MAVLINK_MSG_ID_STATUSTEXT_LONG, false); messageFilter.insert(MAVLINK_MSG_ID_COMMAND_LONG, false); messageFilter.insert(MAVLINK_MSG_ID_COMMAND_ACK, false); messageFilter.insert(MAVLINK_MSG_ID_PARAM_SET, false); diff --git a/src/ui/preferences/GeneralSettings.qml b/src/ui/preferences/GeneralSettings.qml index a358e29338399b803557f81f4e57dd848b08e036..783ad7293b888ea1bace5489dd2333eecc9fb39d 100644 --- a/src/ui/preferences/GeneralSettings.qml +++ b/src/ui/preferences/GeneralSettings.qml @@ -52,6 +52,9 @@ QGCView { property bool _isTCP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.tcpVideoSource property bool _isMPEGTS: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.mpegtsVideoSource + property string gpsDisabled: "Disabled" + property string gpsUdpPort: "UDP Port" + readonly property real _internalWidthRatio: 0.8 QGCPalette { id: qgcPal } @@ -504,7 +507,6 @@ QGCView { Layout.preferredWidth: _comboFieldWidth model: ListModel { - ListElement { text: "disabled" } } onActivated: { @@ -513,18 +515,26 @@ QGCView { } } Component.onCompleted: { + model.append({text: gpsDisabled}) + model.append({text: gpsUdpPort}) + for (var i in QGroundControl.linkManager.serialPorts) { nmeaPortCombo.model.append({text:QGroundControl.linkManager.serialPorts[i]}) } var index = nmeaPortCombo.find(QGroundControl.settingsManager.autoConnectSettings.autoConnectNmeaPort.valueString); nmeaPortCombo.currentIndex = index; + if (QGroundControl.linkManager.serialPorts.length === 0) { + nmeaPortCombo.model.append({text: "Serial "}) + } } } QGCLabel { + visible: nmeaPortCombo.currentText !== gpsUdpPort && nmeaPortCombo.currentText !== gpsDisabled text: qsTr("NMEA GPS Baudrate") } QGCComboBox { + visible: nmeaPortCombo.currentText !== gpsUdpPort && nmeaPortCombo.currentText !== gpsDisabled id: nmeaBaudCombo Layout.preferredWidth: _comboFieldWidth model: [4800, 9600, 19200, 38400, 57600, 115200] @@ -539,6 +549,16 @@ QGCView { nmeaBaudCombo.currentIndex = index; } } + + QGCLabel { + text: qsTr("NMEA stream UDP port") + visible: nmeaPortCombo.currentText === gpsUdpPort + } + FactTextField { + visible: nmeaPortCombo.currentText === gpsUdpPort + Layout.preferredWidth: _valueFieldWidth + fact: QGroundControl.settingsManager.autoConnectSettings.nmeaUdpPort + } } } }