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 "VehicleTypes.h"
5#include "MAVLinkEnums.h"
6#include "QGCMAVLinkTypes.h"
7
8#include <QtCore/QObject>
9#include <QtCore/QString>
10#include <QtCore/QTimer>
11
12class Fact;
14class Vehicle;
15
20class MotorAssignment : public QObject
21{
22 Q_OBJECT
23public:
24 MotorAssignment(QObject* parent, Vehicle* vehicle, QmlObjectListModel* actuators);
25
26 virtual ~MotorAssignment() = default;
27
32 bool initAssignment(int selectedActuatorIdx, int firstMotorsFunction, int numMotors);
33
37 void start();
38
39 void selectMotor(int motorIndex);
40
41 void spinCurrentMotor();
42
43 void abort();
44
45 bool active() const { return _state == State::Running; }
46
47 const QString& message() const { return _message; }
48
49signals:
52 void onAbort();
53
54private slots:
55 void spinTimeout();
56
57private:
58 static constexpr int _spinTimeoutDefaultSec = 1000;
59 static constexpr int _spinTimeoutHighSec = 3000;
60
61 static void ackHandlerEntry(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, VehicleTypes::MavCmdResultFailureCode_t failureCode);
62 void ackHandler(MAV_RESULT commandResult, VehicleTypes::MavCmdResultFailureCode_t failureCode);
63 void sendMavlinkRequest(int function, float value);
64
65 enum class State {
66 Idle,
67 Init,
68 Running
69 };
70
71 Vehicle* _vehicle{nullptr};
72 QmlObjectListModel* _actuators{nullptr};
73
74 int _selectedActuatorIdx{-1};
75 int _firstMotorsFunction{};
76 int _numMotors{};
77 QTimer _spinTimer;
78
79 State _state{State::Idle};
80 bool _assignMotors{false};
81 QList<int> _selectedMotors{};
82 bool _commandInProgress{false};
83 QList<QList<Fact*>> _functionFacts;
84 QString _message;
85};
struct __mavlink_command_ack_t mavlink_command_ack_t
A Fact is used to hold a single value within the system.
Definition Fact.h:17
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()