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 "VehicleTypes.h"
7#include "MAVLinkEnums.h"
8#include "QGCMAVLinkTypes.h"
9
10#include <QtCore/QObject>
11#include <QtCore/QString>
12#include <QtCore/QTimer>
13
14class Vehicle;
15
16namespace ActuatorTesting {
17
18class Actuator : public QObject
19{
20 Q_OBJECT
21public:
22 Actuator(QObject* parent, const QString& label, float min, float max, float defaultValue, int function, bool isMotor)
23 : QObject(parent), _label(label), _min(min), _max(max), _defaultValue(defaultValue), _function(function),
24 _isMotor(isMotor) {}
25
26 Q_PROPERTY(QString label READ label CONSTANT)
27 Q_PROPERTY(float min READ min CONSTANT)
28 Q_PROPERTY(float max READ max CONSTANT)
29 Q_PROPERTY(float defaultValue READ defaultValue CONSTANT)
30 Q_PROPERTY(int function READ function CONSTANT)
31 Q_PROPERTY(bool isMotor READ isMotor CONSTANT)
32
33 const QString& label() const { return _label; }
34 float min() const { return _min; }
35 float max() const { return _max; }
36 float defaultValue() const { return _defaultValue; }
37 int function() const { return _function; }
38 bool isMotor() const { return _isMotor; }
39
40private:
41 const QString _label;
42 const float _min;
43 const float _max;
44 const float _defaultValue;
45 const int _function;
46 const bool _isMotor;
47};
48
49class ActuatorTest : public QObject
50{
51 Q_OBJECT
52public:
53 ActuatorTest(Vehicle* vehicle);
54
56
59 Q_PROPERTY(bool hadFailure READ hadFailure NOTIFY hadFailureChanged)
60
61 QmlObjectListModel* actuators() { return _actuators; }
62 Actuator* allMotorsActuator() { return _allMotorsActuator; }
63
64 void updateFunctions(const QList<Actuator*>& actuators);
65
69 Q_INVOKABLE void setActive(bool active);
70
78 Q_INVOKABLE void setChannelTo(int index, float value);
79
84 Q_INVOKABLE void stopControl(int index);
85
86 bool hadFailure() const { return _hadFailure; }
87
88signals:
91
92private:
93
94 struct ActuatorState {
95 enum class State {
96 NotActive,
97 Active,
98 StopRequest,
99 Stopping
100 };
101 State state{State::NotActive};
102 float value{0.f};
103 QElapsedTimer lastUpdated;
104 };
105
106 void resetStates();
107
108 static void ackHandlerEntry(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, VehicleTypes::MavCmdResultFailureCode_t failureCode);
109 void ackHandler(MAV_RESULT commandResult, VehicleTypes::MavCmdResultFailureCode_t failureCode);
110 void sendMavlinkRequest(int function, float value, float timeout);
111
112 void sendNext();
113 void watchdogTimeout();
114
115 QmlObjectListModel* _actuators{new QmlObjectListModel(this)};
116 Vehicle* _vehicle{nullptr};
117 Actuator* _allMotorsActuator{nullptr};
118 bool _active{false};
119 bool _commandInProgress{false};
120
121 QList<ActuatorState> _states;
122 int _currentState{-1};
123 QTimer _watchdogTimer;
124 bool _hadFailure{false};
125};
126
127} // namespace ActuatorTesting
struct __mavlink_command_ack_t mavlink_command_ack_t
Q_INVOKABLE void setActive(bool active)
void updateFunctions(const QList< Actuator * > &actuators)
Q_INVOKABLE void setChannelTo(int index, float value)
Q_INVOKABLE void stopControl(int index)
QmlObjectListModel * actuators()
const QString & label() const
Actuator(QObject *parent, const QString &label, float min, float max, float defaultValue, int function, bool isMotor)