QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
EventHandler.cc
Go to the documentation of this file.
1#include "EventHandler.h"
2
3#include <QtCore/QSharedPointer>
4
5Q_DECLARE_METATYPE(QSharedPointer<events::parser::ParsedEvent>);
6
7EventHandler::EventHandler(QObject* parent, const QString& profile, handle_event_f handleEventCB,
9 uint8_t ourSystemId, uint8_t ourComponentId, uint8_t systemId, uint8_t componentId)
10 : QObject(parent), _timer(parent),
11 _handleEventCB(handleEventCB),
12 _sendRequestCB(sendRequestCB),
13 _compid(componentId)
14{
15 auto error_cb = [componentId, this](int num_events_lost) {
16 _healthAndArmingChecks.reset();
17 qCWarning(EventsLog) << "Events got lost:" << num_events_lost << "comp_id:" << componentId;
18 };
19
20 auto timeout_cb = [this](int timeout_ms) {
21 if (timeout_ms < 0) {
22 _timer.stop();
23 } else {
24 _timer.setSingleShot(true);
25 _timer.start(timeout_ms);
26 }
27 };
28
29 _parser.setProfile(profile.toStdString());
30
31 _parser.formatters().url = [](const std::string& content, const std::string& link) {
32 return "<a href=\""+link+"\">"+content+"</a>"; };
33
34 _parser.formatters().param = [](const std::string& content) {
35 return "<a href=\"param://"+content+"\">"+content+"</a>"; };
36
37 _parser.formatters().escape = [](const std::string& str) {
38 return QString::fromStdString(str).toHtmlEscaped().toStdString(); };
39
40 events::ReceiveProtocol::Callbacks callbacks{error_cb, _sendRequestCB,
41 std::bind(&EventHandler::gotEvent, this, std::placeholders::_1), timeout_cb};
42 _protocol = new events::ReceiveProtocol(callbacks, ourSystemId, ourComponentId, systemId, componentId);
43
44 connect(&_timer, &QTimer::timeout, this, [this]() { _protocol->timerEvent(); });
45
46 qRegisterMetaType<QSharedPointer<events::parser::ParsedEvent>>("ParsedEvent");
47}
48
50{
51 delete _protocol;
52}
53
54void EventHandler::gotEvent(const mavlink_event_t& event)
55{
56 if (!_parser.hasDefinitions()) {
57 if (_pendingEvents.size() > 50) { // limit size (not expected to happen)
58 _pendingEvents.clear();
59 }
60 qCDebug(EventsLog) << "No metadata, queuing event, ID:" << event.id << "num pending:" << _pendingEvents.size();
61 _pendingEvents.push_back(event);
62 return;
63 }
64
65 std::unique_ptr<events::parser::ParsedEvent> parsed_event = _parser.parse(events::EventType(event));
66 if (parsed_event == nullptr) {
67 qCWarning(EventsLog) << "Got Event w/o known metadata: ID:" << event.id << "comp id:" << _compid;
68 return;
69 }
70
71 qCDebug(EventsLog) << "Got Event: ID:" << parsed_event->id() << "namespace:" << parsed_event->eventNamespace().c_str() <<
72 "name:" << parsed_event->name().c_str() << "msg:" << parsed_event->message().c_str();
73
74 if (_healthAndArmingChecks.handleEvent(*parsed_event)) {
75 _healthAndArmingChecksValid = true;
77 }
78 _handleEventCB(std::move(parsed_event));
79}
80
82{
83 _protocol->processMessage(message);
84}
85
86void EventHandler::setMetadata(const QString &metadataJsonFileName)
87{
88 if (_parser.loadDefinitionsFile(metadataJsonFileName.toStdString())) {
89 if (_parser.hasDefinitions()) {
90 // do we have queued events?
91 for (const auto& event : _pendingEvents) {
92 gotEvent(event);
93 }
94 _pendingEvents.clear();
95 }
96 } else {
97 qCWarning(EventsLog) << "Failed to load events JSON metadata file";
98 }
99}
100
101int EventHandler::getModeGroup(int32_t customMode)
102{
103 events::parser::Parser::NavigationModeGroups groups = _parser.navigationModeGroups(_compid);
104 for (auto groupIter : groups.groups) {
105 if (groupIter.second.find(customMode) != groupIter.second.end()) {
106 return groupIter.first;
107 }
108 }
109 return -1;
110}
Q_DECLARE_METATYPE(QSharedPointer< events::parser::ParsedEvent >)
struct __mavlink_message mavlink_message_t
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)
std::function< void(std::unique_ptr< events::parser::ParsedEvent >)> handle_event_f
std::function< void(const mavlink_request_event_t &msg)> send_request_event_message_f
int getModeGroup(int32_t customMode)