10 _watchdogTimer.setInterval(100);
11 _watchdogTimer.setSingleShot(
false);
12 connect(&_watchdogTimer, &QTimer::timeout,
this, &ActuatorTest::watchdogTimeout);
13 _watchdogTimer.start();
19 delete _allMotorsActuator;
26 if (_allMotorsActuator) {
27 _allMotorsActuator->deleteLater();
30 _allMotorsActuator =
nullptr;
33 for (
const auto& actuator : actuators) {
34 if (actuator->isMotor()) {
35 motorActuator = actuator;
37 _actuators->
append(actuator);
40 _allMotorsActuator =
new Actuator(
this, tr(
"All Motors"), motorActuator->min(), motorActuator->max(), motorActuator->defaultValue(),
41 motorActuator->function(),
true);
48void ActuatorTest::resetStates()
52 for (
int i = 0; i < _actuators->
count(); ++i) {
53 _states.append(ActuatorState{});
57void ActuatorTest::watchdogTimeout()
59 for (
int i = 0; i < _states.size(); ++i) {
60 if (_states[i].state == ActuatorState::State::Active) {
61 if (_states[i].lastUpdated.elapsed() > 100) {
62 qCWarning(ActuatorsConfigLog) <<
"Stopping actuator due to timeout:" << i;
63 _states[i].state = ActuatorState::State::StopRequest;
72 if (!_active || index >= _states.size()) {
75 qCDebug(ActuatorsConfigLog) <<
"setting actuator: index:" << index <<
"value:" << value;
77 _states[index].value = value;
78 _states[index].state = ActuatorState::State::Active;
79 _states[index].lastUpdated.start();
85 if (index >= _states.size() || index < -1) {
88 qCDebug(ActuatorsConfigLog) <<
"stop actuator control: index:" << index;
91 for (
int i = 0; i < _states.size(); ++i) {
92 if (_states[i].state == ActuatorState::State::Active) {
93 _states[i].state = ActuatorState::State::StopRequest;
97 if (_states[index].state == ActuatorState::State::Active) {
98 _states[index].state = ActuatorState::State::StopRequest;
106 qCDebug(ActuatorsConfigLog) <<
"setting active: " << active;
116 actuatorTest->ackHandler(
static_cast<MAV_RESULT
>(ack.result), failureCode);
122 _commandInProgress =
false;
126 }
else if (commandResult == MAV_RESULT_ACCEPTED) {
127 if (_currentState != -1 && _states[_currentState].state == ActuatorState::State::Stopping) {
128 _states[_currentState].state = ActuatorState::State::NotActive;
132 if (_currentState != -1) {
133 _states[_currentState].state = ActuatorState::State::NotActive;
138 if (commandResult == MAV_RESULT_TEMPORARILY_REJECTED) {
139 message = tr(
"Actuator test command temporarily rejected");
140 }
else if (commandResult == MAV_RESULT_DENIED) {
141 message = tr(
"Actuator test command denied");
142 }
else if (commandResult == MAV_RESULT_UNSUPPORTED) {
143 message = tr(
"Actuator test command not supported");
145 message = tr(
"Actuator test command failed");
147 qgcApp()->showAppMessage(message);
155void ActuatorTest::sendNext()
157 if (_commandInProgress) {
162 for (
int i = 0; i < _states.size(); ++i) {
163 _currentState = (_currentState + 1) % _states.size();
165 if (_states[_currentState].state == ActuatorState::State::Active) {
166 sendMavlinkRequest(actuator->
function(), _states[_currentState].value, 1.f);
168 }
else if (_states[_currentState].state == ActuatorState::State::StopRequest) {
169 _states[_currentState].state = ActuatorState::State::Stopping;
170 sendMavlinkRequest(actuator->
function(), NAN, 0.f);
176void ActuatorTest::sendMavlinkRequest(
int function,
float value,
float timeout)
178 qCDebug(ActuatorsConfigLog) <<
"Sending actuator test function:" << function <<
"value:" << value;
188 MAV_COMP_ID_AUTOPILOT1,
189 MAV_CMD_ACTUATOR_TEST,
197 _commandInProgress =
true;
void setActive(bool active)
ActuatorTest(Vehicle *vehicle)
void updateFunctions(const QList< Actuator * > &actuators)
void setChannelTo(int index, float value)
void stopControl(int index)
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
int count() const override final
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
MavCmdResultFailureCode_t
@ MavCmdResultFailureNoResponseToCommand
No response from vehicle to command.
void sendMavCommandWithHandler(const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
Sends the command and calls the callback with the result.
MavCmdResultHandler resultHandler
void * resultHandlerData
‍nullptr for no handler