QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MessageIntervalManager.h
Go to the documentation of this file.
1#pragma once
2
3#include <utility>
4
5#include <QtCore/QHash>
6#include <QtCore/QMultiHash>
7#include <QtCore/QObject>
8
9#include "VehicleTypes.h"
10
11class MavCommandQueue;
13class Vehicle;
14
20class MessageIntervalManager : public QObject, public VehicleTypes
21{
22 Q_OBJECT
23
24public:
25 MessageIntervalManager(Vehicle* vehicle, MavCommandQueue* commandQueue, RequestMessageCoordinator* reqMsgCoord);
26
29 int32_t getMessageRate(uint8_t compId, uint16_t msgId);
30
33 void setMessageRate(uint8_t compId, uint16_t msgId, int32_t rate);
34
37 void handleMessageInterval(const mavlink_message_t& message);
38
39signals:
40 void mavlinkMsgIntervalsChanged(uint8_t compid, uint16_t msgId, int32_t rate);
41
42private:
43 using MavCompMsgId = std::pair<uint8_t /* compId */, uint16_t /* msgId */>;
44
45 static void _requestMessageIntervalResultHandler(void* resultHandlerData, MAV_RESULT result, RequestMessageResultHandlerFailureCode_t failureCode, const mavlink_message_t& message);
46 static void _setMessageRateCommandResultHandler(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode);
47
48 void _requestMessageInterval(uint8_t compId, uint16_t msgId);
49
50 Vehicle* _vehicle = nullptr;
51 MavCommandQueue* _commandQueue = nullptr;
52 RequestMessageCoordinator* _reqMsgCoord = nullptr;
53
54 QHash<MavCompMsgId, int32_t> _mavlinkMsgIntervals;
55 QMultiHash<uint8_t, uint16_t> _unsupportedMessageIds;
56};
struct __mavlink_message mavlink_message_t
struct __mavlink_command_ack_t mavlink_command_ack_t
void handleMessageInterval(const mavlink_message_t &message)
void mavlinkMsgIntervalsChanged(uint8_t compid, uint16_t msgId, int32_t rate)
void setMessageRate(uint8_t compId, uint16_t msgId, int32_t rate)
int32_t getMessageRate(uint8_t compId, uint16_t msgId)
RequestMessageResultHandlerFailureCode_t