4#include <QtCore/QObject>
5#include <QtCore/QSharedPointer>
6#include <QtCore/QString>
40 void setMetadata(uint8_t compid,
const QString &metadataJsonFileName);
53 void _handleEvent(uint8_t comp_id, std::unique_ptr<events::parser::ParsedEvent> event);
54 void _updateHealthReport(uint8_t compid);
57 QMap<uint8_t, QSharedPointer<EventHandler>> _events;
58 std::unique_ptr<HealthAndArmingCheckReport> _healthAndArmingCheckReport;
struct __mavlink_message mavlink_message_t
Drives the MAVLink events protocol for a single component.
Owns per-component EventHandler instances and drives the Health & Arming Check report.
void statusTextMessageFromEvent(uint8_t compid, int severity, const QString &text, const QString &description)
void setMetadata(uint8_t compid, const QString &metadataJsonFileName)
void handleEventMessage(const mavlink_message_t &message)
bool healthAndArmingChecksSupported(uint8_t compid) const
~MAVLinkEventManager() override
HealthAndArmingCheckReport * healthAndArmingCheckReport() const