QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MAVLinkEventManager.cc
Go to the documentation of this file.
2
3#include "EventHandler.h"
4#include "FirmwarePlugin.h"
6#include "MAVLinkProtocol.h"
8#include "Vehicle.h"
10#include "LibEvents.h"
11
12#include <functional>
13#include <string>
14#include <utility>
15
16QGC_LOGGING_CATEGORY(MAVLinkEventManagerLog, "MAVLink.LibEvents.EventManager")
17
19 : QObject(vehicle)
20 , _vehicle(vehicle)
21 , _healthAndArmingCheckReport(std::make_unique<HealthAndArmingCheckReport>(vehicle))
22{
23 // Re-evaluate the report whenever the vehicle's flight mode changes so the
24 // "can arm for the current mode" derivation stays fresh.
25 connect(_vehicle, &Vehicle::flightModeChanged, this, [this]() {
26 for (auto it = _events.begin(); it != _events.end(); ++it) {
27 if (it.value()->healthAndArmingCheckResultsValid()) {
28 _updateHealthReport(it.key());
29 }
30 }
31 });
32}
33
35
37{
38 return _healthAndArmingCheckReport.get();
39}
40
42{
43 _eventHandlerForCompId(message.compid).handleEvents(message);
44}
45
47{
48 const auto it = _events.find(compid);
49 if (it == _events.end()) {
50 return false;
51 }
52 return it.value()->healthAndArmingChecksSupported();
53}
54
55void MAVLinkEventManager::setMetadata(uint8_t compid, const QString &metadataJsonFileName)
56{
57 EventHandler &handler = _eventHandlerForCompId(compid);
58 handler.setMetadata(metadataJsonFileName);
59
60 // Resolve mode groups for the well-known "takeoff" and "mission" flight
61 // modes. These feed the report's canTakeoff / canStartMission derivations.
62 int modeGroups[2]{-1, -1};
63 FirmwarePlugin *firmwarePlugin = _vehicle->firmwarePlugin();
64 const QString modes[2]{firmwarePlugin->takeOffFlightMode(), _vehicle->missionFlightMode()};
65 for (size_t i = 0; i < std::size(modeGroups); ++i) {
66 uint8_t base_mode{};
67 uint32_t custom_mode{};
68 if (firmwarePlugin->setFlightMode(modes[i], &base_mode, &custom_mode)) {
69 modeGroups[i] = handler.getModeGroup(custom_mode);
70 if (modeGroups[i] == -1) {
71 qCDebug(MAVLinkEventManagerLog) << "Failed to get mode group for mode"
72 << modes[i]
73 << "(Might not be in metadata)";
74 }
75 }
76 }
77 _healthAndArmingCheckReport->setModeGroups(modeGroups[0], modeGroups[1]);
78}
79
80EventHandler &MAVLinkEventManager::_eventHandlerForCompId(uint8_t compid)
81{
82 auto eventData = _events.find(compid);
83 if (eventData != _events.end()) {
84 return *eventData->data();
85 }
86
87 // Send mavlink REQUEST_EVENT on behalf of the protocol state machine.
88 auto sendRequestEventMessageCB = [this](const mavlink_request_event_t &msg) {
89 SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
90 if (!sharedLink) {
91 return;
92 }
93 mavlink_message_t message;
94 mavlink_msg_request_event_encode_chan(MAVLinkProtocol::instance()->getSystemId(),
96 sharedLink->mavlinkChannel(),
97 &message,
98 &msg);
99 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), message);
100 };
101
102 const QString profile = QStringLiteral("dev"); // TODO: should be configurable
103
104 QSharedPointer<EventHandler> eventHandler{new EventHandler(
105 this,
106 profile,
107 std::bind(&MAVLinkEventManager::_handleEvent, this, compid, std::placeholders::_1),
108 sendRequestEventMessageCB,
109 MAVLinkProtocol::instance()->getSystemId(),
111 _vehicle->id(),
112 compid)};
113 eventData = _events.insert(compid, eventHandler);
114
115 connect(eventHandler.data(), &EventHandler::healthAndArmingChecksUpdated, this, [this, compid]() {
116 _updateHealthReport(compid);
117 });
118
119 return *eventData->data();
120}
121
122void MAVLinkEventManager::_updateHealthReport(uint8_t compid)
123{
124 const auto it = _events.find(compid);
125 if (it == _events.end()) {
126 return;
127 }
128 const uint32_t effectiveMode = _vehicle->effectiveCustomMode();
129 _healthAndArmingCheckReport->update(compid, *it.value(), it.value()->getModeGroup(effectiveMode));
130}
131
132void MAVLinkEventManager::_handleEvent(uint8_t comp_id, std::unique_ptr<events::parser::ParsedEvent> event)
133{
134 int severity = -1;
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;
143 default: break;
144 }
145
146 // Health / arming-check events are rendered via HealthAndArmingCheckReport, not as raw status text.
147 if (event->group() == "health" || event->group() == "arming_check") {
148 return;
149 }
150 if (event->group() == "calibration") {
151 qCDebug(MAVLinkEventManagerLog) << "Calibration Event Receieved";
152 return;
153 }
154
155 // Only default-group events at a known severity map to status text.
156 if (event->group() != "default" || severity == -1) {
157 return;
158 }
159
160 std::string message = event->message();
161 std::string description = event->description();
162
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);
166 const int modeGroup = handler.getModeGroup(customMode);
167 const std::vector<events::HealthAndArmingChecks::Check> checks = handler.healthAndArmingChecks()->results().checks(modeGroup);
168
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);
173 }
174 }
175 if (messageChecks.empty()) {
176 for (const auto &check : checks) {
177 messageChecks.push_back(check.message);
178 }
179 }
180 if (!message.empty() && !messageChecks.empty()) {
181 message += "\n";
182 }
183 if (messageChecks.size() == 1) {
184 message += messageChecks[0];
185 } else {
186 for (const auto &messageCheck : messageChecks) {
187 message += "- " + messageCheck + "\n";
188 }
189 }
190 }
191
192 if (message.empty()) {
193 return;
194 }
195
196 const QString text = QString::fromStdString(message);
197 // PX4 "[cal]" messages are delivered separately via the calibration flow;
198 // suppress them from the general status-text stream.
199 if (_vehicle->px4Firmware() && text.startsWith(QStringLiteral("[cal]"))) {
200 return;
201 }
202
203 emit statusTextMessageFromEvent(comp_id, severity, text, QString::fromStdString(description));
204}
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
bool px4Firmware() const
Definition Vehicle.h:494
uint32_t effectiveCustomMode() const
Definition Vehicle.h:509
QString missionFlightMode() const
Definition Vehicle.cc:2533
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:575
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
Definition Vehicle.h:444
int id() const
Definition Vehicle.h:425
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
Definition Vehicle.cc:1389
void flightModeChanged(const QString &flightMode)