QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MAVLinkStreamConfig.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QList>
4#include <QtCore/QLoggingCategory>
5
6Q_DECLARE_LOGGING_CATEGORY(MAVLinkStreamConfigLog)
7
8
12{
13public:
14 using SetMessageIntervalCb = std::function<void(int messageId, int rate)>;
15
16 MAVLinkStreamConfig(const SetMessageIntervalCb &messageIntervalCb);
18
19 void setHighRateRateAndAttitude();
20 void setHighRateVelAndPos();
21 void setHighRateAltAirspeed();
22
23 void restoreDefaults();
24
25 void gotSetMessageIntervalAck();
26private:
27 enum class State {
28 Idle,
29 RestoringDefaults,
30 Configuring
31 };
32
33 struct DesiredStreamRate {
34 const int messageId = 0;
35 const int rate = 0;
36 };
37
38 void restoreNextDefault();
39 void nextDesiredRate();
40 void setNextState(State state);
41
42 State _state{State::Idle};
43 QList<DesiredStreamRate> _desiredRates;
44 QList<int> _changedIds;
45
46 State _nextState{State::Idle};
47 QList<DesiredStreamRate> _nextDesiredRates;
48
49 const SetMessageIntervalCb _messageIntervalCb;
50};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
std::function< void(int messageId, int rate)> SetMessageIntervalCb