7#include <QtCore/QObject>
8#include <QtCore/QString>
9#include <QtCore/QTimer>
28 const QString& label()
const {
return _label; }
29 float min()
const {
return _min; }
30 float max()
const {
return _max; }
39 const float _defaultValue;
89 struct ActuatorState {
96 State state{State::NotActive};
98 QElapsedTimer lastUpdated;
105 void sendMavlinkRequest(
int function,
float value,
float timeout);
108 void watchdogTimeout();
112 Actuator* _allMotorsActuator{
nullptr};
114 bool _commandInProgress{
false};
116 QList<ActuatorState> _states;
117 int _currentState{-1};
118 QTimer _watchdogTimer;
119 bool _hadFailure{
false};
void setActive(bool active)
Actuator * allMotorsActuator()
void updateFunctions(const QList< Actuator * > &actuators)
void setChannelTo(int index, float value)
void stopControl(int index)
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
float defaultValue() const
Actuator(QObject *parent, const QString &label, float min, float max, float defaultValue, int function, bool isMotor)
MavCmdResultFailureCode_t