QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
ActuatorTesting.h
Go to the documentation of this file.
1#pragma once
2
3
5#include "Vehicle.h"
6#include "MAVLinkLib.h"
7#include <QtCore/QObject>
8#include <QtCore/QString>
9#include <QtCore/QTimer>
10
11namespace ActuatorTesting {
12
13class Actuator : public QObject
14{
15 Q_OBJECT
16public:
17 Actuator(QObject* parent, const QString& label, float min, float max, float defaultValue, int function, bool isMotor)
18 : QObject(parent), _label(label), _min(min), _max(max), _defaultValue(defaultValue), _function(function),
19 _isMotor(isMotor) {}
20
21 Q_PROPERTY(QString label READ label CONSTANT)
22 Q_PROPERTY(float min READ min CONSTANT)
23 Q_PROPERTY(float max READ max CONSTANT)
24 Q_PROPERTY(float defaultValue READ defaultValue CONSTANT)
25 Q_PROPERTY(int function READ function CONSTANT)
26 Q_PROPERTY(bool isMotor READ isMotor CONSTANT)
27
28 const QString& label() const { return _label; }
29 float min() const { return _min; }
30 float max() const { return _max; }
31 float defaultValue() const { return _defaultValue; }
32 int function() const { return _function; }
33 bool isMotor() const { return _isMotor; }
34
35private:
36 const QString _label;
37 const float _min;
38 const float _max;
39 const float _defaultValue;
40 const int _function;
41 const bool _isMotor;
42};
43
44class ActuatorTest : public QObject
45{
46 Q_OBJECT
47public:
48 ActuatorTest(Vehicle* vehicle);
49
51
52 Q_PROPERTY(QmlObjectListModel* actuators READ actuators NOTIFY actuatorsChanged)
54 Q_PROPERTY(bool hadFailure READ hadFailure NOTIFY hadFailureChanged)
55
56 QmlObjectListModel* actuators() { return _actuators; }
57 Actuator* allMotorsActuator() { return _allMotorsActuator; }
58
59 void updateFunctions(const QList<Actuator*>& actuators);
60
64 Q_INVOKABLE void setActive(bool active);
65
73 Q_INVOKABLE void setChannelTo(int index, float value);
74
79 Q_INVOKABLE void stopControl(int index);
80
81 bool hadFailure() const { return _hadFailure; }
82
83signals:
86
87private:
88
89 struct ActuatorState {
90 enum class State {
91 NotActive,
92 Active,
93 StopRequest,
94 Stopping
95 };
96 State state{State::NotActive};
97 float value{0.f};
98 QElapsedTimer lastUpdated;
99 };
100
101 void resetStates();
102
103 static void ackHandlerEntry(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode);
104 void ackHandler(MAV_RESULT commandResult, Vehicle::MavCmdResultFailureCode_t failureCode);
105 void sendMavlinkRequest(int function, float value, float timeout);
106
107 void sendNext();
108 void watchdogTimeout();
109
110 QmlObjectListModel* _actuators{new QmlObjectListModel(this)};
111 Vehicle* _vehicle{nullptr};
112 Actuator* _allMotorsActuator{nullptr};
113 bool _active{false};
114 bool _commandInProgress{false};
115
116 QList<ActuatorState> _states;
117 int _currentState{-1};
118 QTimer _watchdogTimer;
119 bool _hadFailure{false};
120};
121
122} // namespace ActuatorTesting
void updateFunctions(const QList< Actuator * > &actuators)
void setChannelTo(int index, float value)
QString label READ label CONSTANT(float min READ min CONSTANT) 1(float max READ max CONSTANT) 1(float defaultValue READ defaultValue CONSTANT) 1(int function READ function CONSTANT) 1(bool isMotor READ isMotor CONSTANT) const QString &label() const
Actuator(QObject *parent, const QString &label, float min, float max, float defaultValue, int function, bool isMotor)
MavCmdResultFailureCode_t
Definition Vehicle.h:618