14 changed files with 415 additions and 233 deletions
@ -0,0 +1,94 @@
@@ -0,0 +1,94 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (c) 2022 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||
* |
||||
* QGroundControl is licensed according to the terms in the file |
||||
* COPYING.md in the root of the source code directory. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#include "HealthAndArmingCheckReport.h" |
||||
#include "QGCMAVLink.h" |
||||
|
||||
#include <libevents/libs/cpp/generated/events_generated.h> |
||||
|
||||
HealthAndArmingCheckReport::HealthAndArmingCheckReport() |
||||
{ |
||||
#if 0 // to test the UI
|
||||
_problemsForCurrentMode->append(new HealthAndArmingCheckProblem("No global position", "", "error")); |
||||
_problemsForCurrentMode->append(new HealthAndArmingCheckProblem("No RC", "Details", "warning")); |
||||
_problemsForCurrentMode->append(new HealthAndArmingCheckProblem("Accel uncalibrated", "Details <a href='www.test.com'>test</a>", "error")); |
||||
_problemsForCurrentMode->append(new HealthAndArmingCheckProblem("Gyro uncalibrated", "Details <a href='param://SDLOG_PROFILE'>SDLOG_PROFILE</a>", "error")); |
||||
_problemsForCurrentMode->append(new HealthAndArmingCheckProblem( |
||||
"Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. Ut enim ad minim veniam, quis nostrud exercitation ullamco laboris nisi ut aliquip ex ea commodo consequat.", |
||||
"Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. Ut enim ad minim veniam, quis nostrud exercitation ullamco laboris nisi ut aliquip ex ea commodo consequat. Duis aute irure dolor in reprehenderit in voluptate velit esse cillum dolore eu fugiat nulla pariatur.<br>Excepteur sint occaecat cupidatat non proident, sunt in culpa qui officia deserunt mollit anim id est laborum", "")); |
||||
_supported = true; |
||||
emit updated(); |
||||
#endif |
||||
} |
||||
|
||||
HealthAndArmingCheckReport::~HealthAndArmingCheckReport() |
||||
{ |
||||
_problemsForCurrentMode->clearAndDeleteContents(); |
||||
} |
||||
|
||||
void HealthAndArmingCheckReport::update(uint8_t compid, const events::HealthAndArmingChecks::Results& results, |
||||
int flightModeGroup) |
||||
{ |
||||
if (compid != MAV_COMP_ID_AUTOPILOT1) { |
||||
// only autopilot supported atm
|
||||
return; |
||||
} |
||||
if (flightModeGroup == -1) { |
||||
qWarning() << "Flight mode group not set"; |
||||
return; |
||||
} |
||||
_supported = true; |
||||
|
||||
_problemsForCurrentMode->clearAndDeleteContents(); |
||||
_hasWarningsOrErrors = false; |
||||
for (const auto& check : results.checks(flightModeGroup)) { |
||||
QString severity = ""; |
||||
if (events::externalLogLevel(check.log_levels) <= events::Log::Error) { |
||||
severity = "error"; |
||||
_hasWarningsOrErrors = true; |
||||
} else if (events::externalLogLevel(check.log_levels) <= events::Log::Warning) { |
||||
severity = "warning"; |
||||
_hasWarningsOrErrors = true; |
||||
} |
||||
QString description = QString::fromStdString(check.description); |
||||
_problemsForCurrentMode->append(new HealthAndArmingCheckProblem(QString::fromStdString(check.message), |
||||
description.replace("\n", "<br/>"), severity)); |
||||
} |
||||
|
||||
_canArm = results.canArmAndRun(flightModeGroup); |
||||
if (_missionModeGroup != -1) { |
||||
_canStartMission = results.canArmAndRun(_missionModeGroup); |
||||
} |
||||
if (_takeoffModeGroup != -1) { |
||||
_canTakeoff = results.canArmAndRun(_takeoffModeGroup); |
||||
} |
||||
|
||||
const auto& healthComponents = results.healthComponents().health_components; |
||||
|
||||
// GPS state
|
||||
const auto gpsStateIter = healthComponents.find("gps"); |
||||
if (gpsStateIter != healthComponents.end()) { |
||||
const events::HealthAndArmingChecks::HealthComponent& gpsState = gpsStateIter->second; |
||||
if (gpsState.health.error || gpsState.arming_check.error) { |
||||
_gpsState = "red"; |
||||
} else if (gpsState.health.warning || gpsState.arming_check.warning) { |
||||
_gpsState = "yellow"; |
||||
} else { |
||||
_gpsState = "green"; |
||||
} |
||||
} |
||||
|
||||
emit updated(); |
||||
} |
||||
|
||||
void HealthAndArmingCheckReport::setModeGroups(int takeoffModeGroup, int missionModeGroup) |
||||
{ |
||||
_takeoffModeGroup = takeoffModeGroup; |
||||
_missionModeGroup = missionModeGroup; |
||||
} |
@ -0,0 +1,92 @@
@@ -0,0 +1,92 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (c) 2022 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||
* |
||||
* QGroundControl is licensed according to the terms in the file |
||||
* COPYING.md in the root of the source code directory. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#pragma once |
||||
|
||||
#include <QObject> |
||||
|
||||
#include <QmlObjectListModel.h> |
||||
#include <libevents/libs/cpp/parse/health_and_arming_checks.h> |
||||
|
||||
class HealthAndArmingCheckProblem : public QObject |
||||
{ |
||||
Q_OBJECT |
||||
public: |
||||
HealthAndArmingCheckProblem(const QString& message, const QString& description, const QString& severity) |
||||
: _message(message), _description(description), _severity(severity) {} |
||||
|
||||
Q_PROPERTY(QString message READ message CONSTANT) |
||||
Q_PROPERTY(QString description READ description CONSTANT) |
||||
Q_PROPERTY(QString severity READ severity CONSTANT) |
||||
Q_PROPERTY(bool expanded READ expanded WRITE setExpanded NOTIFY expandedChanged) |
||||
|
||||
const QString& message() const { return _message; } |
||||
const QString& description() const { return _description; } |
||||
const QString& severity() const { return _severity; } |
||||
|
||||
bool expanded() const { return _expanded; } |
||||
void setExpanded(bool expanded) { _expanded = expanded; emit expandedChanged(); } |
||||
|
||||
signals: |
||||
void expandedChanged(); |
||||
private: |
||||
const QString _message; |
||||
const QString _description; |
||||
const QString _severity; |
||||
bool _expanded{false}; |
||||
}; |
||||
|
||||
|
||||
class HealthAndArmingCheckReport : public QObject |
||||
{ |
||||
Q_OBJECT |
||||
public: |
||||
|
||||
Q_PROPERTY(bool supported READ supported NOTIFY updated) |
||||
Q_PROPERTY(bool canArm READ canArm NOTIFY updated) |
||||
Q_PROPERTY(bool canTakeoff READ canTakeoff NOTIFY updated) |
||||
Q_PROPERTY(bool canStartMission READ canStartMission NOTIFY updated) |
||||
Q_PROPERTY(bool hasWarningsOrErrors READ hasWarningsOrErrors NOTIFY updated) |
||||
Q_PROPERTY(QString gpsState READ gpsState NOTIFY updated) |
||||
Q_PROPERTY(QmlObjectListModel* problemsForCurrentMode READ problemsForCurrentMode NOTIFY updated) |
||||
|
||||
HealthAndArmingCheckReport(); |
||||
virtual ~HealthAndArmingCheckReport(); |
||||
|
||||
bool supported() const { return _supported; } |
||||
bool canArm() const { return _canArm; } |
||||
bool canTakeoff() const { return _canTakeoff; } |
||||
bool canStartMission() const { return _canStartMission; } |
||||
bool hasWarningsOrErrors() const { return _hasWarningsOrErrors; } |
||||
|
||||
const QString& gpsState() const { return _gpsState; } |
||||
|
||||
QmlObjectListModel* problemsForCurrentMode() { return _problemsForCurrentMode; } |
||||
|
||||
void update(uint8_t compid, const events::HealthAndArmingChecks::Results& results, int flightModeGroup); |
||||
|
||||
void setModeGroups(int takeoffModeGroup, int missionModeGroup); |
||||
|
||||
signals: |
||||
void updated(); |
||||
|
||||
private: |
||||
bool _supported{false}; |
||||
bool _canArm{true}; ///< whether arming is possible for the current mode
|
||||
bool _canTakeoff{true}; |
||||
bool _canStartMission{true}; |
||||
bool _hasWarningsOrErrors{false}; |
||||
QString _gpsState{}; |
||||
|
||||
int _takeoffModeGroup{-1}; |
||||
int _missionModeGroup{-1}; |
||||
|
||||
QmlObjectListModel* _problemsForCurrentMode = new QmlObjectListModel(this); ///< list of HealthAndArmingCheckProblem*
|
||||
}; |
||||
|
@ -1,125 +0,0 @@
@@ -1,125 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (c) 2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||
* |
||||
* QGroundControl is licensed according to the terms in the file |
||||
* COPYING.md in the root of the source code directory. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#include "HealthAndArmingChecks.h" |
||||
|
||||
#include <QGCLoggingCategory.h> |
||||
|
||||
QGC_LOGGING_CATEGORY(HealthAndArmingChecks, "HealthAndArmingChecks"); |
||||
|
||||
using health_component_t = events::common::enums::health_component_t; |
||||
using navigation_mode_category_t = events::common::enums::navigation_mode_category_t; |
||||
|
||||
void HealthAndArmingCheckHandler::handleEvent(const events::parser::ParsedEvent& event) |
||||
{ |
||||
Type type; |
||||
if (event.eventNamespace() == "common" && event.name() == "arming_check_summary") { |
||||
type = Type::ArmingCheckSummary; |
||||
} else if (event.eventNamespace() == "common" && event.name() == "health_summary") { |
||||
type = Type::HealthSummary; |
||||
} else { |
||||
type = Type::Other; |
||||
} |
||||
|
||||
// the expected order of receiving is:
|
||||
// - ArmingCheckSummary
|
||||
// - N Other
|
||||
// - HealthSummary
|
||||
|
||||
if (type != _expectedEvent) { |
||||
if (_expectedEvent == Type::Other && type == Type::HealthSummary) { |
||||
// all good
|
||||
} else if (type == Type::ArmingCheckSummary) { |
||||
qCDebug(HealthAndArmingChecks) << "Unexpected ArmingCheckSummary event, resetting. Expected:" << (int)_expectedEvent; |
||||
// accept & reset
|
||||
} else { |
||||
qCDebug(HealthAndArmingChecks) << "Unexpected event, resetting. Expected:" << (int)_expectedEvent |
||||
<< "Got:" << (int)type; |
||||
_expectedEvent = Type::ArmingCheckSummary; |
||||
return; |
||||
} |
||||
} |
||||
|
||||
switch (type) { |
||||
case Type::ArmingCheckSummary: |
||||
reset(); |
||||
if (event.id() == (uint32_t)events::common::event_id_t::arming_check_summary) { |
||||
ArmingCheckSummary &arming = _results[_currentResult].arming; |
||||
events::common::decode_arming_check_summary(event.eventData(), arming.error, arming.warning, arming.canArm); |
||||
_expectedEvent = Type::Other; |
||||
} |
||||
break; |
||||
case Type::Other: { |
||||
Check check; |
||||
check.type = event.group() == "health" ? CheckType::Health : CheckType::ArmingCheck; |
||||
check.message = QString::fromStdString(event.message()); |
||||
check.description = QString::fromStdString(event.description()); |
||||
check.affectedModes = (events::common::enums::navigation_mode_category_t)event.argumentValue(0).value.val_uint8_t; |
||||
check.affectedHealthComponentIndex = event.argumentValue(1).value.val_uint8_t; |
||||
check.logLevel = events::externalLogLevel(event.eventData().log_levels); |
||||
_results[_currentResult].checks.append(check); |
||||
} |
||||
break; |
||||
case Type::HealthSummary: |
||||
if (event.id() == (uint32_t)events::common::event_id_t::health_summary) { |
||||
HealthSummary &health = _results[_currentResult].health; |
||||
events::common::decode_health_summary(event.eventData(), health.isPresent, health.error, health.warning); |
||||
_currentResult = (_currentResult + 1) % 2; |
||||
emit update(); |
||||
testReport(); |
||||
} |
||||
reset(); |
||||
break; |
||||
} |
||||
} |
||||
|
||||
void HealthAndArmingCheckHandler::reset() |
||||
{ |
||||
_results[_currentResult].reset(); |
||||
_expectedEvent = Type::ArmingCheckSummary; |
||||
} |
||||
|
||||
void HealthAndArmingCheckHandler::testReport() |
||||
{ |
||||
// just for testing...
|
||||
// qWarning() << "Got Health/Arming checks update";
|
||||
// qWarning() << "Arming possible in current mode: " << (results().arming.canArm & navigation_mode_category_t::current);
|
||||
// qWarning() << "Can a mission be flown: " << (results().arming.canArm & navigation_mode_category_t::mission);
|
||||
// qWarning() << "Autonomous (e.g. Takeoff) flight possible: " << (results().arming.canArm & navigation_mode_category_t::autonomous);
|
||||
//
|
||||
// QString gps_icon_color;
|
||||
// if ((results().health.error & health_component_t::sensor_gps) ||
|
||||
// (results().health.error & health_component_t::global_position_estimate) ||
|
||||
// (results().arming.error & health_component_t::sensor_gps) ||
|
||||
// (results().arming.error & health_component_t::global_position_estimate)) {
|
||||
// gps_icon_color = "red";
|
||||
// } else if((results().health.warning & health_component_t::sensor_gps) ||
|
||||
// (results().health.warning & health_component_t::global_position_estimate) ||
|
||||
// (results().arming.warning & health_component_t::sensor_gps) ||
|
||||
// (results().arming.warning & health_component_t::global_position_estimate)) {
|
||||
// gps_icon_color = "yellow";
|
||||
// } else {
|
||||
// gps_icon_color = "green";
|
||||
// }
|
||||
// qWarning() << "GPS/Position icon color: " << gps_icon_color;
|
||||
//
|
||||
// // display events that are relevant for current mode:
|
||||
// qWarning() << "Current flight mode:";
|
||||
// for (const auto& check : results().checks) {
|
||||
// if (check.affectedModes & navigation_mode_category_t::current) {
|
||||
// qWarning() << " " << (int)check.logLevel << check.message;
|
||||
// }
|
||||
// }
|
||||
// qWarning() << "Other flight modes:";
|
||||
// for (const auto& check : results().checks) {
|
||||
// if (!(check.affectedModes & navigation_mode_category_t::current)) {
|
||||
// qWarning() << " " << (int)check.logLevel << check.message;
|
||||
// }
|
||||
// }
|
||||
} |
@ -1,84 +0,0 @@
@@ -1,84 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (c) 2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||
* |
||||
* QGroundControl is licensed according to the terms in the file |
||||
* COPYING.md in the root of the source code directory. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#pragma once |
||||
|
||||
#include <QObject> |
||||
#include <QLoggingCategory> |
||||
#include <QVector> |
||||
|
||||
#include <libevents/libs/cpp/parse/parser.h> |
||||
#include <libevents/libs/cpp/generated/events_generated.h> |
||||
|
||||
Q_DECLARE_LOGGING_CATEGORY(HealthAndArmingChecks) |
||||
|
||||
class HealthAndArmingCheckHandler : public QObject |
||||
{ |
||||
Q_OBJECT |
||||
public: |
||||
|
||||
enum class CheckType { |
||||
ArmingCheck, |
||||
Health |
||||
}; |
||||
struct Check { |
||||
CheckType type; |
||||
QString message; |
||||
QString description; |
||||
events::common::enums::navigation_mode_category_t affectedModes; |
||||
uint8_t affectedHealthComponentIndex; ///< index for events::common::enums::health_component_t, can be 0xff
|
||||
events::Log logLevel; |
||||
}; |
||||
|
||||
struct HealthSummary { |
||||
events::common::enums::health_component_t isPresent; |
||||
events::common::enums::health_component_t error; |
||||
events::common::enums::health_component_t warning; |
||||
}; |
||||
struct ArmingCheckSummary { |
||||
events::common::enums::health_component_t error; |
||||
events::common::enums::health_component_t warning; |
||||
events::common::enums::navigation_mode_category_t canArm; |
||||
}; |
||||
|
||||
struct Results { |
||||
HealthSummary health{}; |
||||
ArmingCheckSummary arming{}; |
||||
QVector<Check> checks{}; |
||||
|
||||
void reset() { |
||||
health = {}; |
||||
arming = {}; |
||||
checks.clear(); |
||||
} |
||||
}; |
||||
|
||||
void handleEvent(const events::parser::ParsedEvent& event); |
||||
|
||||
const Results& results() const { return _results[(_currentResult + 1) % 2]; } |
||||
|
||||
signals: |
||||
void update(); |
||||
private: |
||||
|
||||
enum class Type { |
||||
ArmingCheckSummary, |
||||
Other, |
||||
HealthSummary, |
||||
}; |
||||
|
||||
void reset(); |
||||
|
||||
void testReport(); |
||||
|
||||
Type _expectedEvent{Type::ArmingCheckSummary}; |
||||
Results _results[2]; ///< store the last full set and currently updating one
|
||||
int _currentResult{0}; ///< index for the currently updating/adding results
|
||||
}; |
||||
|
Loading…
Reference in new issue