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
21
class
MessageIntervalManager
:
public
QObject,
public
VehicleTypes
22
{
23
Q_OBJECT
24
25
public
:
26
MessageIntervalManager
(
Vehicle
* vehicle,
MavCommandQueue
* commandQueue,
RequestMessageCoordinator
* reqMsgCoord);
27
30
int32_t
getMessageRate
(uint8_t compId, uint16_t msgId);
31
34
void
setMessageRate
(uint8_t compId, uint16_t msgId, int32_t rate);
35
38
void
handleMessageInterval
(
const
mavlink_message_t
& message);
39
40
signals:
41
void
mavlinkMsgIntervalsChanged
(uint8_t compid, uint16_t msgId, int32_t rate);
42
43
private
:
44
using
MavCompMsgId = std::pair<uint8_t
/* compId */
, uint16_t
/* msgId */
>;
45
46
static
void
_requestMessageIntervalResultHandler(
void
* resultHandlerData, MAV_RESULT result,
RequestMessageResultHandlerFailureCode_t
failureCode,
const
mavlink_message_t
& message);
47
static
void
_setMessageRateCommandResultHandler(
void
* resultHandlerData,
int
compId,
const
mavlink_command_ack_t
& ack,
MavCmdResultFailureCode_t
failureCode);
48
49
void
_requestMessageInterval(uint8_t compId, uint16_t msgId);
50
51
Vehicle
* _vehicle =
nullptr
;
52
MavCommandQueue
* _commandQueue =
nullptr
;
53
RequestMessageCoordinator
* _reqMsgCoord =
nullptr
;
54
55
QHash<MavCompMsgId, int32_t> _mavlinkMsgIntervals;
56
QMultiHash<uint8_t, uint16_t> _unsupportedMessageIds;
57
};
mavlink_message_t
struct __mavlink_message mavlink_message_t
Definition
QGCCorePlugin.h:24
mavlink_command_ack_t
struct __mavlink_command_ack_t mavlink_command_ack_t
Definition
QGCMAVLinkTypes.h:23
VehicleTypes.h
MavCommandQueue
Owns the COMMAND_LONG / COMMAND_INT send/retry/ack pipeline for a single Vehicle.
Definition
MavCommandQueue.h:22
MessageIntervalManager
Tracks per-component MAVLink message intervals and mediates SET_MESSAGE_INTERVAL commands plus MESSAG...
Definition
MessageIntervalManager.h:22
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
Coordinates MAV_CMD_REQUEST_MESSAGE workflows: per-component queueing, ack/message correlation,...
Definition
RequestMessageCoordinator.h:20
Vehicle
Definition
Vehicle.h:86
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