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
11
class
MavCommandQueue
;
12
class
RequestMessageCoordinator
;
13
class
Vehicle
;
14
20
class
MessageIntervalManager
:
public
QObject,
public
VehicleTypes
21
{
22
Q_OBJECT
23
24
public
:
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
39
signals:
40
void
mavlinkMsgIntervalsChanged
(uint8_t compid, uint16_t msgId, int32_t rate);
41
42
private
:
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
};
mavlink_message_t
struct __mavlink_message mavlink_message_t
Definition
QGCCorePlugin.h:22
mavlink_command_ack_t
struct __mavlink_command_ack_t mavlink_command_ack_t
Definition
QGCMAVLinkTypes.h:23
VehicleTypes.h
MavCommandQueue
Definition
MavCommandQueue.h:21
MessageIntervalManager
Definition
MessageIntervalManager.h:21
MessageIntervalManager::handleMessageInterval
void handleMessageInterval(const mavlink_message_t &message)
Definition
MessageIntervalManager.cc:40
MessageIntervalManager::mavlinkMsgIntervalsChanged
void mavlinkMsgIntervalsChanged(uint8_t compid, uint16_t msgId, int32_t rate)
MessageIntervalManager::setMessageRate
void setMessageRate(uint8_t compId, uint16_t msgId, int32_t rate)
Definition
MessageIntervalManager.cc:107
MessageIntervalManager::getMessageRate
int32_t getMessageRate(uint8_t compId, uint16_t msgId)
Definition
MessageIntervalManager.cc:82
RequestMessageCoordinator
Definition
RequestMessageCoordinator.h:19
Vehicle
Definition
Vehicle.h:82
VehicleTypes
Definition
VehicleTypes.h:16
VehicleTypes::MavCmdResultFailureCode_t
MavCmdResultFailureCode_t
Definition
VehicleTypes.h:17
VehicleTypes::RequestMessageResultHandlerFailureCode_t
RequestMessageResultHandlerFailureCode_t
Definition
VehicleTypes.h:23
src
Vehicle
MessageIntervalManager.h
Generated by
1.9.8