QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MotorAssignment.h
Go to the documentation of this file.
1#pragma once
2
3#include "Vehicle.h"
4
5#include <QtCore/QObject>
6#include <QtCore/QString>
7#include <QtCore/QTimer>
8
10
15class MotorAssignment : public QObject
16{
17 Q_OBJECT
18public:
19 MotorAssignment(QObject* parent, Vehicle* vehicle, QmlObjectListModel* actuators);
20
21 virtual ~MotorAssignment() = default;
22
27 bool initAssignment(int selectedActuatorIdx, int firstMotorsFunction, int numMotors);
28
32 void start();
33
34 void selectMotor(int motorIndex);
35
36 void spinCurrentMotor();
37
38 void abort();
39
40 bool active() const { return _state == State::Running; }
41
42 const QString& message() const { return _message; }
43
44signals:
47 void onAbort();
48
49private slots:
50 void spinTimeout();
51
52private:
53 static constexpr int _spinTimeoutDefaultSec = 1000;
54 static constexpr int _spinTimeoutHighSec = 3000;
55
56 static void ackHandlerEntry(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode);
57 void ackHandler(MAV_RESULT commandResult, Vehicle::MavCmdResultFailureCode_t failureCode);
58 void sendMavlinkRequest(int function, float value);
59
60 enum class State {
61 Idle,
62 Init,
63 Running
64 };
65
66 Vehicle* _vehicle{nullptr};
67 QmlObjectListModel* _actuators{nullptr};
68
69 int _selectedActuatorIdx{-1};
70 int _firstMotorsFunction{};
71 int _numMotors{};
72 QTimer _spinTimer;
73
74 State _state{State::Idle};
75 bool _assignMotors{false};
76 QList<int> _selectedMotors{};
77 bool _commandInProgress{false};
78 QList<QList<Fact*>> _functionFacts;
79 QString _message;
80};
void activeChanged()
virtual ~MotorAssignment()=default
bool active() const
void selectMotor(int motorIndex)
bool initAssignment(int selectedActuatorIdx, int firstMotorsFunction, int numMotors)
const QString & message() const
void messageChanged()
MavCmdResultFailureCode_t
Definition Vehicle.h:618