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

GPS: Prepare for New Position Source #11722

Merged
merged 1 commit into from
Oct 25, 2024
Merged
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
2 changes: 1 addition & 1 deletion .gitmodules
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
[submodule "src/GPS/Drivers"]
path = src/GPS/Drivers
path = libs/PX4-GPSDrivers
url = https://github.com/PX4/GpsDrivers.git
[submodule "libs/mavlink/include/mavlink/v2.0"]
path = libs/mavlink/include/mavlink/v2.0
Expand Down
7 changes: 4 additions & 3 deletions src/Comms/LinkManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
#include "GPSManager.h"
#include "PositionManager.h"
#include "UdpIODevice.h"
#include "GPSRtk.h"
#endif

#ifdef QT_DEBUG
Expand Down Expand Up @@ -852,7 +853,7 @@ void LinkManager::_addSerialAutoConnectLink()
case QGCSerialPortInfo::BoardTypeRTKGPS:
qCDebug(LinkManagerLog) << "RTK GPS auto-connected" << portInfo.portName().trimmed();
_autoConnectRTKPort = portInfo.systemLocation();
_toolbox->gpsManager()->connectGPS(portInfo.systemLocation(), boardName);
GPSManager::instance()->gpsRtk()->connectGPS(portInfo.systemLocation(), boardName);
break;
default:
qCWarning(LinkManagerLog) << "Internal error: Unknown board type" << boardType;
Expand All @@ -876,7 +877,7 @@ void LinkManager::_addSerialAutoConnectLink()
// Check for RTK GPS connection gone
if (!_autoConnectRTKPort.isEmpty() && !currentPorts.contains(_autoConnectRTKPort)) {
qCDebug(LinkManagerLog) << "RTK GPS disconnected" << _autoConnectRTKPort;
_toolbox->gpsManager()->disconnectGPS();
GPSManager::instance()->gpsRtk()->disconnectGPS();
_autoConnectRTKPort.clear();
}
}
Expand All @@ -900,7 +901,7 @@ bool LinkManager::_allowAutoConnectToBoard(QGCSerialPortInfo::BoardType_t boardT
}
break;
case QGCSerialPortInfo::BoardTypeRTKGPS:
if (_autoConnectSettings->autoConnectRTKGPS()->rawValue().toBool() && !_toolbox->gpsManager()->connected()) {
if (_autoConnectSettings->autoConnectRTKGPS()->rawValue().toBool() && !GPSManager::instance()->gpsRtk()->connected()) {
return true;
}
break;
Expand Down
19 changes: 8 additions & 11 deletions src/GPS/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -42,23 +42,20 @@ qt_add_library(GPSDrivers STATIC
${px4-gpsdrivers_SOURCE_DIR}/src/unicore.h
)

target_link_libraries(GPSDrivers
PUBLIC
Qt6::Core
Utilities
)

target_include_directories(GPSDrivers PUBLIC ${px4-gpsdrivers_SOURCE_DIR})
target_link_libraries(GPSDrivers PUBLIC Qt6::Core)

target_compile_definitions(GPSDrivers PUBLIC GPS_DEFINITIONS_HEADER=<${CMAKE_CURRENT_SOURCE_DIR}/definitions.h>)

target_include_directories(GPSDrivers PUBLIC ${px4-gpsdrivers_SOURCE_DIR}/src)

target_sources(GPS
PRIVATE
GPSManager.cc
GPSManager.h
GPSPositionMessage.h
GPSProvider.cc
GPSProvider.h
GPSRtk.cc
GPSRtk.h
RTCMMavlink.cc
RTCMMavlink.h
satellite_info.h
Expand All @@ -69,14 +66,14 @@ target_sources(GPS
target_link_libraries(GPS
PRIVATE
Comms
GPSDrivers
MAVLink
QGC
Settings
Utilities
Vehicle
PUBLIC
Qt6::Core
MAVLink
QGC
GPSDrivers
)

target_include_directories(GPS PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
137 changes: 12 additions & 125 deletions src/GPS/GPSManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -7,142 +7,29 @@
*
****************************************************************************/


#include "GPSManager.h"
#include "GPSProvider.h"
#include "QGCApplication.h"
#include "SettingsManager.h"
#include "RTKSettings.h"
#include "GPSRTKFactGroup.h"
#include "RTCMMavlink.h"
#include "GPSRtk.h"
#include "QGCLoggingCategory.h"

#include <QtCore/qapplicationstatic.h>

GPSManager::GPSManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
{
qRegisterMetaType<GPSPositionMessage>();
qRegisterMetaType<GPSSatelliteMessage>();
}

GPSManager::~GPSManager()
{
disconnectGPS();

delete _gpsRtkFactGroup;
_gpsRtkFactGroup = nullptr;
}

void GPSManager::setToolbox(QGCToolbox *toolbox)
{
QGCTool::setToolbox(toolbox);

_gpsRtkFactGroup = new GPSRTKFactGroup(this);
QGC_LOGGING_CATEGORY(GPSManagerLog, "qgc.gps.gpsmanager")

connect(this, &GPSManager::onConnect, this, &GPSManager::_onGPSConnect);
connect(this, &GPSManager::onDisconnect, this, &GPSManager::_onGPSDisconnect);
connect(this, &GPSManager::surveyInStatus, this, &GPSManager::_gpsSurveyInStatus);
connect(this, &GPSManager::satelliteUpdate, this, &GPSManager::_gpsNumSatellites);
}

void GPSManager::_onGPSConnect()
{
_gpsRtkFactGroup->connected()->setRawValue(true);
}

void GPSManager::_onGPSDisconnect()
{
_gpsRtkFactGroup->connected()->setRawValue(false);
}
Q_APPLICATION_STATIC(GPSManager, _gpsManager);

void GPSManager::_gpsSurveyInStatus(float duration, float accuracyMM, double latitude, double longitude, float altitude, bool valid, bool active)
GPSManager::GPSManager(QObject *parent)
: QObject(parent)
, _gpsRtk(new GPSRtk(this))
{
_gpsRtkFactGroup->currentDuration()->setRawValue(duration);
_gpsRtkFactGroup->currentAccuracy()->setRawValue(static_cast<double>(accuracyMM) / 1000.0);
_gpsRtkFactGroup->currentLatitude()->setRawValue(latitude);
_gpsRtkFactGroup->currentLongitude()->setRawValue(longitude);
_gpsRtkFactGroup->currentAltitude()->setRawValue(altitude);
_gpsRtkFactGroup->valid()->setRawValue(valid);
_gpsRtkFactGroup->active()->setRawValue(active);
// qCDebug(GPSManagerLog) << Q_FUNC_INFO << this;
}

void GPSManager::_gpsNumSatellites(int numSatellites)
{
_gpsRtkFactGroup->numSatellites()->setRawValue(numSatellites);
}

void GPSManager::connectGPS(const QString& device, const QString& gps_type)
{
RTKSettings* rtkSettings = qgcApp()->toolbox()->settingsManager()->rtkSettings();

GPSProvider::GPSType 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";
}

disconnectGPS();
_requestGpsStop = false;
_gpsProvider = new GPSProvider(device,
type,
true, /* enableSatInfo */
rtkSettings->surveyInAccuracyLimit()->rawValue().toDouble(),
rtkSettings->surveyInMinObservationDuration()->rawValue().toInt(),
rtkSettings->useFixedBasePosition()->rawValue().toBool(),
rtkSettings->fixedBasePositionLatitude()->rawValue().toDouble(),
rtkSettings->fixedBasePositionLongitude()->rawValue().toDouble(),
rtkSettings->fixedBasePositionAltitude()->rawValue().toFloat(),
rtkSettings->fixedBasePositionAccuracy()->rawValue().toFloat(),
_requestGpsStop);
_gpsProvider->start();

//create RTCM device
_rtcmMavlink = new RTCMMavlink(*_toolbox);

connect(_gpsProvider, &GPSProvider::RTCMDataUpdate, _rtcmMavlink, &RTCMMavlink::RTCMDataUpdate);

//test: connect to position update
connect(_gpsProvider, &GPSProvider::positionUpdate, this, &GPSManager::GPSPositionUpdate);
connect(_gpsProvider, &GPSProvider::satelliteInfoUpdate, this, &GPSManager::GPSSatelliteUpdate);
connect(_gpsProvider, &GPSProvider::finished, this, &GPSManager::onDisconnect);
connect(_gpsProvider, &GPSProvider::surveyInStatus, this, &GPSManager::surveyInStatus);

emit onConnect();
}

void GPSManager::disconnectGPS(void)
GPSManager::~GPSManager()
{
if (_gpsProvider) {
_requestGpsStop = true;
//Note that we need a relatively high timeout to be sure the GPS thread finished.
if (!_gpsProvider->wait(2000)) {
qWarning() << "Failed to wait for GPS thread exit. Consider increasing the timeout";
}
delete(_gpsProvider);
}
if (_rtcmMavlink) {
delete(_rtcmMavlink);
}
_gpsProvider = nullptr;
_rtcmMavlink = nullptr;
// qCDebug(GPSManagerLog) << Q_FUNC_INFO << this;
}

bool GPSManager::connected() const { return _gpsProvider && _gpsProvider->isRunning(); }

FactGroup* GPSManager::gpsRtkFactGroup(void) { return _gpsRtkFactGroup; }

void GPSManager::GPSPositionUpdate(GPSPositionMessage msg)
{
qCDebug(RTKGPSLog) << QString("GPS: got position update: alt=%1, long=%2, lat=%3").arg(msg.position_data.altitude_msl_m).arg(msg.position_data.longitude_deg).arg(msg.position_data.latitude_deg);
}
void GPSManager::GPSSatelliteUpdate(GPSSatelliteMessage msg)
GPSManager *GPSManager::instance()
{
qCDebug(RTKGPSLog) << QString("GPS: got satellite info update, %1 satellites").arg((int)msg.satellite_data.count);
emit satelliteUpdate(msg.satellite_data.count);
return _gpsManager();
}
49 changes: 10 additions & 39 deletions src/GPS/GPSManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,56 +7,27 @@
*
****************************************************************************/


#pragma once

#include "QGCToolbox.h"
#include "GPSPositionMessage.h"

#include <QtCore/QString>
#include <QtCore/QLoggingCategory>
#include <QtCore/QObject>

class GPSRTKFactGroup;
class FactGroup;
class RTCMMavlink;
class GPSProvider;
Q_DECLARE_LOGGING_CATEGORY(GPSManagerLog)

/**
** class GPSManager
* handles a GPS provider and RTK
*/
class GPSManager : public QGCTool
class GPSRtk;

class GPSManager : public QObject
{
Q_OBJECT

public:
GPSManager(QGCApplication* app, QGCToolbox* toolbox);
GPSManager(QObject *parent = nullptr);
~GPSManager();

void setToolbox(QGCToolbox* toolbox) override;
static GPSManager *instance();

void connectGPS (const QString& device, const QString& gps_type);
void disconnectGPS (void);
bool connected (void) const;
FactGroup* gpsRtkFactGroup(void);

signals:
void onConnect();
void onDisconnect();
void surveyInStatus(float duration, float accuracyMM, double latitude, double longitude, float altitude, bool valid, bool active);
void satelliteUpdate(int numSats);

private slots:
void GPSPositionUpdate(GPSPositionMessage msg);
void GPSSatelliteUpdate(GPSSatelliteMessage msg);
void _onGPSConnect(void);
void _onGPSDisconnect(void);
void _gpsSurveyInStatus(float duration, float accuracyMM, double latitude, double longitude, float altitude, bool valid, bool active);
void _gpsNumSatellites(int numSatellites);
GPSRtk *gpsRtk() { return _gpsRtk; }

private:
GPSProvider* _gpsProvider = nullptr;
RTCMMavlink* _rtcmMavlink = nullptr;
GPSRTKFactGroup* _gpsRtkFactGroup = nullptr;

std::atomic_bool _requestGpsStop; ///< signals the thread to quit
GPSRtk *_gpsRtk = nullptr;
};
32 changes: 0 additions & 32 deletions src/GPS/GPSPositionMessage.h

This file was deleted.

Loading
Loading