9 : QObject(parent), _vehicle(vehicle), _actuators(actuators)
11 _spinTimer.setInterval(_spinTimeoutDefaultSec);
12 _spinTimer.setSingleShot(
true);
13 connect(&_spinTimer, &QTimer::timeout,
this, &MotorAssignment::spinTimeout);
18 if (_state != State::Idle) {
19 qCWarning(ActuatorsConfigLog) <<
"Already init/running";
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());
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) {
45 selectedAssignment[currentFunction - firstMotorsFunction] =
true;
47 otherAssignment[currentFunction - firstMotorsFunction] =
true;
54 int numAssignedToSelected = 0;
55 for (
int i = 0; i < numMotors; ++i) {
56 numAssigned += selectedAssignment[i] || otherAssignment[i];
57 numAssignedToSelected += selectedAssignment[i];
60 QString selectedActuatorOutputName = qobject_cast<ActuatorOutputs::ActuatorOutput*>(_actuators->
get(selectedActuatorIdx))->label();
62 _assignMotors =
false;
64 if (numAssigned == 0 && _functionFacts[selectedActuatorIdx].size() >= numMotors) {
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);
71 } else if (numAssigned > 0 && numAssignedToSelected == 0 && _functionFacts[selectedActuatorIdx].size() >= numMotors) {
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);
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.");
85R
"(This will automatically spin individual motors at 15% thrust.<br /><br />
86<b>Warning: Only proceed if you removed all propellers</b>.<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 />
95Do you wish to proceed?)").arg(extraMessage);
98 _selectedActuatorIdx = selectedActuatorIdx;
99 _firstMotorsFunction = firstMotorsFunction;
100 _numMotors = numMotors;
101 _selectedMotors.clear();
102 _state = State::Init;
109 if (_state != State::Init) {
110 qCWarning(ActuatorsConfigLog) <<
"Invalid state";
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);
126 for (
auto& fact : _functionFacts[_selectedActuatorIdx]) {
127 fact->setRawValue(_firstMotorsFunction + index);
128 if (++index >= _numMotors) {
133 _state = State::Running;
135 _spinTimer.setInterval(_assignMotors ? _spinTimeoutHighSec : _spinTimeoutDefaultSec);
141 if (_state != State::Running) {
142 qCDebug(ActuatorsConfigLog) <<
"Not running";
146 _selectedMotors.append(motorIndex);
147 if (_selectedMotors.size() == _numMotors) {
150 for (
auto& group : _functionFacts) {
151 for (
auto& fact : group) {
152 int currentFunction = fact->rawValue().toInt();
153 if (currentFunction >= _firstMotorsFunction && currentFunction < _firstMotorsFunction + _numMotors) {
155 fact->setRawValue(_firstMotorsFunction + _selectedMotors[currentFunction - _firstMotorsFunction]);
160 _state = State::Idle;
164 _spinTimer.setInterval(_spinTimeoutDefaultSec);
171 if (!_commandInProgress) {
173 int motorIndex = _selectedMotors.size();
174 sendMavlinkRequest(_firstMotorsFunction + motorIndex, 0.15f);
181 _state = State::Idle;
186void MotorAssignment::spinTimeout()
194 motorAssignment->ackHandler(
static_cast<MAV_RESULT
>(ack.result), failureCode);
199 _commandInProgress =
false;
202 qgcApp()->showAppMessage(tr(
"Actuator test command failed"));
206void MotorAssignment::sendMavlinkRequest(
int function,
float value)
208 qCDebug(ActuatorsConfigLog) <<
"Sending actuator test function:" << function <<
"value:" << value;
216 MAV_COMP_ID_AUTOPILOT1,
217 MAV_CMD_ACTUATOR_TEST,
225 _commandInProgress =
true;
void selectMotor(int motorIndex)
bool initAssignment(int selectedActuatorIdx, int firstMotorsFunction, int numMotors)
MotorAssignment(QObject *parent, Vehicle *vehicle, QmlObjectListModel *actuators)
int count() const override final
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