• Home
  • Features
  • Pricing
  • Docs
  • Announcements
  • Sign In

mavlink / MAVSDK / 9106367580

16 May 2024 04:12AM UTC coverage: 36.895% (+0.04%) from 36.858%
9106367580

push

github

web-flow
Merge pull request #2301 from mavlink/pr-timeout-fixes

TimeoutHandler fixes

40 of 47 new or added lines in 4 files covered. (85.11%)

3 existing lines in 2 files now uncovered.

10890 of 29516 relevant lines covered (36.9%)

119.76 hits per line

Source File
Press 'n' to go to next uncovered line, 'b' for previous

45.93
/src/mavsdk/core/mavlink_command_sender.cpp
1
#include "mavlink_command_sender.h"
2
#include "mavlink_address.h"
3
#include "system_impl.h"
4
#include "unused.h"
5
#include <cmath>
6
#include <future>
7
#include <memory>
8

9
namespace mavsdk {
10

11
MavlinkCommandSender::MavlinkCommandSender(SystemImpl& system_impl) : _system_impl(system_impl)
69✔
12
{
13
    if (const char* env_p = std::getenv("MAVSDK_COMMAND_DEBUGGING")) {
69✔
14
        if (std::string(env_p) == "1") {
×
15
            LogDebug() << "Command debugging is on.";
×
16
            _command_debugging = true;
×
17
        }
18
    }
19

20
    _system_impl.register_mavlink_message_handler(
69✔
21
        MAVLINK_MSG_ID_COMMAND_ACK,
22
        [this](const mavlink_message_t& message) { receive_command_ack(message); },
39✔
23
        this);
24
}
69✔
25

26
MavlinkCommandSender::~MavlinkCommandSender()
69✔
27
{
28
    if (_command_debugging) {
69✔
NEW
29
        LogDebug() << "CommandSender destroyed";
×
30
    }
31
    _system_impl.unregister_all_mavlink_message_handlers(this);
69✔
32

33
    LockedQueue<Work>::Guard work_queue_guard(_work_queue);
138✔
34
    for (const auto& work : _work_queue) {
70✔
35
        _system_impl.unregister_timeout_handler(work->timeout_cookie);
1✔
36
    }
37
}
69✔
38

39
MavlinkCommandSender::Result
40
MavlinkCommandSender::send_command(const MavlinkCommandSender::CommandInt& command)
×
41
{
42
    // We wrap the async call with a promise and future.
43
    auto prom = std::make_shared<std::promise<Result>>();
×
44
    auto res = prom->get_future();
×
45

46
    queue_command_async(command, [prom](Result result, float progress) {
×
47
        UNUSED(progress);
×
48
        // We can only fulfill the promise once in C++11.
49
        // Therefore, we have to ignore the IN_PROGRESS state and wait
50
        // for the final result.
51
        if (result != Result::InProgress) {
×
52
            prom->set_value(result);
×
53
        }
54
    });
×
55

56
    // Block now to wait for result.
57
    return res.get();
×
58
}
59

60
MavlinkCommandSender::Result
61
MavlinkCommandSender::send_command(const MavlinkCommandSender::CommandLong& command)
×
62
{
63
    // We wrap the async call with a promise and future.
64
    auto prom = std::make_shared<std::promise<Result>>();
×
65
    auto res = prom->get_future();
×
66

67
    queue_command_async(command, [prom](Result result, float progress) {
×
68
        UNUSED(progress);
×
69
        // We can only fulfill the promise once in C++11.
70
        // Therefore, we have to ignore the IN_PROGRESS state and wait
71
        // for the final result.
72
        if (result != Result::InProgress) {
×
73
            prom->set_value(result);
×
74
        }
75
    });
×
76

77
    return res.get();
×
78
}
79

80
void MavlinkCommandSender::queue_command_async(
×
81
    const CommandInt& command, const CommandResultCallback& callback)
82
{
83
    if (_command_debugging) {
×
84
        LogDebug() << "COMMAND_INT " << (int)(command.command) << " to send to "
×
85
                   << (int)(command.target_system_id) << ", " << (int)(command.target_component_id);
×
86
    }
87

88
    CommandIdentification identification = identification_from_command(command);
×
89

90
    for (const auto& work : _work_queue) {
×
91
        if (work->identification == identification && callback == nullptr) {
×
92
            if (_command_debugging) {
×
93
                LogDebug() << "Dropping command " << static_cast<int>(identification.command)
×
94
                           << " that is already being sent";
×
95
            }
96
            return;
×
97
        }
98
    }
99

100
    auto new_work = std::make_shared<Work>();
×
101
    new_work->timeout_s = _system_impl.timeout_s();
×
102
    new_work->command = command;
×
103
    new_work->identification = identification;
×
104
    new_work->callback = callback;
×
105
    _work_queue.push_back(new_work);
×
106
}
107

108
void MavlinkCommandSender::queue_command_async(
40✔
109
    const CommandLong& command, const CommandResultCallback& callback)
110
{
111
    if (_command_debugging) {
40✔
112
        LogDebug() << "COMMAND_LONG " << (int)(command.command) << " to send to "
×
113
                   << (int)(command.target_system_id) << ", " << (int)(command.target_component_id);
×
114
    }
115

116
    CommandIdentification identification = identification_from_command(command);
40✔
117

118
    for (const auto& work : _work_queue) {
47✔
119
        if (work->identification == identification && callback == nullptr) {
7✔
120
            if (_command_debugging) {
×
121
                LogDebug() << "Dropping command " << static_cast<int>(identification.command)
×
122
                           << " that is already being sent";
×
123
            }
124
            return;
×
125
        }
126
    }
127

128
    auto new_work = std::make_shared<Work>();
80✔
129
    new_work->timeout_s = _system_impl.timeout_s();
40✔
130
    new_work->command = command;
40✔
131
    new_work->identification = identification;
40✔
132
    new_work->callback = callback;
40✔
133
    new_work->time_started = _system_impl.get_time().steady_time();
40✔
134
    _work_queue.push_back(new_work);
40✔
135
}
136

137
void MavlinkCommandSender::receive_command_ack(mavlink_message_t message)
39✔
138
{
139
    mavlink_command_ack_t command_ack;
39✔
140
    mavlink_msg_command_ack_decode(&message, &command_ack);
39✔
141

142
    if ((command_ack.target_system &&
39✔
143
         command_ack.target_system != _system_impl.get_own_system_id()) ||
78✔
144
        (command_ack.target_component &&
78✔
145
         command_ack.target_component != _system_impl.get_own_component_id())) {
39✔
146
        if (_command_debugging) {
×
147
            LogDebug() << "Ignoring command ack for command "
×
148
                       << static_cast<int>(command_ack.command) << " from "
×
149
                       << static_cast<int>(message.sysid) << '/' << static_cast<int>(message.compid)
×
150
                       << " to " << static_cast<int>(command_ack.target_system) << '/'
×
151
                       << static_cast<int>(command_ack.target_component);
×
152
        }
153
        return;
×
154
    }
155

156
    LockedQueue<Work>::Guard work_queue_guard(_work_queue);
39✔
157

158
    for (auto it = _work_queue.begin(); it != _work_queue.end(); ++it) {
43✔
159
        auto work = *it;
43✔
160

161
        if (!work) {
43✔
162
            LogErr() << "No work available! (should not happen #1)";
×
163
            return;
×
164
        }
165

166
        if (work->identification.command != command_ack.command ||
43✔
167
            (work->identification.target_system_id != 0 &&
39✔
168
             work->identification.target_system_id != message.sysid) ||
121✔
169
            (work->identification.target_component_id != 0 &&
39✔
170
             work->identification.target_component_id != message.compid)) {
39✔
171
            if (_command_debugging) {
4✔
172
                LogDebug() << "Command ack for " << command_ack.command
×
173
                           << " (from: " << std::to_string(message.sysid) << "/"
×
174
                           << std::to_string(message.compid) << ")"
×
175
                           << " does not match command " << work->identification.command
×
176
                           << " (to: " << std::to_string(work->identification.target_system_id)
×
177
                           << "/" << std::to_string(work->identification.target_component_id) << ")"
×
178
                           << " after "
×
179
                           << _system_impl.get_time().elapsed_since_s(work->time_started) << " s";
×
180
            }
181
            continue;
4✔
182
        }
183

184
        if (_command_debugging) {
39✔
185
            LogDebug() << "Received command ack for " << command_ack.command << " with result "
×
186
                       << static_cast<int>(command_ack.result) << " after "
×
187
                       << _system_impl.get_time().elapsed_since_s(work->time_started) << " s";
×
188
        }
189

190
        CommandResultCallback temp_callback = work->callback;
78✔
191
        std::pair<Result, float> temp_result{Result::UnknownError, NAN};
39✔
192

193
        switch (command_ack.result) {
39✔
194
            case MAV_RESULT_ACCEPTED:
36✔
195
                _system_impl.unregister_timeout_handler(work->timeout_cookie);
36✔
196
                temp_result = {Result::Success, 1.0f};
36✔
197
                _work_queue.erase(it);
36✔
198
                break;
36✔
199

200
            case MAV_RESULT_DENIED:
1✔
201
                if (_command_debugging) {
1✔
202
                    LogDebug() << "command denied (" << work->identification.command << ").";
×
203
                    if (work->identification.command == 512) {
×
204
                        LogDebug() << "(message " << work->identification.maybe_param1 << ")";
×
205
                    }
206
                }
207
                _system_impl.unregister_timeout_handler(work->timeout_cookie);
1✔
208
                temp_result = {Result::Denied, NAN};
1✔
209
                _work_queue.erase(it);
1✔
210
                break;
1✔
211

212
            case MAV_RESULT_UNSUPPORTED:
×
213
                if (_command_debugging) {
×
214
                    LogDebug() << "command unsupported (" << work->identification.command << ").";
×
215
                }
216
                _system_impl.unregister_timeout_handler(work->timeout_cookie);
×
217
                temp_result = {Result::Unsupported, NAN};
×
218
                _work_queue.erase(it);
×
219
                break;
×
220

221
            case MAV_RESULT_TEMPORARILY_REJECTED:
2✔
222
                if (_command_debugging) {
2✔
223
                    LogDebug() << "command temporarily rejected (" << work->identification.command
×
224
                               << ").";
×
225
                }
226
                _system_impl.unregister_timeout_handler(work->timeout_cookie);
2✔
227
                temp_result = {Result::TemporarilyRejected, NAN};
2✔
228
                _work_queue.erase(it);
2✔
229
                break;
2✔
230

231
            case MAV_RESULT_FAILED:
×
232
                if (_command_debugging) {
×
233
                    LogDebug() << "command failed (" << work->identification.command << ").";
×
234
                }
235
                _system_impl.unregister_timeout_handler(work->timeout_cookie);
×
236
                temp_result = {Result::Failed, NAN};
×
237
                _work_queue.erase(it);
×
238
                break;
×
239

240
            case MAV_RESULT_IN_PROGRESS:
×
241
                if (_command_debugging) {
×
242
                    if (static_cast<int>(command_ack.progress) != 255) {
×
243
                        LogDebug() << "progress: " << static_cast<int>(command_ack.progress)
×
244
                                   << " % (" << work->identification.command << ").";
×
245
                    }
246
                }
247
                // If we get a progress update, we can raise the timeout
248
                // to something higher because we know the initial command
249
                // has arrived.
250
                _system_impl.unregister_timeout_handler(work->timeout_cookie);
×
251
                _system_impl.register_timeout_handler(
×
252
                    [this, identification = work->identification] {
×
253
                        receive_timeout(identification);
×
254
                    },
×
255
                    3.0,
256
                    &work->timeout_cookie);
×
257

258
                temp_result = {
×
259
                    Result::InProgress, static_cast<float>(command_ack.progress) / 100.0f};
×
260
                break;
×
261

262
            case MAV_RESULT_CANCELLED:
×
263
                if (_command_debugging) {
×
264
                    LogDebug() << "command cancelled (" << work->identification.command << ").";
×
265
                }
266
                _system_impl.unregister_timeout_handler(work->timeout_cookie);
×
267
                temp_result = {Result::Cancelled, NAN};
×
268
                _work_queue.erase(it);
×
269
                break;
×
270

271
            default:
×
272
                LogWarn() << "Received unknown ack.";
×
273
                break;
×
274
        }
275

276
        if (temp_callback != nullptr) {
39✔
277
            call_callback(temp_callback, temp_result.first, temp_result.second);
38✔
278
        }
279

280
        return;
39✔
281
    }
282

283
    if (_command_debugging) {
×
284
        LogDebug() << "Received ack from " << static_cast<int>(message.sysid) << '/'
×
285
                   << static_cast<int>(message.compid)
×
286
                   << " for not-existing command: " << static_cast<int>(command_ack.command)
×
287
                   << "! Ignoring...";
×
288
    } else {
289
        LogWarn() << "Received ack for not-existing command: "
×
290
                  << static_cast<int>(command_ack.command) << "! Ignoring...";
×
291
    }
292
}
293

294
void MavlinkCommandSender::receive_timeout(const CommandIdentification& identification)
4✔
295
{
296
    if (_command_debugging) {
4✔
NEW
297
        LogDebug() << "Got timeout!";
×
298
    }
299
    bool found_command = false;
4✔
300
    CommandResultCallback temp_callback = nullptr;
4✔
301
    std::pair<Result, float> temp_result{Result::UnknownError, NAN};
4✔
302

303
    LockedQueue<Work>::Guard work_queue_guard(_work_queue);
4✔
304

305
    for (auto it = _work_queue.begin(); it != _work_queue.end(); ++it) {
8✔
306
        auto work = *it;
4✔
307

308
        if (!work) {
4✔
309
            LogErr() << "No work available! (should not happen #2)";
×
310
            return;
×
311
        }
312

313
        if (work->identification != identification) {
4✔
314
            continue;
×
315
        }
316

317
        found_command = true;
4✔
318

319
        if (work->retries_to_do > 0) {
4✔
320
            // We're not sure the command arrived, let's retransmit.
321
            LogWarn() << "sending again after "
8✔
322
                      << _system_impl.get_time().elapsed_since_s(work->time_started)
8✔
323
                      << " s, retries to do: " << work->retries_to_do << "  ("
4✔
324
                      << work->identification.command << ").";
12✔
325

326
            if (work->identification.command == MAV_CMD_REQUEST_MESSAGE) {
4✔
327
                LogWarn() << "Request was for msg ID: " << work->identification.maybe_param1;
×
328
            }
329

330
            if (!send_mavlink_message(work->command)) {
4✔
331
                LogErr() << "connection send error in retransmit (" << work->identification.command
×
332
                         << ").";
×
333
                temp_callback = work->callback;
×
334
                temp_result = {Result::ConnectionError, NAN};
×
335
                _work_queue.erase(it);
×
336
                break;
×
337
            } else {
338
                --work->retries_to_do;
4✔
339
                _system_impl.register_timeout_handler(
8✔
340
                    [this, identification = work->identification] {
4✔
341
                        receive_timeout(identification);
×
342
                    },
×
343
                    work->timeout_s,
4✔
344
                    &work->timeout_cookie);
4✔
345
            }
346
        } else {
347
            // We have tried retransmitting, giving up now.
348
            LogErr() << "Retrying failed (" << work->identification.command << ")";
×
349

350
            temp_callback = work->callback;
×
351
            temp_result = {Result::Timeout, NAN};
×
352
            _work_queue.erase(it);
×
353
            break;
×
354
        }
355
    }
356

357
    if (temp_callback != nullptr) {
4✔
358
        call_callback(temp_callback, temp_result.first, temp_result.second);
×
359
    }
360

361
    if (!found_command) {
4✔
362
        LogWarn() << "Timeout for not-existing command: "
×
363
                  << static_cast<int>(identification.command) << "! Ignoring...";
×
364
    }
365
}
366

367
void MavlinkCommandSender::do_work()
3,084✔
368
{
369
    LockedQueue<Work>::Guard work_queue_guard(_work_queue);
6,168✔
370

371
    for (const auto& work : _work_queue) {
3,178✔
372
        if (work->already_sent) {
94✔
373
            continue;
54✔
374
        }
375

376
        bool already_being_sent = false;
40✔
377
        for (const auto& other_work : _work_queue) {
91✔
378
            // Ignore itself:
379
            if (other_work == work) {
51✔
380
                continue;
40✔
381
            }
382

383
            // Check if command with same command ID is already being sent.
384
            if (other_work->already_sent &&
18✔
385
                other_work->identification.command == work->identification.command) {
7✔
386
                if (_command_debugging) {
×
387
                    LogDebug() << "Command " << static_cast<int>(work->identification.command)
×
388
                               << " is already being sent, waiting...";
×
389
                }
390
                already_being_sent = true;
×
391
                break;
×
392
            }
393
        }
394

395
        if (already_being_sent) {
40✔
396
            continue;
×
397
        }
398

399
        // LogDebug() << "sending it the first time (" << work->mavlink_command << ")";
400
        work->time_started = _system_impl.get_time().steady_time();
40✔
401

402
        {
403
            if (!send_mavlink_message(work->command)) {
40✔
404
                LogErr() << "connection send error (" << work->identification.command << ")";
×
405
                // In this case we try again after the timeout. Chances are slim it will work next
406
                // time though.
407
            } else {
408
                if (_command_debugging) {
40✔
409
                    LogDebug() << "Sent command " << static_cast<int>(work->identification.command);
×
410
                }
411
            }
412
        }
413

414
        work->already_sent = true;
40✔
415

416
        _system_impl.register_timeout_handler(
80✔
417
            [this, identification = work->identification] { receive_timeout(identification); },
44✔
418
            work->timeout_s,
40✔
419
            &work->timeout_cookie);
40✔
420
    }
421
}
3,084✔
422

423
void MavlinkCommandSender::call_callback(
38✔
424
    const CommandResultCallback& callback, Result result, float progress)
425
{
426
    if (!callback) {
38✔
427
        return;
×
428
    }
429

430
    // It seems that we need to queue the callback on the thread pool otherwise
431
    // we lock ourselves out when we send a command in the callback receiving a command result.
432
    auto temp_callback = callback;
76✔
433
    _system_impl.call_user_callback(
76✔
434
        [temp_callback, result, progress]() { temp_callback(result, progress); });
435
}
436

437
bool MavlinkCommandSender::send_mavlink_message(const Command& command)
44✔
438
{
439
    if (auto command_int = std::get_if<CommandInt>(&command)) {
44✔
440
        return _system_impl.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
441
            mavlink_message_t message;
442
            mavlink_msg_command_int_pack_chan(
×
443
                mavlink_address.system_id,
×
444
                mavlink_address.component_id,
×
445
                channel,
446
                &message,
447
                command_int->target_system_id,
×
448
                command_int->target_component_id,
×
449
                command_int->frame,
×
450
                command_int->command,
×
451
                command_int->current,
×
452
                command_int->autocontinue,
×
453
                maybe_reserved(command_int->params.maybe_param1),
×
454
                maybe_reserved(command_int->params.maybe_param2),
×
455
                maybe_reserved(command_int->params.maybe_param3),
×
456
                maybe_reserved(command_int->params.maybe_param4),
×
457
                command_int->params.x,
×
458
                command_int->params.y,
×
459
                maybe_reserved(command_int->params.maybe_z));
×
460
            return message;
×
461
        });
×
462

463
    } else if (auto command_long = std::get_if<CommandLong>(&command)) {
44✔
464
        return _system_impl.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
88✔
465
            mavlink_message_t message;
466
            mavlink_msg_command_long_pack_chan(
352✔
467
                mavlink_address.system_id,
44✔
468
                mavlink_address.component_id,
44✔
469
                channel,
470
                &message,
471
                command_long->target_system_id,
352✔
472
                command_long->target_component_id,
44✔
473
                command_long->command,
44✔
474
                command_long->confirmation,
44✔
475
                maybe_reserved(command_long->params.maybe_param1),
44✔
476
                maybe_reserved(command_long->params.maybe_param2),
44✔
477
                maybe_reserved(command_long->params.maybe_param3),
44✔
478
                maybe_reserved(command_long->params.maybe_param4),
44✔
479
                maybe_reserved(command_long->params.maybe_param5),
44✔
480
                maybe_reserved(command_long->params.maybe_param6),
44✔
481
                maybe_reserved(command_long->params.maybe_param7));
44✔
482
            return message;
44✔
483
        });
44✔
484
    } else {
485
        return false;
×
486
    }
487
}
488

489
float MavlinkCommandSender::maybe_reserved(const std::optional<float>& maybe_param) const
308✔
490
{
491
    if (maybe_param) {
308✔
492
        return maybe_param.value();
45✔
493

494
    } else {
495
        if (_system_impl.autopilot() == Autopilot::ArduPilot) {
263✔
496
            return 0.0f;
×
497
        } else {
498
            return NAN;
263✔
499
        }
500
    }
501
}
502

503
} // namespace mavsdk
STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2025 Coveralls, Inc