1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
/****************************************************************************
*
* (c) 2009-2016 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.
*
****************************************************************************/
#pragma once
#include <QObject>
#include <QElapsedTimer>
#include "QGCToolbox.h"
#include "MAVLinkProtocol.h"
/**
** class RTCMMavlink
* Receives RTCM updates and sends them via MAVLINK to the device
*/
class RTCMMavlink : public QObject
{
Q_OBJECT
public:
RTCMMavlink(QGCToolbox& toolbox);
//TODO: API to select device(s)?
public slots:
void RTCMDataUpdate(QByteArray message);
private:
void sendMessageToVehicle(const mavlink_gps_rtcm_data_t& msg);
QGCToolbox& _toolbox;
QElapsedTimer _bandwidthTimer;
int _bandwidthByteCounter = 0;
};