Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add NTRIP support to feed RCTM data #12078

Open
wants to merge 7 commits into
base: Stable_V4.4
Choose a base branch
from
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
18 changes: 13 additions & 5 deletions qgroundcontrol.pro
Original file line number Diff line number Diff line change
Expand Up @@ -267,9 +267,10 @@ QT += \
AndroidBuild || iOSBuild {
# Android and iOS don't unclude these
} else {
}
QT += \
serialport \
}


contains(DEFINES, QGC_ENABLE_BLUETOOTH) {
QT += \
Expand Down Expand Up @@ -400,6 +401,7 @@ INCLUDEPATH += \
src/Joystick \
src/PlanView \
src/MissionManager \
src/NTRIP \
src/PositionManager \
src/QmlControls \
src/QtLocationPlugin \
Expand Down Expand Up @@ -589,6 +591,8 @@ HEADERS += \
src/Compression/QGCZlib.h \
src/FirmwarePlugin/PX4/px4_custom_mode.h \
src/FollowMe/FollowMe.h \
src/GPS/Drivers/src/rtcm.h \
src/GPS/RTCM/RTCMMavlink.h \
src/Joystick/Joystick.h \
src/Joystick/JoystickManager.h \
src/Joystick/JoystickMavCommand.h \
Expand Down Expand Up @@ -638,6 +642,7 @@ HEADERS += \
src/MissionManager/TransectStyleComplexItem.h \
src/MissionManager/VisualMissionItem.h \
src/MissionManager/VTOLLandingComplexItem.h \
src/NTRIP/NTRIP.h \
src/PositionManager/PositionManager.h \
src/PositionManager/SimulatedPosition.h \
src/Geo/QGCGeo.h \
Expand Down Expand Up @@ -688,6 +693,7 @@ HEADERS += \
src/Settings/FirmwareUpgradeSettings.h \
src/Settings/FlightMapSettings.h \
src/Settings/FlyViewSettings.h \
src/Settings/NTRIPSettings.h \
src/Settings/OfflineMapsSettings.h \
src/Settings/PlanViewSettings.h \
src/Settings/RTKSettings.h \
Expand Down Expand Up @@ -811,14 +817,12 @@ HEADERS += \
!MobileBuild {
HEADERS += \
src/GPS/Drivers/src/gps_helper.h \
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 \
src/GPS/RTCM/RTCMMavlink.h \
src/GPS/definitions.h \
src/GPS/satellite_info.h \
src/GPS/sensor_gps.h \
Expand Down Expand Up @@ -853,6 +857,8 @@ SOURCES += \
src/Compression/QGCLZMA.cc \
src/Compression/QGCZlib.cc \
src/FollowMe/FollowMe.cc \
src/GPS/Drivers/src/rtcm.cpp \
src/GPS/RTCM/RTCMMavlink.cc \
src/Joystick/Joystick.cc \
src/Joystick/JoystickManager.cc \
src/Joystick/JoystickMavCommand.cc \
Expand Down Expand Up @@ -901,6 +907,7 @@ SOURCES += \
src/MissionManager/TransectStyleComplexItem.cc \
src/MissionManager/VisualMissionItem.cc \
src/MissionManager/VTOLLandingComplexItem.cc \
src/NTRIP/NTRIP.cc \
src/PositionManager/PositionManager.cpp \
src/PositionManager/SimulatedPosition.cc \
src/Geo/QGCGeo.cc \
Expand Down Expand Up @@ -948,6 +955,7 @@ SOURCES += \
src/Settings/RemoteIDSettings.cc \
src/Settings/FirmwareUpgradeSettings.cc \
src/Settings/FlightMapSettings.cc \
src/Settings/NTRIPSettings.cc \
src/Settings/FlyViewSettings.cc \
src/Settings/OfflineMapsSettings.cc \
src/Settings/PlanViewSettings.cc \
Expand Down Expand Up @@ -1060,17 +1068,17 @@ contains (DEFINES, QGC_ENABLE_PAIRING) {
!MobileBuild {
SOURCES += \
src/GPS/Drivers/src/gps_helper.cpp \
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 \
src/Joystick/JoystickSDL.cc \
src/RunGuard.cc \
}

SOURCES += src/GPS/NmeaMessage.cc

#
# Firmware Plugin Support
#
Expand Down
1 change: 1 addition & 0 deletions qgroundcontrol.qrc
Original file line number Diff line number Diff line change
Expand Up @@ -319,6 +319,7 @@
<file alias="MavCmdInfoSub.json">src/MissionManager/MavCmdInfoSub.json</file>
<file alias="MavCmdInfoVTOL.json">src/MissionManager/MavCmdInfoVTOL.json</file>
<file alias="MissionSettings.FactMetaData.json">src/MissionManager/MissionSettings.FactMetaData.json</file>
<file alias="NTRIP.SettingsGroup.json">src/Settings/NTRIP.SettingsGroup.json</file>
<file alias="OfflineMaps.SettingsGroup.json">src/Settings/OfflineMaps.SettingsGroup.json</file>
<file alias="PlanView.SettingsGroup.json">src/Settings/PlanView.SettingsGroup.json</file>
<file alias="QGCMapCircle.Facts.json">src/MissionManager/QGCMapCircle.Facts.json</file>
Expand Down
2 changes: 2 additions & 0 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -140,6 +140,7 @@ if (${QGC_GST_MICROHARD_ENABLED})
add_subdirectory(Microhard)
endif ()
add_subdirectory(MissionManager)
add_subdirectory(NTRIP)
add_subdirectory(PlanView)
add_subdirectory(PositionManager)
add_subdirectory(QmlControls)
Expand Down Expand Up @@ -181,6 +182,7 @@ target_link_libraries(qgc
gps
Joystick
MissionManager
NTRIP
PositionManager
QmlControls
QtLocationPlugin
Expand Down
1 change: 1 addition & 0 deletions src/GPS/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ add_library(gps
Drivers/src/ubx.cpp
GPSManager.cc
GPSProvider.cc
NmeaMessage.cc
RTCM/RTCMMavlink.cc
)

Expand Down
2 changes: 1 addition & 1 deletion src/GPS/Drivers
92 changes: 92 additions & 0 deletions src/GPS/NmeaMessage.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,92 @@
//
// Created by zdanek on 13.11.24.
//

#include "NmeaMessage.h"

#include <QDateTime>
#include <QtCore>
#include <cmath>

NmeaMessage::NmeaMessage(QGeoCoordinate coordinate) {
_coordinate = coordinate;
}

QString NmeaMessage::getGGA() {

double lat = _coordinate.latitude();
double lng = _coordinate.longitude();
double alt = _coordinate.altitude();

// qCDebug(NTRIPLog) << "lat : " << lat << " lon : " << lng << " alt : " << alt;

QString time = QDateTime::currentDateTimeUtc().toString("hhmmss.zzz");

if (lat != 0 || lng != 0) {
if (std::isnan(alt))
alt = 0.0;

int latDegrees = (int)qFabs(lat);
double latMinutes = (qFabs(lat) - latDegrees) * 60.0;

int lngDegrees = (int)qFabs(lng);
double lngMinutes = (qFabs(lng) - lngDegrees) * 60.0;

// Format latitude degrees and minutes with leading zeros
QString latDegreesStr = QString("%1").arg(latDegrees, 2, 10, QChar('0'));
QString latMinutesStr =
QString("%1").arg(latMinutes, 7, 'f', 4, QChar('0'));
QString latStr = latDegreesStr + latMinutesStr;

// Format longitude degrees and minutes with leading zeros
QString lngDegreesStr = QString("%1").arg(lngDegrees, 3, 10, QChar('0'));
QString lngMinutesStr =
QString("%1").arg(lngMinutes, 7, 'f', 4, QChar('0'));
QString lngStr = lngDegreesStr + lngMinutesStr;

QString line =
QString("$GPGGA,%1,%2,%3,%4,%5,%6,%7,%8,%9,%10,%11,%12,%13,%14")
.arg(time) // %1 - UTC Time
.arg(latStr) // %2 - Latitude in NMEA format
.arg(lat < 0 ? "S" : "N") // %3 - N/S Indicator
.arg(lngStr) // %4 - Longitude in NMEA format
.arg(lng < 0 ? "W" : "E") // %5 - E/W Indicator
.arg("1") // %6 - Fix Quality
.arg("10") // %7 - Number of Satellites
.arg("1.0") // %8 - Horizontal Dilution of Precision (HDOP)
.arg(QString::number(alt, 'f', 2)) // %9 - Altitude
.arg("M") // %10 - Altitude Units
.arg("0") // %11 - Geoidal Separation
.arg("M") // %12 - Geoidal Separation Units
.arg("0.0") // %13 - Age of Differential GPS Data
.arg("0"); // %14 - Differential Reference Station ID

// Calculate checksum and send message
QString checkSum = _getCheckSum(line);
QString nmeaMessage = line + "*" + checkSum + "\r\n";

return nmeaMessage;
}
return QString();
}

QString NmeaMessage::_getCheckSum(QString line) {
// qCDebug(NTRIPLog) << "Calculating checksum";
QByteArray temp_Byte = line.toUtf8();
const char* buf = temp_Byte.constData();

char character;
int checksum = 0;

// Start from index 1 to skip the '$' character
for(int i = 1; i < line.length(); i++) {
character = buf[i];
if(character == '*') {
break;
}
checksum ^= character;
}

// Ensure the checksum is a two-digit uppercase hexadecimal string
return QString("%1").arg(checksum, 2, 16, QChar('0')).toUpper();
}
20 changes: 20 additions & 0 deletions src/GPS/NmeaMessage.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
//
// Created by zdanek on 13.11.24.
//

#pragma once

#include <QGeoCoordinate>
#include <QString>

class NmeaMessage {
public:
NmeaMessage(QGeoCoordinate coordinate);
QString getGGA();

private:
QString _getCheckSum(QString line);
QGeoCoordinate _coordinate;
};


26 changes: 15 additions & 11 deletions src/GPS/RTCM/RTCMMavlink.cc
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/****************************************************************************
*
* (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
* (c) 2009-2024 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
Expand All @@ -15,6 +15,8 @@

#include <cstdio>

QGC_LOGGING_CATEGORY(RTCMMavlinkLog, "RTCMMavlinkLog")

RTCMMavlink::RTCMMavlink(QGCToolbox& toolbox)
: _toolbox(toolbox)
{
Expand All @@ -23,13 +25,13 @@ RTCMMavlink::RTCMMavlink(QGCToolbox& toolbox)

void RTCMMavlink::RTCMDataUpdate(QByteArray message)
{
/* statistics */
qCDebug(RTCMMavlinkLog) << "RTCMDataUpdate: " << message.size() << " bytes"; /* statistics */
_bandwidthByteCounter += message.size();
qint64 elapsed = _bandwidthTimer.elapsed();
if (elapsed > 1000) {
printf("RTCM bandwidth: %.2f kB/s\n", (float) _bandwidthByteCounter / elapsed * 1000.f / 1024.f);
_bandwidthTimer.restart();
_bandwidthByteCounter = 0;
qCDebug(RTCMMavlinkLog) << "RTCM bandwidth: " << ((float) _bandwidthByteCounter / elapsed * 1000.f / 1024.f) << " KB/s";
_bandwidthTimer.restart();
_bandwidthByteCounter = 0;
}

const int maxMessageLength = MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN;
Expand Down Expand Up @@ -72,12 +74,14 @@ void RTCMMavlink::sendMessageToVehicle(const mavlink_gps_rtcm_data_t& msg)
mavlink_message_t message;
SharedLinkInterfacePtr sharedLink = weakLink.lock();

mavlink_msg_gps_rtcm_data_encode_chan(mavlinkProtocol->getSystemId(),
mavlinkProtocol->getComponentId(),
sharedLink->mavlinkChannel(),
&message,
&msg);
vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), message);
if (sharedLink->isConnected()) {
mavlink_msg_gps_rtcm_data_encode_chan(mavlinkProtocol->getSystemId(),
mavlinkProtocol->getComponentId(),
sharedLink->mavlinkChannel(),
&message,
&msg);
vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), message);
}
}
}
}
5 changes: 4 additions & 1 deletion src/GPS/RTCM/RTCMMavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,11 @@
#include <QObject>
#include <QElapsedTimer>

#include "QGCToolbox.h"
#include "MAVLinkProtocol.h"
#include "QGCLoggingCategory.h"
#include "QGCToolbox.h"

Q_DECLARE_LOGGING_CATEGORY(RTCMMavlinkLog)

/**
** class RTCMMavlink
Expand Down
14 changes: 14 additions & 0 deletions src/NTRIP/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
add_library(NTRIP
NTRIP.cc
NTRIP.h
)

target_link_libraries(NTRIP
PUBLIC
qgc
)

target_include_directories(NTRIP
PUBLIC
${CMAKE_CURRENT_SOURCE_DIR}
)
Loading
Loading