QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
Autotune.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QTimer>
4#include <QtQmlIntegration/QtQmlIntegration>
5
6#include "Vehicle.h"
7#include "MAVLinkLib.h"
8
9class Autotune : public QObject
10{
11 Q_OBJECT
12 QML_ELEMENT
13 QML_UNCREATABLE("")
14
15public:
16 explicit Autotune(Vehicle *vehicle);
17
19 Q_PROPERTY(float autotuneProgress READ autotuneProgress NOTIFY autotuneChanged)
20 Q_PROPERTY(QString autotuneStatus READ autotuneStatus NOTIFY autotuneChanged)
21
22 Q_INVOKABLE void autotuneRequest ();
23
24 static void ackHandler (void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode);
25 static void progressHandler (void* progressHandlerData, int compId, const mavlink_command_ack_t& ack);
26
27 bool autotuneInProgress () { return _autotuneInProgress; }
28 float autotuneProgress () { return _autotuneProgress; }
29 QString autotuneStatus () { return _autotuneStatus; }
30
31
32public slots:
33 void sendMavlinkRequest();
34
35signals:
37
38private:
39 void handleAckStatus(uint8_t ackProgress);
40 void handleAckFailure();
41 void handleAckError(uint8_t ackError);
42 void startTimers();
43 void stopTimers();
44
45private:
46 Vehicle* _vehicle {nullptr};
47 bool _autotuneInProgress {false};
48 float _autotuneProgress {0.0};
49 QString _autotuneStatus {tr("Autotune: Not performed")};
50 bool _disarmMessageDisplayed {false};
51
52 QTimer _pollTimer; // the frequency at which the polling should be performed
53
54};
static void ackHandler(void *resultHandlerData, int compId, const mavlink_command_ack_t &ack, Vehicle::MavCmdResultFailureCode_t failureCode)
Definition Autotune.cpp:29
static void progressHandler(void *progressHandlerData, int compId, const mavlink_command_ack_t &ack)
Definition Autotune.cpp:56
bool autotuneInProgress()
Definition Autotune.h:27
QString autotuneStatus()
Definition Autotune.h:29
void autotuneChanged()
void sendMavlinkRequest()
Definition Autotune.cpp:149
float autotuneProgress()
Definition Autotune.h:28
MavCmdResultFailureCode_t
Definition Vehicle.h:618