QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
RTCMMavlink.cc
Go to the documentation of this file.
2#include "RTCMMavlink.h"
3#include "MAVLinkProtocol.h"
6#include "Vehicle.h"
8
9QGC_LOGGING_CATEGORY(RTCMMavlinkLog, "GPS.RTCMMavlink")
10
11RTCMMavlink::RTCMMavlink(QObject *parent)
12 : QObject(parent)
13{
14 // qCDebug(RTCMMavlinkLog) << Q_FUNC_INFO << this;
15
16 _bandwidthTimer.start();
17}
18
20{
21 // qCDebug(RTCMMavlinkLog) << Q_FUNC_INFO << this;
22}
23
24void RTCMMavlink::RTCMDataUpdate(QByteArrayView data)
25{
26 _calculateBandwith(data.size());
27
28 mavlink_gps_rtcm_data_t gpsRtcmData{};
29
30 static constexpr qsizetype maxMessageLength = MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN;
31 if (data.size() < maxMessageLength) {
32 gpsRtcmData.len = data.size();
33 gpsRtcmData.flags = (_sequenceId & 0x1FU) << 3;
34 (void) memcpy(&gpsRtcmData.data, data.data(), data.size());
35 _sendMessageToVehicle(gpsRtcmData);
36 } else {
37 uint8_t fragmentId = 0;
38 qsizetype start = 0;
39 while (start < data.size()) {
40 gpsRtcmData.flags = 0x01U; // LSB set indicates message is fragmented
41 gpsRtcmData.flags |= fragmentId++ << 1; // Next 2 bits are fragment id
42 gpsRtcmData.flags |= (_sequenceId & 0x1FU) << 3; // Next 5 bits are sequence id
43
44 const qsizetype length = std::min(data.size() - start, maxMessageLength);
45 gpsRtcmData.len = length;
46
47 (void) memcpy(gpsRtcmData.data, data.constData() + start, length);
48 _sendMessageToVehicle(gpsRtcmData);
49
50 start += length;
51 }
52 }
53
54 ++_sequenceId;
55}
56
57void RTCMMavlink::_sendMessageToVehicle(const mavlink_gps_rtcm_data_t &data)
58{
60 for (qsizetype i = 0; i < vehicles->count(); i++) {
61 Vehicle* const vehicle = qobject_cast<Vehicle*>(vehicles->get(i));
62 const SharedLinkInterfacePtr sharedLink = vehicle->vehicleLinkManager()->primaryLink().lock();
63 if (sharedLink) {
64 mavlink_message_t message;
65 (void) mavlink_msg_gps_rtcm_data_encode_chan(
68 sharedLink->mavlinkChannel(),
69 &message,
70 &data
71 );
72 (void) vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), message);
73 }
74 }
75}
76
77void RTCMMavlink::_calculateBandwith(qsizetype bytes)
78{
79 if (!_bandwidthTimer.isValid()) {
80 return;
81 }
82
83 _bandwidthByteCounter += bytes;
84
85 const qint64 elapsed = _bandwidthTimer.elapsed();
86 if (elapsed > 1000) {
87 qCDebug(RTCMMavlinkLog) << QStringLiteral("RTCM bandwidth: %1 kB/s").arg((_bandwidthByteCounter * 1000.0) / elapsed / 1024.0, 0, 'f', 3);
88 (void) _bandwidthTimer.restart();
89 _bandwidthByteCounter = 0;
90 }
91}
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
static int getComponentId()
static MAVLinkProtocol * instance()
int getSystemId() const
static MultiVehicleManager * instance()
QmlObjectListModel * vehicles() const
Q_INVOKABLE QObject * get(int index)
int count() const override final
WeakLinkInterfacePtr primaryLink() const
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:575
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
Definition Vehicle.cc:1389