9 _pollTimer.setInterval(1000);
10 _pollTimer.setSingleShot(
false);
16void Autotune::autotuneRequest()
21 _autotuneInProgress =
true;
22 _autotuneStatus = tr(
"Autotune: In progress");
32 Q_UNUSED(failureCode);
34 auto * autotune =
static_cast<Autotune *
>(resultHandlerData);
36 if (autotune->_autotuneInProgress) {
38 if ((ack.result == MAV_RESULT_IN_PROGRESS) || (ack.result == MAV_RESULT_ACCEPTED)) {
39 autotune->handleAckStatus(ack.progress);
41 else if (ack.result == MAV_RESULT_FAILED) {
42 autotune->handleAckFailure();
45 autotune->handleAckError(ack.result);
48 autotune->handleAckFailure();
50 emit autotune->autotuneChanged();
52 qWarning() <<
"Ack received for a command different from MAV_CMD_DO_AUTOTUNE_ENABLE ot wrong UI state.";
60 auto * autotune =
static_cast<Autotune *
>(progressHandlerData);
62 if (autotune->_autotuneInProgress) {
63 autotune->handleAckStatus(ack.progress);
64 emit autotune->autotuneChanged();
66 qWarning() <<
"Ack received for a command different from MAV_CMD_DO_AUTOTUNE_ENABLE ot wrong UI state.";
71void Autotune::handleAckStatus(uint8_t ackProgress)
73 _autotuneProgress = ackProgress/100.f;
75 if (ackProgress < 20) {
76 _autotuneStatus = tr(
"Autotune: initializing");
78 else if (ackProgress < 40) {
79 _autotuneStatus = tr(
"Autotune: roll");
81 else if (ackProgress < 60) {
82 _autotuneStatus = tr(
"Autotune: pitch");
84 else if (ackProgress < 80) {
85 _autotuneStatus = tr(
"Autotune: yaw");
87 else if (ackProgress == 95) {
88 _autotuneStatus = tr(
"Wait for disarm");
90 if(!_disarmMessageDisplayed) {
91 qgcApp()->showAppMessage(tr(
"Land and disarm the vehicle in order to apply the parameters."));
92 _disarmMessageDisplayed =
true;
95 else if (ackProgress < 100) {
96 _autotuneStatus = tr(
"Autotune: in progress");
100 _autotuneInProgress =
false;
102 if (ackProgress == 100) {
103 _autotuneStatus = tr(
"Autotune: Success");
105 qgcApp()->showAppMessage(tr(
"Autotune successful."));
108 _autotuneStatus = tr(
"Autotune: Unknown error");
115void Autotune::handleAckFailure()
118 _autotuneInProgress =
false;
119 _disarmMessageDisplayed =
false;
120 _autotuneStatus = tr(
"Autotune: Failed");
125void Autotune::handleAckError(uint8_t ackError)
128 _autotuneInProgress =
false;
129 _disarmMessageDisplayed =
false;
130 _autotuneStatus = tr(
"Autotune: Ack error %1").arg(ackError);
135void Autotune::startTimers()
142void Autotune::stopTimers()
159 MAV_COMP_ID_AUTOPILOT1,
160 MAV_CMD_DO_AUTOTUNE_ENABLE,
static void ackHandler(void *resultHandlerData, int compId, const mavlink_command_ack_t &ack, Vehicle::MavCmdResultFailureCode_t failureCode)
static void progressHandler(void *progressHandlerData, int compId, const mavlink_command_ack_t &ack)
Autotune(Vehicle *vehicle)
void sendMavlinkRequest()
MavCmdResultFailureCode_t
@ MavCmdResultCommandResultOnly
commandResult specifies full success/fail info
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
MavCmdProgressHandler progressHandler
void * progressHandlerData