QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
ActuatorTesting.cc
Go to the documentation of this file.
1#include "ActuatorTesting.h"
2#include "Common.h"
3#include "QGCApplication.h"
4
5using namespace ActuatorTesting;
6
8 : _vehicle(vehicle)
9{
10 _watchdogTimer.setInterval(100);
11 _watchdogTimer.setSingleShot(false);
12 connect(&_watchdogTimer, &QTimer::timeout, this, &ActuatorTest::watchdogTimeout);
13 _watchdogTimer.start();
14}
15
17{
18 _actuators->clearAndDeleteContents();
19 delete _allMotorsActuator;
20}
21
22void ActuatorTest::updateFunctions(const QList<Actuator*> &actuators)
23{
24 _actuators->clearAndDeleteContents();
25
26 if (_allMotorsActuator) {
27 _allMotorsActuator->deleteLater();
28 }
29
30 _allMotorsActuator = nullptr;
31
32 Actuator* motorActuator{nullptr};
33 for (const auto& actuator : actuators) {
34 if (actuator->isMotor()) {
35 motorActuator = actuator;
36 }
37 _actuators->append(actuator);
38 }
39 if (motorActuator) {
40 _allMotorsActuator = new Actuator(this, tr("All Motors"), motorActuator->min(), motorActuator->max(), motorActuator->defaultValue(),
41 motorActuator->function(), true);
42 }
43 resetStates();
44
45 emit actuatorsChanged();
46}
47
48void ActuatorTest::resetStates()
49{
50 _states.clear();
51 _currentState = -1;
52 for (int i = 0; i < _actuators->count(); ++i) {
53 _states.append(ActuatorState{});
54 }
55}
56
57void ActuatorTest::watchdogTimeout()
58{
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;
64 }
65 }
66 }
67 sendNext();
68}
69
70void ActuatorTest::setChannelTo(int index, float value)
71{
72 if (!_active || index >= _states.size()) {
73 return;
74 }
75 qCDebug(ActuatorsConfigLog) << "setting actuator: index:" << index << "value:" << value;
76
77 _states[index].value = value;
78 _states[index].state = ActuatorState::State::Active;
79 _states[index].lastUpdated.start();
80 sendNext();
81}
82
84{
85 if (index >= _states.size() || index < -1) {
86 return;
87 }
88 qCDebug(ActuatorsConfigLog) << "stop actuator control: index:" << index;
89
90 if (index == -1) {
91 for (int i = 0; i < _states.size(); ++i) {
92 if (_states[i].state == ActuatorState::State::Active) {
93 _states[i].state = ActuatorState::State::StopRequest;
94 }
95 }
96 } else {
97 if (_states[index].state == ActuatorState::State::Active) {
98 _states[index].state = ActuatorState::State::StopRequest;
99 }
100 }
101 sendNext();
102}
103
104void ActuatorTest::setActive(bool active)
105{
106 qCDebug(ActuatorsConfigLog) << "setting active: " << active;
107 if (!active) {
108 stopControl(-1);
109 }
110 _active = active;
111}
112
113void ActuatorTest::ackHandlerEntry(void* resultHandlerData, int /*compId*/, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode)
114{
115 ActuatorTest* actuatorTest = (ActuatorTest*)resultHandlerData;
116 actuatorTest->ackHandler(static_cast<MAV_RESULT>(ack.result), failureCode);
117}
118
119void ActuatorTest::ackHandler(MAV_RESULT commandResult, Vehicle::MavCmdResultFailureCode_t failureCode)
120{
121 // upon receiving an (n)ack, continuously cycle through the active actuators, one at a time
122 _commandInProgress = false;
124 // on timeout, just try the next one
125 sendNext();
126 } else if (commandResult == MAV_RESULT_ACCEPTED) {
127 if (_currentState != -1 && _states[_currentState].state == ActuatorState::State::Stopping) {
128 _states[_currentState].state = ActuatorState::State::NotActive;
129 }
130 sendNext();
131 } else { // failure
132 if (_currentState != -1) {
133 _states[_currentState].state = ActuatorState::State::NotActive;
134 }
135
136 if (!_hadFailure) {
137 QString message;
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");
144 } else {
145 message = tr("Actuator test command failed");
146 }
147 qgcApp()->showAppMessage(message);
148 _hadFailure = true;
149 emit hadFailureChanged();
150 }
151 sendNext();
152 }
153}
154
155void ActuatorTest::sendNext()
156{
157 if (_commandInProgress) {
158 return;
159 }
160
161 // find the next actuator not in state NotActive
162 for (int i = 0; i < _states.size(); ++i) {
163 _currentState = (_currentState + 1) % _states.size();
164 Actuator* actuator = _actuators->value<Actuator*>(_currentState);
165 if (_states[_currentState].state == ActuatorState::State::Active) {
166 sendMavlinkRequest(actuator->function(), _states[_currentState].value, 1.f);
167 break;
168 } else if (_states[_currentState].state == ActuatorState::State::StopRequest) {
169 _states[_currentState].state = ActuatorState::State::Stopping;
170 sendMavlinkRequest(actuator->function(), NAN, 0.f);
171 break;
172 }
173 }
174}
175
176void ActuatorTest::sendMavlinkRequest(int function, float value, float timeout)
177{
178 qCDebug(ActuatorsConfigLog) << "Sending actuator test function:" << function << "value:" << value;
179
180 // TODO: consider using a lower command timeout
181
182 Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {};
183 handlerInfo.resultHandler = ackHandlerEntry;
184 handlerInfo.resultHandlerData = this;
185
187 &handlerInfo,
188 MAV_COMP_ID_AUTOPILOT1, // the ID of the autopilot
189 MAV_CMD_ACTUATOR_TEST, // the mavlink command
190 value, // value
191 timeout, // timeout
192 0, // unused parameter
193 0, // unused parameter
194 1000+function, // function
195 0, // unused parameter
196 0);
197 _commandInProgress = true;
198}
#define qgcApp()
void updateFunctions(const QList< Actuator * > &actuators)
void setChannelTo(int index, float value)
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
T value(int index) const
int count() const override final
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
MavCmdResultFailureCode_t
Definition Vehicle.h:618
@ MavCmdResultFailureNoResponseToCommand
No response from vehicle to command.
Definition Vehicle.h:620
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.
Definition Vehicle.cc:2339
MavCmdResultHandler resultHandler
Definition Vehicle.h:639
void * resultHandlerData
‍nullptr for no handler
Definition Vehicle.h:640