Browse Source

UI: add health and arming check reporting UI

QGC4.4
Beat Küng 3 years ago
parent
commit
5e6b77db85
  1. 2
      QGCExternalLibs.pri
  2. 4
      qgroundcontrol.pro
  3. 9
      src/FlightDisplay/GuidedActionsController.qml
  4. 2
      src/FlightDisplay/VehicleWarnings.qml
  5. 4
      src/Vehicle/CMakeLists.txt
  6. 27
      src/Vehicle/EventHandler.cc
  7. 15
      src/Vehicle/EventHandler.h
  8. 94
      src/Vehicle/HealthAndArmingCheckReport.cc
  9. 92
      src/Vehicle/HealthAndArmingCheckReport.h
  10. 125
      src/Vehicle/HealthAndArmingChecks.cc
  11. 84
      src/Vehicle/HealthAndArmingChecks.h
  12. 31
      src/Vehicle/Vehicle.cc
  13. 5
      src/Vehicle/Vehicle.h
  14. 154
      src/ui/toolbar/MainStatusIndicator.qml

2
QGCExternalLibs.pri

@ -105,11 +105,13 @@ DEFINES += NOMINMAX @@ -105,11 +105,13 @@ DEFINES += NOMINMAX
# [REQUIRED] Events submodule
HEADERS+= \
libs/libevents/libevents/libs/cpp/protocol/receive.h \
libs/libevents/libevents/libs/cpp/parse/health_and_arming_checks.h \
libs/libevents/libevents/libs/cpp/parse/parser.h \
libs/libevents/libevents/libs/cpp/generated/events_generated.h \
libs/libevents/libevents_definitions.h
SOURCES += \
libs/libevents/libevents/libs/cpp/protocol/receive.cpp \
libs/libevents/libevents/libs/cpp/parse/health_and_arming_checks.cpp \
libs/libevents/libevents/libs/cpp/parse/parser.cpp \
libs/libevents/definitions.cpp
INCLUDEPATH += \

4
qgroundcontrol.pro

@ -709,7 +709,7 @@ HEADERS += \ @@ -709,7 +709,7 @@ HEADERS += \
src/Vehicle/EventHandler.h \
src/Vehicle/FTPManager.h \
src/Vehicle/GPSRTKFactGroup.h \
src/Vehicle/HealthAndArmingChecks.h \
src/Vehicle/HealthAndArmingCheckReport.h \
src/Vehicle/ImageProtocolManager.h \
src/Vehicle/InitialConnectStateMachine.h \
src/Vehicle/MAVLinkLogManager.h \
@ -964,7 +964,7 @@ SOURCES += \ @@ -964,7 +964,7 @@ SOURCES += \
src/Vehicle/EventHandler.cc \
src/Vehicle/FTPManager.cc \
src/Vehicle/GPSRTKFactGroup.cc \
src/Vehicle/HealthAndArmingChecks.cc \
src/Vehicle/HealthAndArmingCheckReport.cc \
src/Vehicle/ImageProtocolManager.cc \
src/Vehicle/InitialConnectStateMachine.cc \
src/Vehicle/MAVLinkLogManager.cc \

9
src/FlightDisplay/GuidedActionsController.qml

@ -109,16 +109,19 @@ Item { @@ -109,16 +109,19 @@ Item {
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _useChecklist: QGroundControl.settingsManager.appSettings.useChecklist.rawValue && QGroundControl.corePlugin.options.preFlightChecklistUrl.toString().length
property bool _enforceChecklist: _useChecklist && QGroundControl.settingsManager.appSettings.enforceChecklist.rawValue
property bool _canArm: _activeVehicle ? (_useChecklist ? (_enforceChecklist ? _activeVehicle.checkListState === Vehicle.CheckListPassed : true) : true) : false
property bool _checklistPassed: _activeVehicle ? (_useChecklist ? (_enforceChecklist ? _activeVehicle.checkListState === Vehicle.CheckListPassed : true) : true) : true
property bool _canArm: _activeVehicle ? (_checklistPassed && (!_activeVehicle.healthAndArmingCheckReport.supported || _activeVehicle.healthAndArmingCheckReport.canArm)) : false
property bool _canTakeoff: _activeVehicle ? (_checklistPassed && (!_activeVehicle.healthAndArmingCheckReport.supported || _activeVehicle.healthAndArmingCheckReport.canTakeoff)) : false
property bool _canStartMission: _activeVehicle ? (_checklistPassed && (!_activeVehicle.healthAndArmingCheckReport.supported || _activeVehicle.healthAndArmingCheckReport.canStartMission)) : false
property bool showEmergenyStop: _guidedActionsEnabled && !_hideEmergenyStop && _vehicleArmed && _vehicleFlying
property bool showArm: _guidedActionsEnabled && !_vehicleArmed && _canArm
property bool showForceArm: _guidedActionsEnabled && !_vehicleArmed
property bool showDisarm: _guidedActionsEnabled && _vehicleArmed && !_vehicleFlying
property bool showRTL: _guidedActionsEnabled && _vehicleArmed && _activeVehicle.guidedModeSupported && _vehicleFlying && !_vehicleInRTLMode
property bool showTakeoff: _guidedActionsEnabled && _activeVehicle.takeoffVehicleSupported && !_vehicleFlying && _canArm
property bool showTakeoff: _guidedActionsEnabled && _activeVehicle.takeoffVehicleSupported && !_vehicleFlying && _canTakeoff
property bool showLand: _guidedActionsEnabled && _activeVehicle.guidedModeSupported && _vehicleArmed && !_activeVehicle.fixedWing && !_vehicleInLandMode
property bool showStartMission: _guidedActionsEnabled && _missionAvailable && !_missionActive && !_vehicleFlying && _canArm
property bool showStartMission: _guidedActionsEnabled && _missionAvailable && !_missionActive && !_vehicleFlying && _canStartMission
property bool showContinueMission: _guidedActionsEnabled && _missionAvailable && !_missionActive && _vehicleArmed && _vehicleFlying && (_currentMissionIndex < _missionItemCount - 1)
property bool showPause: _guidedActionsEnabled && _vehicleArmed && _activeVehicle.pauseVehicleSupported && _vehicleFlying && !_vehiclePaused && !_fixedWingOnApproach
property bool showChangeAlt: _guidedActionsEnabled && _vehicleFlying && _activeVehicle.guidedModeSupported && _vehicleArmed && !_missionActive

2
src/FlightDisplay/VehicleWarnings.qml

@ -23,7 +23,7 @@ Rectangle { @@ -23,7 +23,7 @@ Rectangle {
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _noGPSLockVisible: _activeVehicle && _activeVehicle.requiresGpsFix && !_activeVehicle.coordinate.isValid
property bool _prearmErrorVisible: _activeVehicle && !_activeVehicle.armed && _activeVehicle.prearmError
property bool _prearmErrorVisible: _activeVehicle && !_activeVehicle.armed && _activeVehicle.prearmError && !_activeVehicle.healthAndArmingCheckReport.supported
Column {
id: warningsCol

4
src/Vehicle/CMakeLists.txt

@ -40,8 +40,8 @@ add_library(Vehicle @@ -40,8 +40,8 @@ add_library(Vehicle
FTPManager.h
GPSRTKFactGroup.cc
GPSRTKFactGroup.h
HealthAndArmingChecks.cc
HealthAndArmingChecks.h
HealthAndArmingCheckReport.cc
HealthAndArmingCheckReport.h
ImageProtocolManager.cc
ImageProtocolManager.h
InitialConnectStateMachine.cc

27
src/Vehicle/EventHandler.cc

@ -23,7 +23,8 @@ EventHandler::EventHandler(QObject* parent, const QString& profile, handle_event @@ -23,7 +23,8 @@ EventHandler::EventHandler(QObject* parent, const QString& profile, handle_event
_sendRequestCB(sendRequestCB),
_compid(componentId)
{
auto error_cb = [componentId](int num_events_lost) {
auto error_cb = [componentId, this](int num_events_lost) {
_healthAndArmingChecks.reset();
qCWarning(EventsLog) << "Events got lost:" << num_events_lost << "comp_id:" << componentId;
};
@ -41,6 +42,9 @@ EventHandler::EventHandler(QObject* parent, const QString& profile, handle_event @@ -41,6 +42,9 @@ EventHandler::EventHandler(QObject* parent, const QString& profile, handle_event
_parser.formatters().url = [](const std::string& content, const std::string& link) {
return "<a href=\""+link+"\">"+content+"</a>"; };
_parser.formatters().param = [](const std::string& content) {
return "<a href=\"param://"+content+"\">"+content+"</a>"; };
events::ReceiveProtocol::Callbacks callbacks{error_cb, _sendRequestCB,
std::bind(&EventHandler::gotEvent, this, std::placeholders::_1), timeout_cb};
_protocol = new events::ReceiveProtocol(callbacks, ourSystemId, ourComponentId, systemId, componentId);
@ -75,6 +79,9 @@ void EventHandler::gotEvent(const mavlink_event_t& event) @@ -75,6 +79,9 @@ void EventHandler::gotEvent(const mavlink_event_t& event)
qCDebug(EventsLog) << "Got Event: ID:" << parsed_event->id() << "namespace:" << parsed_event->eventNamespace().c_str() <<
"name:" << parsed_event->name().c_str() << "msg:" << parsed_event->message().c_str();
if (_healthAndArmingChecks.handleEvent(*parsed_event)) {
emit healthAndArmingChecksUpdated();
}
_handleEventCB(std::move(parsed_event));
}
@ -83,13 +90,9 @@ void EventHandler::handleEvents(const mavlink_message_t& message) @@ -83,13 +90,9 @@ void EventHandler::handleEvents(const mavlink_message_t& message)
_protocol->processMessage(message);
}
void EventHandler::setMetadata(const QString &metadataJsonFileName, const QString &translationJsonFileName)
void EventHandler::setMetadata(const QString &metadataJsonFileName)
{
auto translate = [](const std::string& s) {
// TODO: use translation file
return s;
};
if (_parser.loadDefinitionsFile(metadataJsonFileName.toStdString(), translate)) {
if (_parser.loadDefinitionsFile(metadataJsonFileName.toStdString())) {
if (_parser.hasDefinitions()) {
// do we have queued events?
for (const auto& event : _pendingEvents) {
@ -102,3 +105,13 @@ void EventHandler::setMetadata(const QString &metadataJsonFileName, const QStrin @@ -102,3 +105,13 @@ void EventHandler::setMetadata(const QString &metadataJsonFileName, const QStrin
}
}
int EventHandler::getModeGroup(int32_t customMode)
{
events::parser::Parser::NavigationModeGroups groups = _parser.navigationModeGroups(_compid);
for (auto groupIter : groups.groups) {
if (groupIter.second.find(customMode) != groupIter.second.end()) {
return groupIter.first;
}
}
return -1;
}

15
src/Vehicle/EventHandler.h

@ -15,9 +15,8 @@ @@ -15,9 +15,8 @@
#include <functional>
#include "HealthAndArmingChecks.h"
#include <libevents/libs/cpp/protocol/receive.h>
#include <libevents/libs/cpp/parse/health_and_arming_checks.h>
#include <libevents/libs/cpp/parse/parser.h>
#include <libevents/libs/cpp/generated/events_generated.h>
@ -36,16 +35,22 @@ public: @@ -36,16 +35,22 @@ public:
void handleEvents(const mavlink_message_t& message);
void setMetadata(const QString& metadataJsonFileName, const QString& translationJsonFileName);
void setMetadata(const QString& metadataJsonFileName);
const events::HealthAndArmingChecks::Results& healthAndArmingCheckResults() const { return _healthAndArmingChecks.results(); }
int getModeGroup(int32_t customMode);
signals:
void healthAndArmingChecksUpdated();
HealthAndArmingCheckHandler& healthAndArmingChecks() { return _healthAndArmingChecks; }
private:
void gotEvent(const mavlink_event_t& event);
events::ReceiveProtocol* _protocol{nullptr};
QTimer _timer;
events::parser::Parser _parser;
HealthAndArmingCheckHandler _healthAndArmingChecks;
events::HealthAndArmingChecks _healthAndArmingChecks;
QVector<mavlink_event_t> _pendingEvents; ///< stores incoming events until we have the metadata loaded
handle_event_f _handleEventCB;
send_request_event_message_f _sendRequestCB;

94
src/Vehicle/HealthAndArmingCheckReport.cc

@ -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;
}

92
src/Vehicle/HealthAndArmingCheckReport.h

@ -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*
};

125
src/Vehicle/HealthAndArmingChecks.cc

@ -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;
// }
// }
}

84
src/Vehicle/HealthAndArmingChecks.h

@ -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
};

31
src/Vehicle/Vehicle.cc

@ -1561,7 +1561,6 @@ void Vehicle::_handleEvent(uint8_t comp_id, std::unique_ptr<events::parser::Pars @@ -1561,7 +1561,6 @@ void Vehicle::_handleEvent(uint8_t comp_id, std::unique_ptr<events::parser::Pars
// handle special groups & protocols
if (event->group() == "health" || event->group() == "arming_check") {
_events[comp_id]->healthAndArmingChecks().handleEvent(*event.get());
// these are displayed separately
return;
}
@ -1613,13 +1612,41 @@ EventHandler& Vehicle::_eventHandler(uint8_t compid) @@ -1613,13 +1612,41 @@ EventHandler& Vehicle::_eventHandler(uint8_t compid)
sendRequestEventMessageCB,
_mavlink->getSystemId(), _mavlink->getComponentId(), _id, compid)};
eventData = _events.insert(compid, eventHandler);
// connect health and arming check updates
connect(eventHandler.data(), &EventHandler::healthAndArmingChecksUpdated, this, [compid, this]() {
// TODO: use user-intended mode instead of currently set mode
const QSharedPointer<EventHandler>& eventHandler = _events[compid];
_healthAndArmingCheckReport.update(compid, eventHandler->healthAndArmingCheckResults(),
eventHandler->getModeGroup(_custom_mode));
});
connect(this, &Vehicle::flightModeChanged, this, [compid, this]() {
const QSharedPointer<EventHandler>& eventHandler = _events[compid];
_healthAndArmingCheckReport.update(compid, eventHandler->healthAndArmingCheckResults(),
eventHandler->getModeGroup(_custom_mode));
});
}
return *eventData->data();
}
void Vehicle::setEventsMetadata(uint8_t compid, const QString& metadataJsonFileName, const QString& translationJsonFileName)
{
_eventHandler(compid).setMetadata(metadataJsonFileName, translationJsonFileName);
_eventHandler(compid).setMetadata(metadataJsonFileName);
// get the mode group for some well-known flight modes
int modeGroups[2]{-1, -1};
const QString modes[2]{"Takeoff", "Mission"};
for (size_t i = 0; i < sizeof(modeGroups)/sizeof(modeGroups[0]); ++i) {
uint8_t base_mode;
uint32_t custom_mode;
if (_firmwarePlugin->setFlightMode(modes[i], &base_mode, &custom_mode)) {
modeGroups[i] = _eventHandler(compid).getModeGroup(custom_mode);
if (modeGroups[i] == -1) {
qCDebug(VehicleLog) << "Failed to get mode group for mode" << modes[i] << "(Might not be in metadata)";
}
}
}
_healthAndArmingCheckReport.setModeGroups(modeGroups[0], modeGroups[1]);
}
void Vehicle::setActuatorsMetadata(uint8_t compid, const QString& metadataJsonFileName, const QString& translationJsonFileName)

5
src/Vehicle/Vehicle.h

@ -46,6 +46,7 @@ @@ -46,6 +46,7 @@
#include "RallyPointManager.h"
#include "FTPManager.h"
#include "ImageProtocolManager.h"
#include "HealthAndArmingCheckReport.h"
class Actuators;
class EventHandler;
@ -321,6 +322,7 @@ public: @@ -321,6 +322,7 @@ public:
Q_PROPERTY(FactGroup* hygrometer READ hygrometerFactGroup CONSTANT)
Q_PROPERTY(QmlObjectListModel* batteries READ batteries CONSTANT)
Q_PROPERTY(Actuators* actuators READ actuators CONSTANT)
Q_PROPERTY(HealthAndArmingCheckReport* healthAndArmingCheckReport READ healthAndArmingCheckReport CONSTANT)
Q_PROPERTY(int firmwareMajorVersion READ firmwareMajorVersion NOTIFY firmwareVersionChanged)
Q_PROPERTY(int firmwareMinorVersion READ firmwareMinorVersion NOTIFY firmwareVersionChanged)
@ -853,6 +855,8 @@ public: @@ -853,6 +855,8 @@ public:
void setEventsMetadata(uint8_t compid, const QString& metadataJsonFileName, const QString& translationJsonFileName);
void setActuatorsMetadata(uint8_t compid, const QString& metadataJsonFileName, const QString& translationJsonFileName);
HealthAndArmingCheckReport* healthAndArmingCheckReport() { return &_healthAndArmingCheckReport; }
public slots:
void setVtolInFwdFlight (bool vtolInFwdFlight);
void _offlineFirmwareTypeSettingChanged (QVariant varFirmwareType); // Should only be used by MissionControler to set firmware from Plan file
@ -1224,6 +1228,7 @@ private: @@ -1224,6 +1228,7 @@ private:
static const int _orbitTelemetryTimeoutMsecs = 3000; // No telemetry for this amount and orbit will go inactive
QMap<uint8_t, QSharedPointer<EventHandler>> _events; ///< One protocol handler for each component ID
HealthAndArmingCheckReport _healthAndArmingCheckReport;
MAVLinkStreamConfig _mavlinkStreamConfig;

154
src/ui/toolbar/MainStatusIndicator.qml

@ -15,6 +15,7 @@ import QGroundControl.Controls 1.0 @@ -15,6 +15,7 @@ import QGroundControl.Controls 1.0
import QGroundControl.MultiVehicleManager 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0
import QGroundControl.FactSystem 1.0
RowLayout {
id: _root
@ -26,6 +27,7 @@ RowLayout { @@ -26,6 +27,7 @@ RowLayout {
property bool _armed: _activeVehicle ? _activeVehicle.armed : false
property real _margins: ScreenTools.defaultFontPixelWidth
property real _spacing: ScreenTools.defaultFontPixelWidth / 2
property bool _healthAndArmingChecksSupported: _activeVehicle ? _activeVehicle.healthAndArmingCheckReport.supported : false
QGCLabel {
id: mainStatusLabel
@ -49,6 +51,17 @@ RowLayout { @@ -49,6 +51,17 @@ RowLayout {
}
if (_activeVehicle.armed) {
_mainStatusBGColor = "green"
if (_healthAndArmingChecksSupported) {
if (_activeVehicle.healthAndArmingCheckReport.canArm) {
if (_activeVehicle.healthAndArmingCheckReport.hasWarningsOrErrors) {
_mainStatusBGColor = "yellow"
}
} else {
_mainStatusBGColor = "red"
}
}
if (_activeVehicle.flying) {
return mainStatusLabel._flyingText
} else if (_activeVehicle.landing) {
@ -57,7 +70,19 @@ RowLayout { @@ -57,7 +70,19 @@ RowLayout {
return mainStatusLabel._armedText
}
} else {
if (_activeVehicle.readyToFlyAvailable) {
if (_healthAndArmingChecksSupported) {
if (_activeVehicle.healthAndArmingCheckReport.canArm) {
if (_activeVehicle.healthAndArmingCheckReport.hasWarningsOrErrors) {
_mainStatusBGColor = "yellow"
} else {
_mainStatusBGColor = "green"
}
return mainStatusLabel._readyToFlyText
} else {
_mainStatusBGColor = "red"
return mainStatusLabel._notReadyToFlyText
}
} else if (_activeVehicle.readyToFlyAvailable) {
if (_activeVehicle.readyToFly) {
_mainStatusBGColor = "green"
return mainStatusLabel._readyToFlyText
@ -167,7 +192,10 @@ RowLayout { @@ -167,7 +192,10 @@ RowLayout {
spacing: _spacing
QGCButton {
Layout.alignment: Qt.AlignHCenter
Layout.leftMargin: _healthAndArmingChecksSupported ? width / 2 : 0
Layout.alignment: _healthAndArmingChecksSupported ? Qt.AlignLeft : Qt.AlignHCenter
// FIXME: forceArm is not possible anymore if _healthAndArmingChecksSupported == true
enabled: _armed || !_healthAndArmingChecksSupported || _activeVehicle.healthAndArmingCheckReport.canArm
text: _armed ? qsTr("Disarm") : (forceArm ? qsTr("Force Arm") : qsTr("Arm"))
property bool forceArm: false
@ -192,6 +220,7 @@ RowLayout { @@ -192,6 +220,7 @@ RowLayout {
QGCLabel {
Layout.alignment: Qt.AlignHCenter
text: qsTr("Sensor Status")
visible: !_healthAndArmingChecksSupported
}
GridLayout {
@ -199,6 +228,7 @@ RowLayout { @@ -199,6 +228,7 @@ RowLayout {
columnSpacing: _spacing
rows: _activeVehicle.sysStatusSensorInfo.sensorNames.length
flow: GridLayout.TopToBottom
visible: !_healthAndArmingChecksSupported
Repeater {
model: _activeVehicle.sysStatusSensorInfo.sensorNames
@ -216,6 +246,126 @@ RowLayout { @@ -216,6 +246,126 @@ RowLayout {
}
}
}
QGCLabel {
text: qsTr("Arming Check Report:")
visible: _healthAndArmingChecksSupported && _activeVehicle.healthAndArmingCheckReport.problemsForCurrentMode.count > 0
}
// List health and arming checks
QGCListView {
visible: _healthAndArmingChecksSupported
anchors.margins: ScreenTools.defaultFontPixelHeight
spacing: ScreenTools.defaultFontPixelWidth
width: mainWindow.width * 0.66666
height: contentHeight
model: _activeVehicle ? _activeVehicle.healthAndArmingCheckReport.problemsForCurrentMode : null
delegate: listdelegate
}
FactPanelController {
id: controller
}
Component {
id: listdelegate
Column {
width: parent ? parent.width : 0
Row {
width: parent.width
QGCLabel {
id: message
text: object.message
wrapMode: Text.WordWrap
textFormat: TextEdit.RichText
width: parent.width - arrowDownIndicator.width
color: object.severity == 'error' ? qgcPal.colorRed : object.severity == 'warning' ? qgcPal.colorOrange : qgcPal.text
MouseArea {
anchors.fill: parent
onClicked: {
if (object.description != "")
object.expanded = !object.expanded
}
}
}
QGCColoredImage {
id: arrowDownIndicator
height: 1.5 * ScreenTools.defaultFontPixelWidth
width: height
source: "/qmlimages/arrow-down.png"
color: qgcPal.text
visible: object.description != ""
MouseArea {
anchors.fill: parent
onClicked: object.expanded = !object.expanded
}
}
}
Rectangle {
property var margin: ScreenTools.defaultFontPixelWidth
id: descriptionRect
width: parent.width
height: description.height + margin
color: qgcPal.windowShade
visible: false
Connections {
target: object
function onExpandedChanged() {
if (object.expanded) {
description.height = description.preferredHeight
} else {
description.height = 0
}
}
}
Behavior on height {
NumberAnimation {
id: animation
duration: 150
onRunningChanged: {
descriptionRect.visible = animation.running || object.expanded
}
}
}
QGCLabel {
id: description
anchors.centerIn: parent
width: parent.width - parent.margin * 2
height: 0
text: object.description
textFormat: TextEdit.RichText
wrapMode: Text.WordWrap
clip: true
property var fact: null
onLinkActivated: {
if (link.startsWith('param://')) {
var paramName = link.substr(8);
fact = controller.getParameterFact(-1, paramName, true)
if (fact != null) {
paramEditorDialogComponent.createObject(mainWindow).open()
}
} else {
Qt.openUrlExternally(link);
}
}
}
Component {
id: paramEditorDialogComponent
ParameterEditorDialog {
title: qsTr("Edit Parameter")
fact: description.fact
destroyOnClose: true
}
}
}
}
}
}
}
}

Loading…
Cancel
Save