QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
EventHandler.cc
Go to the documentation of this file.
1#include "EventHandler.h"
3#include "LibEvents.h"
4
5#include <QtCore/QSharedPointer>
6#include <QtCore/QTimer>
7#include <QtCore/QVector>
8
9#include <utility>
10
11QGC_LOGGING_CATEGORY(EventHandlerLog, "MAVLink.LibEvents.EventHandler")
12
14{
16 const QString &profile,
17 handle_event_f handleEventCB_,
18 send_request_event_message_f sendRequestCB_,
19 uint8_t ourSystemId, uint8_t ourComponentId,
20 uint8_t systemId, uint8_t componentId)
21 : q(q_)
22 , timer(q_)
23 , handleEventCB(std::move(handleEventCB_))
24 , sendRequestCB(std::move(sendRequestCB_))
25 , compid(componentId)
26 {
27 auto error_cb = [this](int num_events_lost) {
28 healthAndArmingChecks.reset();
29 qCWarning(EventHandlerLog) << "Events got lost:" << num_events_lost
30 << "comp_id:" << compid;
31 };
32
33 auto timeout_cb = [this](int timeout_ms) {
34 if (timeout_ms < 0) {
35 timer.stop();
36 } else {
37 timer.setSingleShot(true);
38 timer.start(timeout_ms);
39 }
40 };
41
42 parser.setProfile(profile.toStdString());
43 parser.formatters().url = [](const std::string &content, const std::string &link) {
44 return "<a href=\"" + link + "\">" + content + "</a>";
45 };
46 parser.formatters().param = [](const std::string &content) {
47 return "<a href=\"param://" + content + "\">" + content + "</a>";
48 };
49 parser.formatters().escape = [](const std::string &str) {
50 return QString::fromStdString(str).toHtmlEscaped().toStdString();
51 };
52
53 events::ReceiveProtocol::Callbacks callbacks{
54 error_cb,
55 sendRequestCB,
56 std::bind(&Impl::gotEvent, this, std::placeholders::_1),
57 timeout_cb};
58 protocol = new events::ReceiveProtocol(callbacks, ourSystemId, ourComponentId,
59 systemId, componentId);
60
61 QObject::connect(&timer, &QTimer::timeout, q, [this]() { protocol->timerEvent(); });
62 }
63
64 ~Impl() { delete protocol; }
65
66 void gotEvent(const mavlink_event_t &event);
67
69 events::ReceiveProtocol *protocol{nullptr};
70 QTimer timer;
71 events::parser::Parser parser;
72 events::HealthAndArmingChecks healthAndArmingChecks;
73 bool healthAndArmingChecksValid{false};
74 QVector<mavlink_event_t> pendingEvents;
77 const uint8_t compid;
78};
79
81{
82 if (!parser.hasDefinitions()) {
83 if (pendingEvents.size() > 50) { // limit size (not expected to happen)
84 pendingEvents.clear();
85 }
86 qCDebug(EventHandlerLog) << "No metadata, queuing event, ID:" << event.id
87 << "num pending:" << pendingEvents.size();
88 pendingEvents.push_back(event);
89 return;
90 }
91
92 std::unique_ptr<events::parser::ParsedEvent> parsed_event = parser.parse(events::EventType(event));
93 if (parsed_event == nullptr) {
94 qCWarning(EventHandlerLog) << "Got Event w/o known metadata: ID:" << event.id
95 << "comp id:" << compid;
96 return;
97 }
98
99 qCDebug(EventHandlerLog) << "Got Event: ID:" << parsed_event->id()
100 << "namespace:" << parsed_event->eventNamespace().c_str()
101 << "name:" << parsed_event->name().c_str()
102 << "msg:" << parsed_event->message().c_str();
103
104 if (healthAndArmingChecks.handleEvent(*parsed_event)) {
107 }
108 handleEventCB(std::move(parsed_event));
109}
110
111/*===========================================================================*/
112
114 const QString &profile,
115 handle_event_f handleEventCB,
116 send_request_event_message_f sendRequestCB,
117 uint8_t ourSystemId, uint8_t ourComponentId,
118 uint8_t systemId, uint8_t componentId)
119 : QObject(parent)
120 , _impl(std::make_unique<Impl>(this, profile,
121 std::move(handleEventCB),
122 std::move(sendRequestCB),
123 ourSystemId, ourComponentId,
124 systemId, componentId))
125{
126}
127
129
131{
132 _impl->protocol->processMessage(message);
133}
134
135void EventHandler::setMetadata(const QString &metadataJsonFileName)
136{
137 if (_impl->parser.loadDefinitionsFile(metadataJsonFileName.toStdString())) {
138 if (_impl->parser.hasDefinitions()) {
139 // Flush queued events now that metadata is available.
140 for (const auto &event : _impl->pendingEvents) {
141 _impl->gotEvent(event);
142 }
143 _impl->pendingEvents.clear();
144 }
145 } else {
146 qCWarning(EventHandlerLog) << "Failed to load events JSON metadata file";
147 }
148}
149
150const events::HealthAndArmingChecks *EventHandler::healthAndArmingChecks() const
151{
152 return &_impl->healthAndArmingChecks;
153}
154
156{
157 return _impl->healthAndArmingChecksValid;
158}
159
160int EventHandler::getModeGroup(int32_t customMode) const
161{
162 events::parser::Parser::NavigationModeGroups groups = _impl->parser.navigationModeGroups(_impl->compid);
163 for (const auto &groupIter : groups.groups) {
164 if (groupIter.second.find(customMode) != groupIter.second.end()) {
165 return groupIter.first;
166 }
167 }
168 return -1;
169}
170
172{
173 const auto &protocols = _impl->parser.supportedProtocols(_impl->compid);
174 return protocols.find("health_and_arming_check") != protocols.end();
175}
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
struct __mavlink_event_t mavlink_event_t
Drives the MAVLink events protocol for a single component.
EventHandler(QObject *parent, const QString &profile, handle_event_f handleEventCB, send_request_event_message_f sendRequestCB, uint8_t ourSystemId, uint8_t ourComponentId, uint8_t systemId, uint8_t componentId)
void handleEvents(const mavlink_message_t &message)
void healthAndArmingChecksUpdated()
void setMetadata(const QString &metadataJsonFileName)
const events::HealthAndArmingChecks * healthAndArmingChecks() const
std::function< void(std::unique_ptr< events::parser::ParsedEvent >)> handle_event_f
int getModeGroup(int32_t customMode) const
std::function< void(const mavlink_request_event_t &msg)> send_request_event_message_f
bool healthAndArmingChecksSupported() const
bool healthAndArmingCheckResultsValid() const
~EventHandler() override
events::HealthAndArmingChecks healthAndArmingChecks
const uint8_t compid
EventHandler * q
events::parser::Parser parser
Impl(EventHandler *q_, const QString &profile, handle_event_f handleEventCB_, send_request_event_message_f sendRequestCB_, uint8_t ourSystemId, uint8_t ourComponentId, uint8_t systemId, uint8_t componentId)
void gotEvent(const mavlink_event_t &event)
QVector< mavlink_event_t > pendingEvents
stores incoming events until we have the metadata loaded
handle_event_f handleEventCB
send_request_event_message_f sendRequestCB