26 for (
auto it = _events.begin(); it != _events.end(); ++it) {
27 if (it.value()->healthAndArmingCheckResultsValid()) {
28 _updateHealthReport(it.key());
38 return _healthAndArmingCheckReport.get();
43 _eventHandlerForCompId(message.compid).
handleEvents(message);
48 const auto it = _events.find(compid);
49 if (it == _events.end()) {
52 return it.value()->healthAndArmingChecksSupported();
62 int modeGroups[2]{-1, -1};
65 for (
size_t i = 0; i < std::size(modeGroups); ++i) {
67 uint32_t custom_mode{};
68 if (firmwarePlugin->
setFlightMode(modes[i], &base_mode, &custom_mode)) {
70 if (modeGroups[i] == -1) {
71 qCDebug(MAVLinkEventManagerLog) <<
"Failed to get mode group for mode"
73 <<
"(Might not be in metadata)";
77 _healthAndArmingCheckReport->setModeGroups(modeGroups[0], modeGroups[1]);
80EventHandler &MAVLinkEventManager::_eventHandlerForCompId(uint8_t compid)
82 auto eventData = _events.find(compid);
83 if (eventData != _events.end()) {
84 return *eventData->data();
96 sharedLink->mavlinkChannel(),
102 const QString profile = QStringLiteral(
"dev");
104 QSharedPointer<EventHandler> eventHandler{
new EventHandler(
107 std::bind(&MAVLinkEventManager::_handleEvent,
this, compid, std::placeholders::_1),
108 sendRequestEventMessageCB,
113 eventData = _events.insert(compid, eventHandler);
116 _updateHealthReport(compid);
119 return *eventData->data();
122void MAVLinkEventManager::_updateHealthReport(uint8_t compid)
124 const auto it = _events.find(compid);
125 if (it == _events.end()) {
129 _healthAndArmingCheckReport->update(compid, *it.value(), it.value()->getModeGroup(effectiveMode));
132void MAVLinkEventManager::_handleEvent(uint8_t comp_id, std::unique_ptr<events::parser::ParsedEvent> event)
135 switch (events::externalLogLevel(event->eventData().log_levels)) {
136 case events::Log::Emergency: severity = MAV_SEVERITY_EMERGENCY;
break;
137 case events::Log::Alert: severity = MAV_SEVERITY_ALERT;
break;
138 case events::Log::Critical: severity = MAV_SEVERITY_CRITICAL;
break;
139 case events::Log::Error: severity = MAV_SEVERITY_ERROR;
break;
140 case events::Log::Warning: severity = MAV_SEVERITY_WARNING;
break;
141 case events::Log::Notice: severity = MAV_SEVERITY_NOTICE;
break;
142 case events::Log::Info: severity = MAV_SEVERITY_INFO;
break;
147 if (event->group() ==
"health" || event->group() ==
"arming_check") {
150 if (event->group() ==
"calibration") {
151 qCDebug(MAVLinkEventManagerLog) <<
"Calibration Event Receieved";
156 if (event->group() !=
"default" || severity == -1) {
160 std::string message =
event->message();
161 std::string description =
event->description();
163 if (event->type() ==
"append_health_and_arming_messages" && event->numArguments() > 0) {
164 const uint32_t customMode =
event->argumentValue(0).value.val_uint32_t;
165 EventHandler &handler = _eventHandlerForCompId(comp_id);
167 const std::vector<events::HealthAndArmingChecks::Check> checks = handler.
healthAndArmingChecks()->results().checks(modeGroup);
169 std::vector<std::string> messageChecks;
170 for (
const auto &check : checks) {
171 if (events::externalLogLevel(check.log_levels) <= events::Log::Warning) {
172 messageChecks.push_back(check.message);
175 if (messageChecks.empty()) {
176 for (
const auto &check : checks) {
177 messageChecks.push_back(check.message);
180 if (!message.empty() && !messageChecks.empty()) {
183 if (messageChecks.size() == 1) {
184 message += messageChecks[0];
186 for (
const auto &messageCheck : messageChecks) {
187 message +=
"- " + messageCheck +
"\n";
192 if (message.empty()) {
196 const QString text = QString::fromStdString(message);
199 if (_vehicle->
px4Firmware() && text.startsWith(QStringLiteral(
"[cal]"))) {
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
struct __mavlink_request_event_t mavlink_request_event_t
Drives the MAVLink events protocol for a single component.
void handleEvents(const mavlink_message_t &message)
void healthAndArmingChecksUpdated()
void setMetadata(const QString &metadataJsonFileName)
const events::HealthAndArmingChecks * healthAndArmingChecks() const
int getModeGroup(int32_t customMode) const
The FirmwarePlugin class represents the methods and objects which are specific to a certain Firmware ...
virtual bool setFlightMode(const QString &flightMode, uint8_t *base_mode, uint32_t *custom_mode) const
virtual QString takeOffFlightMode() const
Returns the flight mode for TakeOff.
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
static int getComponentId()
static MAVLinkProtocol * instance()
WeakLinkInterfacePtr primaryLink() const
uint32_t effectiveCustomMode() const
QString missionFlightMode() const
VehicleLinkManager * vehicleLinkManager()
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
void flightModeChanged(const QString &flightMode)