7#include "MAVLinkEnums.h"
10#include <QtCore/QObject>
11#include <QtCore/QString>
12#include <QtCore/QTimer>
27 Q_PROPERTY(
float min READ
min CONSTANT)
28 Q_PROPERTY(
float max READ
max CONSTANT)
33 const QString&
label()
const {
return _label; }
34 float min()
const {
return _min; }
35 float max()
const {
return _max; }
44 const float _defaultValue;
94 struct ActuatorState {
101 State state{State::NotActive};
103 QElapsedTimer lastUpdated;
110 void sendMavlinkRequest(
int function,
float value,
float timeout);
113 void watchdogTimeout();
117 Actuator* _allMotorsActuator{
nullptr};
119 bool _commandInProgress{
false};
121 QList<ActuatorState> _states;
122 int _currentState{-1};
123 QTimer _watchdogTimer;
124 bool _hadFailure{
false};
struct __mavlink_command_ack_t mavlink_command_ack_t
Q_INVOKABLE void setActive(bool active)
Actuator * allMotorsActuator()
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
float defaultValue() const
Actuator(QObject *parent, const QString &label, float min, float max, float defaultValue, int function, bool isMotor)
MavCmdResultFailureCode_t