QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
Actuators.h
Go to the documentation of this file.
1#pragma once
2
3#include "ActuatorOutputs.h"
4#include "ActuatorTesting.h"
5#include "Mixer.h"
6#include "MotorAssignment.h"
7
8#include <QtCore/QObject>
9#include <QtCore/QString>
10#include <QtCore/QJsonDocument>
11
12class Vehicle;
13
14class Actuators : public QObject
15{
16 Q_OBJECT
17public:
18 Actuators(QObject* parent, Vehicle* vehicle);
19 ~Actuators() = default;
20
23 Q_PROPERTY(bool isMultirotor READ isMultirotor CONSTANT)
29
31 Q_PROPERTY(Mixer::Mixers* mixer READ mixer CONSTANT)
33
34 Q_INVOKABLE void imageClicked(QSizeF displaySize, float x, float y);
35
36 Q_INVOKABLE void selectActuatorOutput(int index);
37
41 void load(const QString& json_file);
42
46 void init();
47
48 QmlObjectListModel* actuatorOutputs() { return _actuatorOutputs; }
50
51 ActuatorTesting::ActuatorTest* actuatorTest() { return &_actuatorTest; }
52
53 bool isMultirotor() const;
54
55 bool imageRefreshFlag() const { return _imageRefreshFlag; }
56
57 Mixer::Mixers* mixer() { return &_mixer; }
58
59 bool hasUnsetRequiredFunctions() const { return _hasUnsetRequiredFunctions; }
60
61 bool showUi() const;
62 bool isInitialized() const { return _init; }
63 const QString& initializationError() const { return _initError; }
64
65 QmlObjectListModel* actuatorActions() { return _actuatorActions; }
66
67 Q_INVOKABLE bool initMotorAssignment();
68 Q_INVOKABLE void startMotorAssignment();
69 Q_INVOKABLE void spinCurrentMotor() { _motorAssignment.spinCurrentMotor(); }
70 Q_INVOKABLE void abortMotorAssignment();
71 bool motorAssignmentActive() const { return _motorAssignment.active(); }
72 bool motorAssignmentEnabled() const { return _motorAssignmentEnabled; }
73 const QString& motorAssignmentMessage() const { return _motorAssignment.message(); }
74
75public slots:
76 void parametersChanged();
77
78signals:
87
88private slots:
89 void updateGeometryImage();
90
91private:
92 bool parseJson(const QJsonDocument& json);
93
94 void updateActuatorActions();
95
96 void subscribeFact(Fact* fact);
97
98 Fact* getFact(const QString& paramName);
99
100 void highlightActuators(bool highlight);
101
102 void updateFunctionMetadata();
103
104 QSet<Fact*> _subscribedFacts{};
105 QJsonDocument _jsonMetadata;
106 bool _init{false};
107 QString _initError;
108 Condition _showUi;
109 QmlObjectListModel* _actuatorOutputs = new QmlObjectListModel(this);
110 QmlObjectListModel* _actuatorActions = new QmlObjectListModel(this);
111 ActuatorTesting::ActuatorTest _actuatorTest;
112 Mixer::Mixers _mixer;
113 MotorAssignment _motorAssignment;
114 bool _motorAssignmentEnabled{false};
115 bool _hasUnsetRequiredFunctions{false};
116 bool _imageRefreshFlag{false};
117 int _selectedActuatorOutput{0};
118 Vehicle* _vehicle{nullptr};
119 QMap<int, QString> _usedMixerLabels;
120};
QmlObjectListModel * actuatorOutputs()
Definition Actuators.h:48
void actuatorOutputsChanged()
Mixer::Mixers * mixer()
Definition Actuators.h:57
Q_INVOKABLE bool initMotorAssignment()
Definition Actuators.cc:782
void hasUnsetRequiredFunctionsChanged()
Q_INVOKABLE void abortMotorAssignment()
Definition Actuators.cc:815
bool showUi() const
Definition Actuators.cc:777
bool isMultirotor() const
Definition Actuators.cc:109
void imageRefreshFlagChanged()
ActuatorTesting::ActuatorTest * actuatorTest()
Definition Actuators.h:51
const QString & initializationError() const
Definition Actuators.h:63
bool imageRefreshFlag() const
Definition Actuators.h:55
bool isInitialized() const
Definition Actuators.h:62
void motorAssignmentMessageChanged()
Q_INVOKABLE void selectActuatorOutput(int index)
Definition Actuators.cc:56
Q_INVOKABLE void startMotorAssignment()
Definition Actuators.cc:810
void init()
Definition Actuators.cc:139
Q_INVOKABLE void imageClicked(QSizeF displaySize, float x, float y)
Definition Actuators.cc:31
void motorAssignmentActiveChanged()
ActuatorOutputs::ActuatorOutput * selectedActuatorOutput() const
Definition Actuators.cc:64
void actuatorActionsChanged()
~Actuators()=default
void motorAssignmentEnabledChanged()
void parametersChanged()
Definition Actuators.cc:169
void load(const QString &json_file)
Definition Actuators.cc:114
bool hasUnsetRequiredFunctions() const
Definition Actuators.h:59
Q_INVOKABLE void spinCurrentMotor()
Definition Actuators.h:69
bool motorAssignmentEnabled() const
Definition Actuators.h:72
const QString & motorAssignmentMessage() const
Definition Actuators.h:73
bool motorAssignmentActive() const
Definition Actuators.h:71
void selectedActuatorOutputChanged()
QmlObjectListModel * actuatorActions()
Definition Actuators.h:65
A Fact is used to hold a single value within the system.
Definition Fact.h:17
bool active() const
const QString & message() const