Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 0 additions & 4 deletions qgcimages.qrc
Original file line number Diff line number Diff line change
Expand Up @@ -100,9 +100,6 @@
<file alias="GeoFence.svg">src/AutoPilotPlugins/PX4/Images/GeoFence.svg</file>
<file alias="GeoFenceLight.svg">src/AutoPilotPlugins/PX4/Images/GeoFenceLight.svg</file>
<file alias="GeoTagIcon.svg">src/AnalyzeView/GeoTag/GeoTagIcon.svg</file>
<file alias="Gps.svg">src/UI/toolbar/Images/Gps.svg</file>
<file alias="GpsAuthentication.svg">src/UI/toolbar/Images/GpsAuthentication.svg</file>
<file alias="GpsInterference.svg">src/UI/toolbar/Images/GpsInterference.svg</file>
<file alias="Hamburger.svg">src/UI/toolbar/Images/Hamburger.svg</file>
<file alias="HamburgerThin.svg">src/UI/toolbar/Images/HamburgerThin.svg</file>
<file alias="Help.svg">src/FlightMap/Images/Help.svg</file>
Expand Down Expand Up @@ -172,7 +169,6 @@
<file alias="roi.svg">src/UI/toolbar/Images/roi.svg</file>
<file alias="rollDialWhite.svg">src/FlightMap/Images/rollDialWhite.svg</file>
<file alias="rollPointerWhite.svg">src/FlightMap/Images/rollPointerWhite.svg</file>
<file alias="RTK.svg">src/UI/toolbar/Images/RTK.svg</file>
<file alias="SafetyComponentIcon.png">src/AutoPilotPlugins/Common/Images/SafetyComponentIcon.png</file>
<file alias="scale.png">src/FlightMap/Images/scale.png</file>
<file alias="scale_end.png">src/FlightMap/Images/scale_end.png</file>
Expand Down
2 changes: 1 addition & 1 deletion src/API/QGCCorePlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -302,7 +302,7 @@ const QVariantList &QGCCorePlugin::toolBarIndicators()
{
static const QVariantList toolBarIndicatorList = QVariantList(
{
QVariant::fromValue(QUrl::fromUserInput(QStringLiteral("qrc:/qml/QGroundControl/Toolbar/RTKGPSIndicator.qml"))),
QVariant::fromValue(QUrl::fromUserInput(QStringLiteral("qrc:/qml/QGroundControl/GPS/RTK/RTKGPSIndicator.qml"))),
}
);

Expand Down
3 changes: 2 additions & 1 deletion src/AnalyzeView/GeoTag/GeoTagPage.qml
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ import QtQuick.Layouts
import QGroundControl
import QGroundControl.AnalyzeView
import QGroundControl.Controls
import "qrc:/qml/QGroundControl/GPS/GPSFormatHelpers.js" as GPSHelpers

AnalyzePage {
id: geoTagPage
Expand Down Expand Up @@ -530,7 +531,7 @@ AnalyzePage {
Layout.preferredWidth: ScreenTools.defaultFontPixelWidth * 20
text: {
if (model.coordinate && model.coordinate.isValid) {
return model.coordinate.latitude.toFixed(6) + ", " + model.coordinate.longitude.toFixed(6)
return GPSHelpers.formatCoordinate(model.coordinate.latitude, model.coordinate.longitude, 6)
}
return ""
}
Expand Down
6 changes: 6 additions & 0 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@ add_subdirectory(FirmwarePlugin)
add_subdirectory(FlyView)
add_subdirectory(FlightMap)
add_subdirectory(FollowMe)
add_subdirectory(GCSGeofence)
add_subdirectory(Gimbal)
add_subdirectory(GPS)
add_subdirectory(Utilities)
Expand Down Expand Up @@ -131,7 +132,12 @@ target_link_libraries(${CMAKE_PROJECT_NAME}
FirstRunPromptDialogsModule
FlyViewModule
FlightMapModule
GCSGeofenceModule
GPSModule
GPSNTRIPModule
GPSRTKModule
PlanViewModule
PositionManagerModule
QGroundControlControlsModule
QGroundControlModule
ToolbarModule
Expand Down
71 changes: 14 additions & 57 deletions src/Comms/LinkManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,6 @@
#ifndef QGC_NO_SERIAL_LINK
#include "SerialLink.h"
#include "GPSManager.h"
#include "PositionManager.h"
#include "UdpIODevice.h"
#include "GPSRtk.h"
#endif

#ifdef QT_DEBUG
Expand All @@ -38,9 +35,6 @@ LinkManager::LinkManager(QObject *parent)
: QObject(parent)
, _portListTimer(new QTimer(this))
, _qmlConfigurations(new QmlObjectListModel(this))
#ifndef QGC_NO_SERIAL_LINK
, _nmeaSocket(new UdpIODevice(this))
#endif
{
qCDebug(LinkManagerLog) << this;

Expand Down Expand Up @@ -432,26 +426,6 @@ void LinkManager::_updateAutoConnectLinks()
_addUDPAutoConnectLink();
_addMAVLinkForwardingLink();

// 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());
QGCPositionManager::instance()->setNmeaSourceDevice(_nmeaSocket);
}
#ifndef QGC_NO_SERIAL_LINK
if (_nmeaPort) {
_nmeaPort->close();
delete _nmeaPort;
_nmeaPort = nullptr;
_nmeaDeviceName = "";
}
#endif
} else {
_nmeaSocket->close();
}

#ifndef QGC_NO_SERIAL_LINK
_addSerialAutoConnectLink();
#endif
Expand Down Expand Up @@ -758,27 +732,7 @@ void LinkManager::_addSerialAutoConnectLink()
QGCSerialPortInfo::BoardType_t boardType;
QString boardName;

// 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();
qCDebug(LinkManagerLog) << "Configuring nmea port" << _nmeaDeviceName;
QSerialPort* newPort = new QSerialPort(portInfo, this);
_nmeaBaud = _autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt();
newPort->setBaudRate(static_cast<qint32>(_nmeaBaud));
qCDebug(LinkManagerLog) << "Configuring nmea baudrate" << _nmeaBaud;
// This will stop polling old device if previously set
QGCPositionManager::instance()->setNmeaSourceDevice(newPort);
if (_nmeaPort) {
delete _nmeaPort;
}
_nmeaPort = newPort;
} else if (_autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt() != _nmeaBaud) {
_nmeaBaud = _autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt();
_nmeaPort->setBaudRate(static_cast<qint32>(_nmeaBaud));
qCDebug(LinkManagerLog) << "Configuring nmea baudrate" << _nmeaBaud;
}
} else if (portInfo.getBoardInfo(boardType, boardName)) {
if (portInfo.getBoardInfo(boardType, boardName)) {
// Should we be auto-connecting to this board type?
if (!_allowAutoConnectToBoard(boardType)) {
continue;
Expand All @@ -789,7 +743,7 @@ void LinkManager::_addSerialAutoConnectLink()
qCDebug(LinkManagerLog) << "Waiting for bootloader to finish" << portInfo.systemLocation();
continue;
}
if (_portAlreadyConnected(portInfo.systemLocation()) || (_autoConnectRTKPort == portInfo.systemLocation())) {
if (_portAlreadyConnected(portInfo.systemLocation()) || _autoConnectRTKPorts.contains(portInfo.systemLocation())) {
qCDebug(LinkManagerVerboseLog) << "Skipping existing autoconnect" << portInfo.systemLocation();
} else if (!_autoconnectPortWaitList.contains(portInfo.systemLocation())) {
// We don't connect to the port the first time we see it. The ability to correctly detect whether we
Expand All @@ -812,9 +766,9 @@ void LinkManager::_addSerialAutoConnectLink()
pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName, portInfo.portName().trimmed()));
break;
case QGCSerialPortInfo::BoardTypeRTKGPS:
qCDebug(LinkManagerLog) << "RTK GPS auto-connected" << portInfo.portName().trimmed();
_autoConnectRTKPort = portInfo.systemLocation();
GPSManager::instance()->gpsRtk()->connectGPS(portInfo.systemLocation(), boardName);
qCDebug(LinkManagerLog) << "RTK GPS auto-connected" << portInfo.portName().trimmed() << boardName;
_autoConnectRTKPorts.append(portInfo.systemLocation());
GPSManager::instance()->connectGPS(portInfo.systemLocation(), boardName);
break;
default:
qCWarning(LinkManagerLog) << "Internal error: Unknown board type" << boardType;
Expand All @@ -835,11 +789,14 @@ void LinkManager::_addSerialAutoConnectLink()
}
}

// Check for RTK GPS connection gone
if (!_autoConnectRTKPort.isEmpty() && !currentPorts.contains(_autoConnectRTKPort)) {
qCDebug(LinkManagerLog) << "RTK GPS disconnected" << _autoConnectRTKPort;
GPSManager::instance()->gpsRtk()->disconnectGPS();
_autoConnectRTKPort.clear();
// Check for RTK GPS connections gone
for (int i = _autoConnectRTKPorts.size() - 1; i >= 0; --i) {
const QString &port = _autoConnectRTKPorts.at(i);
if (!currentPorts.contains(port)) {
qCDebug(LinkManagerLog) << "RTK GPS disconnected" << port;
GPSManager::instance()->disconnectGPS(port);
_autoConnectRTKPorts.removeAt(i);
}
}
}

Expand All @@ -862,7 +819,7 @@ bool LinkManager::_allowAutoConnectToBoard(QGCSerialPortInfo::BoardType_t boardT
}
break;
case QGCSerialPortInfo::BoardTypeRTKGPS:
if (_autoConnectSettings->autoConnectRTKGPS()->rawValue().toBool() && !GPSManager::instance()->gpsRtk()->connected()) {
if (_autoConnectSettings->autoConnectRTKGPS()->rawValue().toBool() && !GPSManager::instance()->connected()) {
return true;
}
break;
Expand Down
7 changes: 1 addition & 6 deletions src/Comms/LinkManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@ class QmlObjectListModel;
class QTimer;
class SerialLink;
class UDPConfiguration;
class UdpIODevice;

/// @brief Manage communication links
/// The Link Manager organizes the physical Links. It can manage arbitrary
Expand Down Expand Up @@ -179,14 +178,10 @@ private slots:
bool _portAlreadyConnected(const QString &portName);
void _filterCompositePorts(QList<QGCSerialPortInfo> &portList);

UdpIODevice *_nmeaSocket = nullptr;
QMap<QString, int> _autoconnectPortWaitList; ///< key: QGCSerialPortInfo::systemLocation, value: wait count
QList<SerialLink*> _activeLinkCheckList; ///< List of links we are waiting for a vehicle to show up on
QStringList _commPortList;
QStringList _commPortDisplayList;
QString _autoConnectRTKPort;
QString _nmeaDeviceName;
uint32_t _nmeaBaud = 0;
QSerialPort *_nmeaPort = nullptr;
QStringList _autoConnectRTKPorts;
#endif // QGC_NO_SERIAL_LINK
};
3 changes: 1 addition & 2 deletions src/FirmwarePlugin/FirmwarePlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -195,8 +195,7 @@ const QVariantList &FirmwarePlugin::toolIndicators(const Vehicle*)
//-- Default list of indicators for all vehicles.
if (_toolIndicatorList.isEmpty()) {
_toolIndicatorList = QVariantList({
QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/VehicleGPSIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/GPSResilienceIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/GPS/RTK/VehicleGPSIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/TelemetryRSSIIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/RCRSSIIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/BatteryIndicator.qml")),
Expand Down
19 changes: 19 additions & 0 deletions src/FlightMap/FlightMap.qml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ import Qt.labs.animation
import QGroundControl
import QGroundControl.Controls
import QGroundControl.FlightMap
import QGroundControl.GPS.RTK

Map {
id: _map
Expand Down Expand Up @@ -225,12 +226,30 @@ Map {
}
}

RTKBaseStationMapItem {
activeVehicle: _activeVehicle
planView: _map.planView
}

/// GCS position accuracy circle
MapCircle {
center: gcsPosition
radius: QGroundControl.qgcPositionManger.gcsPositionHorizontalAccuracy
color: Qt.rgba(0.2, 0.4, 0.8, 0.15)
border.color: Qt.rgba(0.2, 0.4, 0.8, 0.4)
border.width: 1
visible: gcsPosition.isValid && !planView
&& isFinite(QGroundControl.qgcPositionManger.gcsPositionHorizontalAccuracy)
&& QGroundControl.qgcPositionManger.gcsPositionHorizontalAccuracy < 100
}

/// Ground Station location
MapQuickItem {
anchorPoint.x: sourceItem.width / 2
anchorPoint.y: sourceItem.height / 2
visible: gcsPosition.isValid && !planView
coordinate: gcsPosition
opacity: QGroundControl.qgcPositionManger.positionStale ? 0.4 : 1.0

sourceItem: Image {
id: mapItemImage
Expand Down
5 changes: 3 additions & 2 deletions src/FlyView/FlyViewMap.qml
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ import QGroundControl.Controls
import QGroundControl.FlyView
import QGroundControl.FlightMap
import QGroundControl.PlanView
import "qrc:/qml/QGroundControl/GPS/GPSFormatHelpers.js" as GPSHelpers

FlightMap {
id: _root
Expand Down Expand Up @@ -745,8 +746,8 @@ FlightMap {

ColumnLayout {
spacing: 0
QGCLabel { text: qsTr("Lat: %1").arg(mapClickCoord.latitude.toFixed(6)) }
QGCLabel { text: qsTr("Lon: %1").arg(mapClickCoord.longitude.toFixed(6)) }
QGCLabel { text: qsTr("Lat: %1").arg(GPSHelpers.formatLatitude(mapClickCoord.latitude, 6)) }
QGCLabel { text: qsTr("Lon: %1").arg(GPSHelpers.formatLongitude(mapClickCoord.longitude, 6)) }
}
}
}
Expand Down
16 changes: 16 additions & 0 deletions src/FlyView/FlyViewWidgetLayer.qml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@ import QGroundControl
import QGroundControl.Controls
import QGroundControl.FlyView
import QGroundControl.FlightMap
import QGroundControl.GCSGeofence
import QGroundControl.GPS.RTK
import QGroundControl.Viewer3D

// This is the ui overlay layer for the widgets/tools for Fly View
Expand Down Expand Up @@ -163,6 +165,20 @@ Item {
z: QGroundControl.zOrderTopMost
}

GCSGeofenceAlert {
anchors.horizontalCenter: parent.horizontalCenter
anchors.top: parent.top
anchors.topMargin: ScreenTools.defaultFontPixelHeight
z: QGroundControl.zOrderTopMost
}

GNSSIntegrityAlert {
anchors.horizontalCenter: parent.horizontalCenter
anchors.top: parent.top
anchors.topMargin: ScreenTools.defaultFontPixelHeight * 4
z: QGroundControl.zOrderTopMost
}

MapScale {
id: mapScale
anchors.left: toolStrip.right
Expand Down
13 changes: 9 additions & 4 deletions src/FlyView/PreFlightGPSCheck.qml
Original file line number Diff line number Diff line change
Expand Up @@ -5,18 +5,23 @@ import QGroundControl.Controls

PreFlightCheckButton {
name: qsTr("GPS")
telemetryFailure: _3dLockFailure || _satCountFailure
telemetryFailure: _3dLockFailure || _satCountFailure || _hdopFailure
telemetryTextFailure: _3dLockFailure ?
qsTr("Waiting for 3D lock.") :
(_satCountFailure ? _satCountFailureText : "")
allowTelemetryFailureOverride: !_3dLockFailure && _satCountFailure && allowOverrideSatCount
(_hdopFailure ? _hdopFailureText :
(_satCountFailure ? _satCountFailureText : ""))
allowTelemetryFailureOverride: !_3dLockFailure && (_satCountFailure && allowOverrideSatCount || _hdopFailure)

property bool allowOverrideSatCount: false ///< true: sat count above failureSatCount reguired to pass, false: user can click past satCount <= failureSetCount
property int failureSatCount: -1 ///< -1 indicates no sat count check
property real failureHdop: -1 ///< -1 indicates no HDOP check

property bool _3dLock: globals.activeVehicle ? globals.activeVehicle.gps.lock.rawValue >= 3 : false
property bool _3dLock: globals.activeVehicle ? globals.activeVehicle.gps.lock.rawValue >= VehicleGPSFactGroup.Fix3D : false
property int _satCount: globals.activeVehicle ? globals.activeVehicle.gps.count.rawValue : 0
property real _hdop: globals.activeVehicle && !isNaN(globals.activeVehicle.gps.hdop.rawValue) ? globals.activeVehicle.gps.hdop.rawValue : -1
property bool _3dLockFailure: !_3dLock
property bool _satCountFailure: failureSatCount !== -1 && _satCount <= failureSatCount
property bool _hdopFailure: failureHdop > 0 && _hdop > 0 && _hdop > failureHdop
property string _satCountFailureText: allowOverrideSatCount ? qsTr("Warning - Sat count below %1.").arg(failureSatCount + 1) : qsTr("Waiting for sat count above %1.").arg(failureSatCount)
property string _hdopFailureText: qsTr("Warning - HDOP %1 exceeds limit %2.").arg(_hdop.toFixed(1)).arg(failureHdop.toFixed(1))
}
5 changes: 3 additions & 2 deletions src/FollowMe/FollowMe.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include "FirmwarePlugin.h"
#include "Vehicle.h"
#include "PositionManager.h"
#include "QGCMAVLink.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include "QGCLoggingCategory.h"
Expand Down Expand Up @@ -116,8 +117,8 @@ void FollowMe::_sendGCSMotionReport()

// Get the current location coordinates
// Important note: QGC only supports sending the constant GCS home position altitude for follow me.
motionReport.lat_int = static_cast<int>(gcsCoordinate.latitude() * 1e7);
motionReport.lon_int = static_cast<int>(gcsCoordinate.longitude() * 1e7);
motionReport.lat_int = QGCMAVLink::doubleToMavlinkLatLon(gcsCoordinate.latitude());
motionReport.lon_int = QGCMAVLink::doubleToMavlinkLatLon(gcsCoordinate.longitude());
motionReport.altMetersAMSL = gcsCoordinate.altitude();
estimationCapabilities |= (1 << POS);

Expand Down
28 changes: 28 additions & 0 deletions src/GCSGeofence/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
# ============================================================================
# GCS Geofence Module
# Client-side geofence monitoring and vehicle fence synchronization
# ============================================================================

target_sources(${CMAKE_PROJECT_NAME}
PRIVATE
GCSGeofenceMonitor.cc
GCSGeofenceMonitor.h
GCSGeofenceSyncer.cc
GCSGeofenceSyncer.h
)

target_include_directories(${CMAKE_PROJECT_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR})

# ----------------------------------------------------------------------------
# GCSGeofence QML Module
# ----------------------------------------------------------------------------
qt_add_library(GCSGeofenceModule STATIC)

qt_add_qml_module(GCSGeofenceModule
URI QGroundControl.GCSGeofence
VERSION 1.0
RESOURCE_PREFIX /qml
QML_FILES
GCSGeofenceAlert.qml
NO_PLUGIN
)
Loading
Loading