QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
HealthAndArmingCheckReport.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QObject>
4#include <QtCore/QString>
5
6class EventHandler;
8
9class HealthAndArmingCheckProblem : public QObject
10{
11 Q_OBJECT
12 Q_PROPERTY(QString message READ message CONSTANT)
13 Q_PROPERTY(QString description READ description CONSTANT)
14 Q_PROPERTY(QString severity READ severity CONSTANT)
15 Q_PROPERTY(bool expanded READ expanded WRITE setExpanded NOTIFY expandedChanged)
16
17public:
18 HealthAndArmingCheckProblem(const QString& message, const QString& description, const QString& severity, QObject *parent = nullptr);
19
20 const QString& message() const { return _message; }
21 const QString& description() const { return _description; }
22 const QString& severity() const { return _severity; }
23
24 bool expanded() const { return _expanded; }
25 void setExpanded(bool expanded) { _expanded = expanded; emit expandedChanged(); }
26
27signals:
29
30private:
31 const QString _message;
32 const QString _description;
33 const QString _severity;
34 bool _expanded{false};
35};
36
37/*===========================================================================*/
38
39class HealthAndArmingCheckReport : public QObject
40{
41 Q_OBJECT
42 Q_MOC_INCLUDE("QmlObjectListModel.h")
43 Q_PROPERTY(bool supported READ supported NOTIFY updated)
44 Q_PROPERTY(bool canArm READ canArm NOTIFY updated)
45 Q_PROPERTY(bool canTakeoff READ canTakeoff NOTIFY updated)
46 Q_PROPERTY(bool canStartMission READ canStartMission NOTIFY updated)
47 Q_PROPERTY(bool hasWarningsOrErrors READ hasWarningsOrErrors NOTIFY updated)
48 Q_PROPERTY(QString gpsState READ gpsState NOTIFY updated)
50
51public:
52 explicit HealthAndArmingCheckReport(QObject *parent = nullptr);
54
55 bool supported() const { return _supported; }
56 bool canArm() const { return _canArm; }
57 bool canTakeoff() const { return _canTakeoff; }
58 bool canStartMission() const { return _canStartMission; }
59 bool hasWarningsOrErrors() const { return _hasWarningsOrErrors; }
60 const QString& gpsState() const { return _gpsState; }
61 QmlObjectListModel* problemsForCurrentMode() { return _problemsForCurrentMode; }
62
63 void update(uint8_t compid, const EventHandler &eventHandler, int flightModeGroup);
64 void setModeGroups(int takeoffModeGroup, int missionModeGroup);
65
66signals:
67 void updated();
68
69private:
70 bool _supported{false};
71 bool _canArm{true};
72 bool _canTakeoff{true};
73 bool _canStartMission{true};
74 bool _hasWarningsOrErrors{false};
75 QString _gpsState{};
76
77 int _takeoffModeGroup{-1};
78 int _missionModeGroup{-1};
79
80 QmlObjectListModel* _problemsForCurrentMode = nullptr;
81};
Drives the MAVLink events protocol for a single component.
QmlObjectListModel * problemsForCurrentMode()
void update(uint8_t compid, const EventHandler &eventHandler, int flightModeGroup)
void setModeGroups(int takeoffModeGroup, int missionModeGroup)