5#include <QtCore/QSharedPointer>
6#include <QtCore/QTimer>
7#include <QtCore/QVector>
16 const QString &profile,
19 uint8_t ourSystemId, uint8_t ourComponentId,
20 uint8_t systemId, uint8_t componentId)
23 , handleEventCB(std::move(handleEventCB_))
24 , sendRequestCB(std::move(sendRequestCB_))
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;
33 auto timeout_cb = [
this](
int timeout_ms) {
37 timer.setSingleShot(
true);
38 timer.start(timeout_ms);
42 parser.setProfile(profile.toStdString());
43 parser.formatters().url = [](
const std::string &content,
const std::string &link) {
44 return "<a href=\"" + link +
"\">" + content +
"</a>";
46 parser.formatters().param = [](
const std::string &content) {
47 return "<a href=\"param://" + content +
"\">" + content +
"</a>";
49 parser.formatters().escape = [](
const std::string &str) {
50 return QString::fromStdString(str).toHtmlEscaped().toStdString();
53 events::ReceiveProtocol::Callbacks callbacks{
56 std::bind(&Impl::gotEvent,
this, std::placeholders::_1),
58 protocol =
new events::ReceiveProtocol(callbacks, ourSystemId, ourComponentId,
59 systemId, componentId);
61 QObject::connect(&timer, &QTimer::timeout, q, [
this]() { protocol->timerEvent(); });
69 events::ReceiveProtocol *protocol{
nullptr};
73 bool healthAndArmingChecksValid{
false};
82 if (!
parser.hasDefinitions()) {
86 qCDebug(EventHandlerLog) <<
"No metadata, queuing event, ID:" <<
event.id
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
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();
114 const QString &profile,
117 uint8_t ourSystemId, uint8_t ourComponentId,
118 uint8_t systemId, uint8_t componentId)
120 , _impl(std::make_unique<
Impl>(this, profile,
121 std::move(handleEventCB),
122 std::move(sendRequestCB),
123 ourSystemId, ourComponentId,
124 systemId, componentId))
132 _impl->protocol->processMessage(message);
137 if (_impl->parser.loadDefinitionsFile(metadataJsonFileName.toStdString())) {
138 if (_impl->parser.hasDefinitions()) {
140 for (
const auto &event : _impl->pendingEvents) {
141 _impl->gotEvent(event);
143 _impl->pendingEvents.clear();
146 qCWarning(EventHandlerLog) <<
"Failed to load events JSON metadata file";
152 return &_impl->healthAndArmingChecks;
157 return _impl->healthAndArmingChecksValid;
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;
173 const auto &protocols = _impl->parser.supportedProtocols(_impl->compid);
174 return protocols.find(
"health_and_arming_check") != protocols.end();
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
events::HealthAndArmingChecks healthAndArmingChecks
events::parser::Parser parser
bool healthAndArmingChecksValid
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