QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
Autotune.cpp
Go to the documentation of this file.
1#include "Autotune.h"
2#include "QGCApplication.h"
3
4//-----------------------------------------------------------------------------
6 QObject(vehicle)
7 , _vehicle(vehicle)
8{
9 _pollTimer.setInterval(1000); // 1s for the polling interval
10 _pollTimer.setSingleShot(false);
11 connect(&_pollTimer, &QTimer::timeout, this, &Autotune::sendMavlinkRequest);
12}
13
14
15//-----------------------------------------------------------------------------
16void Autotune::autotuneRequest()
17{
19
20 startTimers();
21 _autotuneInProgress = true;
22 _autotuneStatus = tr("Autotune: In progress");
23
24 emit autotuneChanged();
25}
26
27
28//-----------------------------------------------------------------------------
29void Autotune::ackHandler(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode)
30{
31 Q_UNUSED(compId);
32 Q_UNUSED(failureCode);
33
34 auto * autotune = static_cast<Autotune *>(resultHandlerData);
35
36 if (autotune->_autotuneInProgress) {
37 if (failureCode == Vehicle::MavCmdResultCommandResultOnly) {
38 if ((ack.result == MAV_RESULT_IN_PROGRESS) || (ack.result == MAV_RESULT_ACCEPTED)) {
39 autotune->handleAckStatus(ack.progress);
40 }
41 else if (ack.result == MAV_RESULT_FAILED) {
42 autotune->handleAckFailure();
43 }
44 else {
45 autotune->handleAckError(ack.result);
46 }
47 } else {
48 autotune->handleAckFailure();
49 }
50 emit autotune->autotuneChanged();
51 } else {
52 qWarning() << "Ack received for a command different from MAV_CMD_DO_AUTOTUNE_ENABLE ot wrong UI state.";
53 }
54}
55
56void Autotune::progressHandler(void* progressHandlerData, int compId, const mavlink_command_ack_t& ack)
57{
58 Q_UNUSED(compId);
59
60 auto * autotune = static_cast<Autotune *>(progressHandlerData);
61
62 if (autotune->_autotuneInProgress) {
63 autotune->handleAckStatus(ack.progress);
64 emit autotune->autotuneChanged();
65 } else {
66 qWarning() << "Ack received for a command different from MAV_CMD_DO_AUTOTUNE_ENABLE ot wrong UI state.";
67 }
68}
69
70//-----------------------------------------------------------------------------
71void Autotune::handleAckStatus(uint8_t ackProgress)
72{
73 _autotuneProgress = ackProgress/100.f;
74
75 if (ackProgress < 20) {
76 _autotuneStatus = tr("Autotune: initializing");
77 }
78 else if (ackProgress < 40) {
79 _autotuneStatus = tr("Autotune: roll");
80 }
81 else if (ackProgress < 60) {
82 _autotuneStatus = tr("Autotune: pitch");
83 }
84 else if (ackProgress < 80) {
85 _autotuneStatus = tr("Autotune: yaw");
86 }
87 else if (ackProgress == 95) {
88 _autotuneStatus = tr("Wait for disarm");
89
90 if(!_disarmMessageDisplayed) {
91 qgcApp()->showAppMessage(tr("Land and disarm the vehicle in order to apply the parameters."));
92 _disarmMessageDisplayed = true;
93 }
94 }
95 else if (ackProgress < 100) {
96 _autotuneStatus = tr("Autotune: in progress");
97 }
98 else { // success or unknown error
99 stopTimers();
100 _autotuneInProgress = false;
101
102 if (ackProgress == 100) {
103 _autotuneStatus = tr("Autotune: Success");
104
105 qgcApp()->showAppMessage(tr("Autotune successful."));
106 }
107 else {
108 _autotuneStatus = tr("Autotune: Unknown error");
109 }
110 }
111}
112
113
114//-----------------------------------------------------------------------------
115void Autotune::handleAckFailure()
116{
117 stopTimers();
118 _autotuneInProgress = false;
119 _disarmMessageDisplayed = false;
120 _autotuneStatus = tr("Autotune: Failed");
121}
122
123
124//-----------------------------------------------------------------------------
125void Autotune::handleAckError(uint8_t ackError)
126{
127 stopTimers();
128 _autotuneInProgress = false;
129 _disarmMessageDisplayed = false;
130 _autotuneStatus = tr("Autotune: Ack error %1").arg(ackError);
131}
132
133
134//-----------------------------------------------------------------------------
135void Autotune::startTimers()
136{
137 _pollTimer.start();
138}
139
140
141//-----------------------------------------------------------------------------
142void Autotune::stopTimers()
143{
144 _pollTimer.stop();
145}
146
147
148//-----------------------------------------------------------------------------
150{
151 Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {};
152 handlerInfo.resultHandler = ackHandler;
153 handlerInfo.resultHandlerData = this;
154 handlerInfo.progressHandler = progressHandler;
155 handlerInfo.progressHandlerData = this;
156
158 &handlerInfo,
159 MAV_COMP_ID_AUTOPILOT1, // the ID of the autopilot
160 MAV_CMD_DO_AUTOTUNE_ENABLE, // the mavlink command
161 1, // request autotune
162 0, // unused parameter
163 0, // unused parameter
164 0, // unused parameter
165 0, // unused parameter
166 0, // unused parameter
167 0);
168}
#define qgcApp()
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
Autotune(Vehicle *vehicle)
Definition Autotune.cpp:5
void autotuneChanged()
void sendMavlinkRequest()
Definition Autotune.cpp:149
MavCmdResultFailureCode_t
Definition Vehicle.h:618
@ MavCmdResultCommandResultOnly
commandResult specifies full success/fail info
Definition Vehicle.h:619
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
MavCmdProgressHandler progressHandler
Definition Vehicle.h:641