QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MotorAssignment.cc
Go to the documentation of this file.
1#include "MotorAssignment.h"
2#include "QGCApplication.h"
3#include "ActuatorOutputs.h"
5
6#include <vector>
7
8MotorAssignment::MotorAssignment(QObject* parent, Vehicle* vehicle, QmlObjectListModel* actuators)
9 : QObject(parent), _vehicle(vehicle), _actuators(actuators)
10{
11 _spinTimer.setInterval(_spinTimeoutDefaultSec);
12 _spinTimer.setSingleShot(true);
13 connect(&_spinTimer, &QTimer::timeout, this, &MotorAssignment::spinTimeout);
14}
15
16bool MotorAssignment::initAssignment(int selectedActuatorIdx, int firstMotorsFunction, int numMotors)
17{
18 if (_state != State::Idle) {
19 qCWarning(ActuatorsConfigLog) << "Already init/running";
20 }
21
22 // gather all the function facts
23 _functionFacts.clear();
24 for (int groupIdx = 0; groupIdx < _actuators->count(); groupIdx++) {
25 auto group = qobject_cast<ActuatorOutputs::ActuatorOutput*>(_actuators->get(groupIdx));
26 _functionFacts.append(QList<Fact*>{});
27 group->getAllChannelFunctions(_functionFacts.last());
28 }
29
30 // Check the current configuration for these cases:
31 // - no motors assigned: ask to assign to selected output
32 // - there are motors, but none assigned to the selected output: ask to remove and assign to selected output
33 // - partially assigned motors: abort with error
34 // - all assigned to current output: nothing further to do
35
36 int index = 0;
37 std::vector<bool> selectedAssignment(numMotors);
38 std::vector<bool> otherAssignment(numMotors);
39 for (auto& group : _functionFacts) {
40 bool selected = index == selectedActuatorIdx;
41 for (auto& fact : group) {
42 int currentFunction = fact->rawValue().toInt();
43 if (currentFunction >= firstMotorsFunction && currentFunction < firstMotorsFunction + numMotors) {
44 if (selected) {
45 selectedAssignment[currentFunction - firstMotorsFunction] = true;
46 } else {
47 otherAssignment[currentFunction - firstMotorsFunction] = true;
48 }
49 }
50 }
51 ++index;
52 }
53 int numAssigned = 0;
54 int numAssignedToSelected = 0;
55 for (int i = 0; i < numMotors; ++i) {
56 numAssigned += selectedAssignment[i] || otherAssignment[i];
57 numAssignedToSelected += selectedAssignment[i];
58 }
59
60 QString selectedActuatorOutputName = qobject_cast<ActuatorOutputs::ActuatorOutput*>(_actuators->get(selectedActuatorIdx))->label();
61
62 _assignMotors = false;
63 QString extraMessage;
64 if (numAssigned == 0 && _functionFacts[selectedActuatorIdx].size() >= numMotors) {
65 _assignMotors = true;
66 extraMessage = tr(
67R"(<br />No motors are assigned yet.
68By saying yes, all motors will be assigned to the first %1 channels of the selected output (%2)
69 (you can also first assign all motors, then start the identification).<br />)").arg(numMotors).arg(selectedActuatorOutputName);
70
71 } else if (numAssigned > 0 && numAssignedToSelected == 0 && _functionFacts[selectedActuatorIdx].size() >= numMotors) {
72 _assignMotors = true;
73 extraMessage = tr(
74R"(<br />Motors are currently assigned to a different output.
75By saying yes, all motors will be reassigned to the first %1 channels of the selected output (%2).<br />)")
76 .arg(numMotors).arg(selectedActuatorOutputName);
77
78 } else if (numAssigned < numMotors) {
79 _message = tr("Not all motors are assigned yet. Either clear all existing assignments or assign all motors to an output.");
80 emit messageChanged();
81 return false;
82 }
83
84 _message = tr(
85R"(This will automatically spin individual motors at 15% thrust.<br /><br />
86<b>Warning: Only proceed if you removed all propellers</b>.<br />
87%1
88<br />
89The procedure is as following:<br />
90- After confirming, the first motor starts to spin for 0.5 seconds.<br />
91- Then click on the motor that was spinning.<br />
92- The above steps are repeated for all motors.<br />
93- The motor output functions will automatically be reassigned by the selected order.<br />
94<br />
95Do you wish to proceed?)").arg(extraMessage);
96 emit messageChanged();
97
98 _selectedActuatorIdx = selectedActuatorIdx;
99 _firstMotorsFunction = firstMotorsFunction;
100 _numMotors = numMotors;
101 _selectedMotors.clear();
102 _state = State::Init;
103 emit activeChanged();
104 return true;
105}
106
108{
109 if (_state != State::Init) {
110 qCWarning(ActuatorsConfigLog) << "Invalid state";
111 return;
112 }
113
114 if (_assignMotors) {
115 // clear all motors
116 for (auto& group : _functionFacts) {
117 for (auto& fact : group) {
118 int currentFunction = fact->rawValue().toInt();
119 if (currentFunction >= _firstMotorsFunction && currentFunction < _firstMotorsFunction + _numMotors) {
120 fact->setRawValue(0);
121 }
122 }
123 }
124 // assign to selected output
125 int index = 0;
126 for (auto& fact : _functionFacts[_selectedActuatorIdx]) {
127 fact->setRawValue(_firstMotorsFunction + index);
128 if (++index >= _numMotors) {
129 break;
130 }
131 }
132 }
133 _state = State::Running;
134 emit activeChanged();
135 _spinTimer.setInterval(_assignMotors ? _spinTimeoutHighSec : _spinTimeoutDefaultSec);
136 _spinTimer.start();
137}
138
139void MotorAssignment::selectMotor(int motorIndex)
140{
141 if (_state != State::Running) {
142 qCDebug(ActuatorsConfigLog) << "Not running";
143 return;
144 }
145
146 _selectedMotors.append(motorIndex);
147 if (_selectedMotors.size() == _numMotors) {
148
149 // finished, change functions
150 for (auto& group : _functionFacts) {
151 for (auto& fact : group) {
152 int currentFunction = fact->rawValue().toInt();
153 if (currentFunction >= _firstMotorsFunction && currentFunction < _firstMotorsFunction + _numMotors) {
154 // this is set to a motor -> update
155 fact->setRawValue(_firstMotorsFunction + _selectedMotors[currentFunction - _firstMotorsFunction]);
157 }
158 }
159
160 _state = State::Idle;
161 emit activeChanged();
162 } else {
163 // spin the next motor after some time
164 _spinTimer.setInterval(_spinTimeoutDefaultSec);
165 _spinTimer.start();
166 }
167}
168
170{
171 if (!_commandInProgress) {
172 _spinTimer.stop();
173 int motorIndex = _selectedMotors.size();
174 sendMavlinkRequest(_firstMotorsFunction + motorIndex, 0.15f);
175 }
176}
177
179{
180 _spinTimer.stop();
181 _state = State::Idle;
182 emit activeChanged();
183 emit onAbort();
184}
185
186void MotorAssignment::spinTimeout()
187{
189}
190
191void MotorAssignment::ackHandlerEntry(void* resultHandlerData, int /*compId*/, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode)
192{
193 MotorAssignment* motorAssignment = (MotorAssignment*)resultHandlerData;
194 motorAssignment->ackHandler(static_cast<MAV_RESULT>(ack.result), failureCode);
195}
196
197void MotorAssignment::ackHandler(MAV_RESULT commandResult, Vehicle::MavCmdResultFailureCode_t failureCode)
198{
199 _commandInProgress = false;
200 if (failureCode != Vehicle::MavCmdResultFailureNoResponseToCommand && commandResult != MAV_RESULT_ACCEPTED) {
201 abort();
202 qgcApp()->showAppMessage(tr("Actuator test command failed"));
203 }
204}
205
206void MotorAssignment::sendMavlinkRequest(int function, float value)
207{
208 qCDebug(ActuatorsConfigLog) << "Sending actuator test function:" << function << "value:" << value;
209
210 Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {};
211 handlerInfo.resultHandler = ackHandlerEntry;
212 handlerInfo.resultHandlerData = this;
213
215 &handlerInfo,
216 MAV_COMP_ID_AUTOPILOT1, // the ID of the autopilot
217 MAV_CMD_ACTUATOR_TEST, // the mavlink command
218 value, // value
219 0.5f, // timeout
220 0, // unused parameter
221 0, // unused parameter
222 1000+function, // function
223 0, // unused parameter
224 0);
225 _commandInProgress = true;
226}
#define qgcApp()
void activeChanged()
void selectMotor(int motorIndex)
bool initAssignment(int selectedActuatorIdx, int firstMotorsFunction, int numMotors)
MotorAssignment(QObject *parent, Vehicle *vehicle, QmlObjectListModel *actuators)
void messageChanged()
QObject * get(int index)
int count() const override final
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