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

mavlink / MAVSDK / 6752913415

04 Nov 2023 05:06AM UTC coverage: 36.901% (-0.05%) from 36.952%
6752913415

push

github

web-flow
Merge pull request #2160 from mavlink/pr-split-mission-transfer

Split mission transfer into client and server

488 of 683 new or added lines in 14 files covered. (71.45%)

24 existing lines in 7 files now uncovered.

9925 of 26896 relevant lines covered (36.9%)

118.33 hits per line

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

43.48
/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)
68✔
12
{
13
    if (const char* env_p = std::getenv("MAVSDK_COMMAND_DEBUGGING")) {
68✔
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(
68✔
21
        MAVLINK_MSG_ID_COMMAND_ACK,
22
        [this](const mavlink_message_t& message) { receive_command_ack(message); },
36✔
23
        this);
24
}
68✔
25

26
MavlinkCommandSender::~MavlinkCommandSender()
68✔
27
{
28
    _system_impl.unregister_all_mavlink_message_handlers(this);
68✔
29
}
68✔
30

31
MavlinkCommandSender::Result
32
MavlinkCommandSender::send_command(const MavlinkCommandSender::CommandInt& command)
×
33
{
34
    // We wrap the async call with a promise and future.
35
    auto prom = std::make_shared<std::promise<Result>>();
×
36
    auto res = prom->get_future();
×
37

38
    queue_command_async(command, [prom](Result result, float progress) {
×
39
        UNUSED(progress);
×
40
        // We can only fulfill the promise once in C++11.
41
        // Therefore, we have to ignore the IN_PROGRESS state and wait
42
        // for the final result.
43
        if (result != Result::InProgress) {
×
44
            prom->set_value(result);
×
45
        }
46
    });
×
47

48
    // Block now to wait for result.
49
    return res.get();
×
50
}
51

52
MavlinkCommandSender::Result
53
MavlinkCommandSender::send_command(const MavlinkCommandSender::CommandLong& command)
×
54
{
55
    // We wrap the async call with a promise and future.
56
    auto prom = std::make_shared<std::promise<Result>>();
×
57
    auto res = prom->get_future();
×
58

59
    queue_command_async(command, [prom](Result result, float progress) {
×
60
        UNUSED(progress);
×
61
        // We can only fulfill the promise once in C++11.
62
        // Therefore, we have to ignore the IN_PROGRESS state and wait
63
        // for the final result.
64
        if (result != Result::InProgress) {
×
65
            prom->set_value(result);
×
66
        }
67
    });
×
68

69
    return res.get();
×
70
}
71

72
void MavlinkCommandSender::queue_command_async(
×
73
    const CommandInt& command, const CommandResultCallback& callback)
74
{
75
    if (_command_debugging) {
×
76
        LogDebug() << "COMMAND_INT " << (int)(command.command) << " to send to "
×
77
                   << (int)(command.target_system_id) << ", " << (int)(command.target_component_id);
×
78
    }
79

80
    CommandIdentification identification = identification_from_command(command);
×
81

82
    for (const auto& work : _work_queue) {
×
83
        if (work->identification == identification && callback == nullptr) {
×
84
            if (_command_debugging) {
×
85
                LogDebug() << "Dropping command " << static_cast<int>(identification.command)
×
86
                           << " that is already being sent";
×
87
            }
88
            return;
×
89
        }
90
    }
91

92
    auto new_work = std::make_shared<Work>();
×
93
    new_work->timeout_s = _system_impl.timeout_s();
×
94
    new_work->command = command;
×
95
    new_work->identification = identification;
×
96
    new_work->callback = callback;
×
97
    _work_queue.push_back(new_work);
×
98
}
99

100
void MavlinkCommandSender::queue_command_async(
38✔
101
    const CommandLong& command, const CommandResultCallback& callback)
102
{
103
    if (_command_debugging) {
38✔
104
        LogDebug() << "COMMAND_LONG " << (int)(command.command) << " to send to "
×
105
                   << (int)(command.target_system_id) << ", " << (int)(command.target_component_id);
×
106
    }
107

108
    CommandIdentification identification = identification_from_command(command);
38✔
109

110
    for (const auto& work : _work_queue) {
44✔
111
        if (work->identification == identification && callback == nullptr) {
6✔
112
            if (_command_debugging) {
×
113
                LogDebug() << "Dropping command " << static_cast<int>(identification.command)
×
114
                           << " that is already being sent";
×
115
            }
116
            return;
×
117
        }
118
    }
119

120
    auto new_work = std::make_shared<Work>();
76✔
121
    new_work->timeout_s = _system_impl.timeout_s();
38✔
122
    new_work->command = command;
38✔
123
    new_work->identification = identification;
38✔
124
    new_work->callback = callback;
38✔
125
    new_work->time_started = _system_impl.get_time().steady_time();
38✔
126
    _work_queue.push_back(new_work);
38✔
127
}
128

129
void MavlinkCommandSender::receive_command_ack(mavlink_message_t message)
36✔
130
{
131
    mavlink_command_ack_t command_ack;
36✔
132
    mavlink_msg_command_ack_decode(&message, &command_ack);
36✔
133

134
    if ((command_ack.target_system &&
36✔
135
         command_ack.target_system != _system_impl.get_own_system_id()) ||
72✔
136
        (command_ack.target_component &&
72✔
137
         command_ack.target_component != _system_impl.get_own_component_id())) {
36✔
138
        if (_command_debugging) {
×
139
            LogDebug() << "Ignoring command ack for command "
×
140
                       << static_cast<int>(command_ack.command) << " from "
×
141
                       << static_cast<int>(message.sysid) << '/' << static_cast<int>(message.compid)
×
142
                       << " to " << static_cast<int>(command_ack.target_system) << '/'
×
143
                       << static_cast<int>(command_ack.target_component);
×
144
        }
145
        return;
×
146
    }
147

148
    LockedQueue<Work>::Guard work_queue_guard(_work_queue);
36✔
149

150
    for (auto it = _work_queue.begin(); it != _work_queue.end(); ++it) {
40✔
151
        auto work = *it;
40✔
152

153
        if (!work) {
40✔
154
            LogErr() << "No work available! (should not happen #1)";
×
155
            return;
×
156
        }
157

158
        if (work->identification.command != command_ack.command ||
40✔
159
            (work->identification.target_system_id != 0 &&
36✔
160
             work->identification.target_system_id != message.sysid) ||
112✔
161
            (work->identification.target_component_id != 0 &&
36✔
162
             work->identification.target_component_id != message.compid)) {
36✔
163
            if (_command_debugging) {
4✔
164
                LogDebug() << "Command ack for " << command_ack.command
×
165
                           << " (from: " << std::to_string(message.sysid) << "/"
×
166
                           << std::to_string(message.compid) << ")"
×
167
                           << " does not match command " << work->identification.command
×
168
                           << " (to: " << std::to_string(work->identification.target_system_id)
×
169
                           << "/" << std::to_string(work->identification.target_component_id) << ")"
×
170
                           << " after "
×
171
                           << _system_impl.get_time().elapsed_since_s(work->time_started) << " s";
×
172
            }
173
            continue;
4✔
174
        }
175

176
        if (_command_debugging) {
36✔
177
            LogDebug() << "Received command ack for " << command_ack.command << " with result "
×
178
                       << static_cast<int>(command_ack.result) << " after "
×
179
                       << _system_impl.get_time().elapsed_since_s(work->time_started) << " s";
×
180
        }
181

182
        CommandResultCallback temp_callback = work->callback;
72✔
183
        std::pair<Result, float> temp_result{Result::UnknownError, NAN};
36✔
184

185
        switch (command_ack.result) {
36✔
186
            case MAV_RESULT_ACCEPTED:
34✔
187
                _system_impl.unregister_timeout_handler(work->timeout_cookie);
34✔
188
                temp_result = {Result::Success, 1.0f};
34✔
189
                _work_queue.erase(it);
34✔
190
                break;
34✔
191

192
            case MAV_RESULT_DENIED:
×
193
                if (_command_debugging) {
×
194
                    LogDebug() << "command denied (" << work->identification.command << ").";
×
195
                }
196
                _system_impl.unregister_timeout_handler(work->timeout_cookie);
×
197
                temp_result = {Result::Denied, NAN};
×
198
                _work_queue.erase(it);
×
199
                break;
×
200

201
            case MAV_RESULT_UNSUPPORTED:
×
202
                if (_command_debugging) {
×
203
                    LogDebug() << "command unsupported (" << work->identification.command << ").";
×
204
                }
205
                _system_impl.unregister_timeout_handler(work->timeout_cookie);
×
206
                temp_result = {Result::Unsupported, NAN};
×
207
                _work_queue.erase(it);
×
208
                break;
×
209

210
            case MAV_RESULT_TEMPORARILY_REJECTED:
2✔
211
                if (_command_debugging) {
2✔
212
                    LogDebug() << "command temporarily rejected (" << work->identification.command
×
213
                               << ").";
×
214
                }
215
                _system_impl.unregister_timeout_handler(work->timeout_cookie);
2✔
216
                temp_result = {Result::TemporarilyRejected, NAN};
2✔
217
                _work_queue.erase(it);
2✔
218
                break;
2✔
219

220
            case MAV_RESULT_FAILED:
×
221
                if (_command_debugging) {
×
222
                    LogDebug() << "command failed (" << work->identification.command << ").";
×
223
                }
224
                _system_impl.unregister_timeout_handler(work->timeout_cookie);
×
225
                temp_result = {Result::Failed, NAN};
×
226
                _work_queue.erase(it);
×
227
                break;
×
228

229
            case MAV_RESULT_IN_PROGRESS:
×
230
                if (_command_debugging) {
×
231
                    if (static_cast<int>(command_ack.progress) != 255) {
×
232
                        LogDebug() << "progress: " << static_cast<int>(command_ack.progress)
×
233
                                   << " % (" << work->identification.command << ").";
×
234
                    }
235
                }
236
                // If we get a progress update, we can raise the timeout
237
                // to something higher because we know the initial command
238
                // has arrived. A possible timeout for this case is the initial
239
                // timeout * the possible retries because this should match the
240
                // case where there is no progress update, and we keep trying.
241
                _system_impl.unregister_timeout_handler(work->timeout_cookie);
×
242
                _system_impl.register_timeout_handler(
×
243
                    [this, identification = work->identification] {
×
244
                        receive_timeout(identification);
×
245
                    },
×
246
                    work->retries_to_do * work->timeout_s,
×
247
                    &work->timeout_cookie);
×
248

249
                temp_result = {
×
250
                    Result::InProgress, static_cast<float>(command_ack.progress) / 100.0f};
×
251
                break;
×
252

253
            case MAV_RESULT_CANCELLED:
×
254
                if (_command_debugging) {
×
255
                    LogDebug() << "command cancelled (" << work->identification.command << ").";
×
256
                }
257
                _system_impl.unregister_timeout_handler(work->timeout_cookie);
×
258
                temp_result = {Result::Cancelled, NAN};
×
259
                _work_queue.erase(it);
×
260
                break;
×
261

262
            default:
×
263
                LogWarn() << "Received unknown ack.";
×
264
                break;
×
265
        }
266

267
        if (temp_callback != nullptr) {
36✔
268
            call_callback(temp_callback, temp_result.first, temp_result.second);
4✔
269
        }
270

271
        return;
36✔
272
    }
273

274
    if (_command_debugging) {
×
275
        LogDebug() << "Received ack from " << static_cast<int>(message.sysid) << '/'
×
276
                   << static_cast<int>(message.compid)
×
277
                   << " for not-existing command: " << static_cast<int>(command_ack.command)
×
278
                   << "! Ignoring...";
×
279
    } else {
280
        LogWarn() << "Received ack for not-existing command: "
×
281
                  << static_cast<int>(command_ack.command) << "! Ignoring...";
×
282
    }
283
}
284

285
void MavlinkCommandSender::receive_timeout(const CommandIdentification& identification)
2✔
286
{
287
    bool found_command = false;
2✔
288
    CommandResultCallback temp_callback = nullptr;
2✔
289
    std::pair<Result, float> temp_result{Result::UnknownError, NAN};
2✔
290

291
    LockedQueue<Work>::Guard work_queue_guard(_work_queue);
2✔
292

293
    for (auto it = _work_queue.begin(); it != _work_queue.end(); ++it) {
4✔
294
        auto work = *it;
2✔
295

296
        if (!work) {
2✔
297
            LogErr() << "No work available! (should not happen #2)";
×
298
            return;
×
299
        }
300

301
        if (work->identification != identification) {
2✔
302
            continue;
×
303
        }
304

305
        found_command = true;
2✔
306

307
        if (work->retries_to_do > 0) {
2✔
308
            // We're not sure the command arrived, let's retransmit.
309
            LogWarn() << "sending again after "
4✔
310
                      << _system_impl.get_time().elapsed_since_s(work->time_started)
4✔
311
                      << " s, retries to do: " << work->retries_to_do << "  ("
2✔
312
                      << work->identification.command << ").";
6✔
313

314
            if (work->identification.command == MAV_CMD_REQUEST_MESSAGE) {
2✔
315
                LogWarn() << "Request was for msg ID: " << work->identification.maybe_param1;
×
316
            }
317

318
            if (!send_mavlink_message(work->command)) {
2✔
319
                LogErr() << "connection send error in retransmit (" << work->identification.command
×
320
                         << ").";
×
321
                temp_callback = work->callback;
×
322
                temp_result = {Result::ConnectionError, NAN};
×
323
                _work_queue.erase(it);
×
324
                break;
×
325
            } else {
326
                --work->retries_to_do;
2✔
327
                _system_impl.register_timeout_handler(
4✔
328
                    [this, identification = work->identification] {
2✔
UNCOV
329
                        receive_timeout(identification);
×
UNCOV
330
                    },
×
331
                    work->timeout_s,
2✔
332
                    &work->timeout_cookie);
2✔
333
            }
334
        } else {
335
            // We have tried retransmitting, giving up now.
336
            LogErr() << "Retrying failed (" << work->identification.command << ")";
×
337

338
            temp_callback = work->callback;
×
339
            temp_result = {Result::Timeout, NAN};
×
340
            _work_queue.erase(it);
×
341
            break;
×
342
        }
343
    }
344

345
    if (temp_callback != nullptr) {
2✔
346
        call_callback(temp_callback, temp_result.first, temp_result.second);
×
347
    }
348

349
    if (!found_command) {
2✔
350
        LogWarn() << "Timeout for not-existing command: "
×
351
                  << static_cast<int>(identification.command) << "! Ignoring...";
×
352
    }
353
}
354

355
void MavlinkCommandSender::do_work()
3,112✔
356
{
357
    LockedQueue<Work>::Guard work_queue_guard(_work_queue);
6,224✔
358

359
    for (const auto& work : _work_queue) {
3,174✔
360
        if (work->already_sent) {
62✔
361
            continue;
24✔
362
        }
363

364
        bool already_being_sent = false;
38✔
365
        for (const auto& other_work : _work_queue) {
85✔
366
            // Ignore itself:
367
            if (other_work == work) {
47✔
368
                continue;
38✔
369
            }
370

371
            // Check if command with same command ID is already being sent.
372
            if (other_work->already_sent &&
15✔
373
                other_work->identification.command == work->identification.command) {
6✔
374
                if (_command_debugging) {
×
375
                    LogDebug() << "Command " << static_cast<int>(work->identification.command)
×
376
                               << " is already being sent, waiting...";
×
377
                }
378
                already_being_sent = true;
×
379
                break;
×
380
            }
381
        }
382

383
        if (already_being_sent) {
38✔
384
            continue;
×
385
        }
386

387
        // LogDebug() << "sending it the first time (" << work->mavlink_command << ")";
388
        work->time_started = _system_impl.get_time().steady_time();
38✔
389

390
        {
391
            if (!send_mavlink_message(work->command)) {
38✔
392
                LogErr() << "connection send error (" << work->identification.command << ")";
×
393
                // In this case we try again after the timeout. Chances are slim it will work next
394
                // time though.
395
            } else {
396
                if (_command_debugging) {
38✔
397
                    LogDebug() << "Sent command " << static_cast<int>(work->identification.command);
×
398
                }
399
            }
400
        }
401

402
        work->already_sent = true;
38✔
403

404
        _system_impl.register_timeout_handler(
76✔
405
            [this, identification = work->identification] { receive_timeout(identification); },
40✔
406
            work->timeout_s,
38✔
407
            &work->timeout_cookie);
38✔
408
    }
409
}
3,112✔
410

411
void MavlinkCommandSender::call_callback(
4✔
412
    const CommandResultCallback& callback, Result result, float progress)
413
{
414
    if (!callback) {
4✔
415
        return;
×
416
    }
417

418
    // It seems that we need to queue the callback on the thread pool otherwise
419
    // we lock ourselves out when we send a command in the callback receiving a command result.
420
    auto temp_callback = callback;
8✔
421
    _system_impl.call_user_callback(
8✔
422
        [temp_callback, result, progress]() { temp_callback(result, progress); });
423
}
424

425
bool MavlinkCommandSender::send_mavlink_message(const Command& command)
40✔
426
{
427
    if (auto command_int = std::get_if<CommandInt>(&command)) {
40✔
428
        return _system_impl.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
429
            mavlink_message_t message;
430
            mavlink_msg_command_int_pack_chan(
×
431
                mavlink_address.system_id,
×
432
                mavlink_address.component_id,
×
433
                channel,
434
                &message,
435
                command_int->target_system_id,
×
436
                command_int->target_component_id,
×
437
                command_int->frame,
×
438
                command_int->command,
×
439
                command_int->current,
×
440
                command_int->autocontinue,
×
441
                maybe_reserved(command_int->params.maybe_param1),
×
442
                maybe_reserved(command_int->params.maybe_param2),
×
443
                maybe_reserved(command_int->params.maybe_param3),
×
444
                maybe_reserved(command_int->params.maybe_param4),
×
445
                command_int->params.x,
×
446
                command_int->params.y,
×
447
                maybe_reserved(command_int->params.maybe_z));
×
448
            return message;
×
449
        });
×
450

451
    } else if (auto command_long = std::get_if<CommandLong>(&command)) {
40✔
452
        return _system_impl.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
80✔
453
            mavlink_message_t message;
454
            mavlink_msg_command_long_pack_chan(
320✔
455
                mavlink_address.system_id,
40✔
456
                mavlink_address.component_id,
40✔
457
                channel,
458
                &message,
459
                command_long->target_system_id,
320✔
460
                command_long->target_component_id,
40✔
461
                command_long->command,
40✔
462
                command_long->confirmation,
40✔
463
                maybe_reserved(command_long->params.maybe_param1),
40✔
464
                maybe_reserved(command_long->params.maybe_param2),
40✔
465
                maybe_reserved(command_long->params.maybe_param3),
40✔
466
                maybe_reserved(command_long->params.maybe_param4),
40✔
467
                maybe_reserved(command_long->params.maybe_param5),
40✔
468
                maybe_reserved(command_long->params.maybe_param6),
40✔
469
                maybe_reserved(command_long->params.maybe_param7));
40✔
470
            return message;
40✔
471
        });
40✔
472
    } else {
473
        return false;
×
474
    }
475
}
476

477
float MavlinkCommandSender::maybe_reserved(const std::optional<float>& maybe_param) const
280✔
478
{
479
    if (maybe_param) {
280✔
480
        return maybe_param.value();
41✔
481

482
    } else {
483
        if (_system_impl.autopilot() == Autopilot::ArduPilot) {
239✔
484
            return 0.0f;
×
485
        } else {
486
            return NAN;
239✔
487
        }
488
    }
489
}
490

491
} // 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

© 2026 Coveralls, Inc