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

mavlink / MAVSDK / 4899817366

pending completion
4899817366

Pull #1772

github

GitHub
Merge c0bb90862 into e4e9c71dd
Pull Request #1772: Refactor MAVLinkParameters into client and server classes

2192 of 2192 new or added lines in 34 files covered. (100.0%)

7708 of 24812 relevant lines covered (31.07%)

19.96 hits per line

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

56.12
/src/mavsdk/core/mavlink_parameter_sender.cpp
1
#include "mavlink_parameter_helper.h"
2
#include "mavlink_parameter_sender.h"
3
#include "mavlink_message_handler.h"
4
#include "timeout_handler.h"
5
#include "system_impl.h"
6
#include "plugin_base.h"
7
#include <algorithm>
8
#include <future>
9
#include <utility>
10

11
namespace mavsdk {
12

13
MavlinkParameterSender::MavlinkParameterSender(
8✔
14
    Sender& sender,
15
    MavlinkMessageHandler& message_handler,
16
    TimeoutHandler& timeout_handler,
17
    TimeoutSCallback timeout_s_callback,
18
    const uint8_t target_component_id,
19
    bool use_extended) :
8✔
20
    _sender(sender),
21
    _message_handler(message_handler),
22
    _timeout_handler(timeout_handler),
23
    _timeout_s_callback(std::move(timeout_s_callback)),
8✔
24
    _target_component_id(target_component_id),
25
    _use_extended(use_extended)
8✔
26
{
27
    if (const char* env_p = std::getenv("MAVSDK_PARAMETER_DEBUGGING")) {
8✔
28
        if (std::string(env_p) == "1") {
×
29
            LogDebug() << "Parameter debugging is on.";
×
30
            _parameter_debugging = true;
×
31
        }
32
    }
33

34
    if (_parameter_debugging) {
8✔
35
        LogDebug() << "MavlinkParameterSender created for target compid: "
×
36
                   << (int)_target_component_id << " and "
×
37
                   << (_use_extended ? "extended" : "not extended");
×
38
    }
39

40
    if (_use_extended) {
8✔
41
        _message_handler.register_one(
4✔
42
            MAVLINK_MSG_ID_PARAM_EXT_VALUE,
43
            [this](const mavlink_message_t& message) { process_param_ext_value(message); },
28✔
44
            this);
45

46
        _message_handler.register_one(
4✔
47
            MAVLINK_MSG_ID_PARAM_EXT_ACK,
48
            [this](const mavlink_message_t& message) { process_param_ext_ack(message); },
2✔
49
            this);
50
    } else {
51
        _message_handler.register_one(
4✔
52
            MAVLINK_MSG_ID_PARAM_VALUE,
53
            [this](const mavlink_message_t& message) { process_param_value(message); },
26✔
54
            this);
55
    }
56
}
8✔
57

58
MavlinkParameterSender::~MavlinkParameterSender()
8✔
59
{
60
    if (_parameter_debugging) {
8✔
61
        LogDebug() << "MavlinkParameterSender destructed for target compid: "
×
62
                   << (int)_target_component_id << " and "
×
63
                   << (_use_extended ? "extended" : "not extended");
×
64
    }
65

66
    _message_handler.unregister_all(this);
8✔
67
}
8✔
68

69
MavlinkParameterSender::Result
70
MavlinkParameterSender::set_param(const std::string& name, const ParamValue& value)
×
71
{
72
    auto prom = std::promise<Result>();
×
73
    auto res = prom.get_future();
×
74
    set_param_async(
×
75
        name, value, [&prom](Result result) { prom.set_value(result); }, this);
×
76
    return res.get();
×
77
}
78

79
void MavlinkParameterSender::set_param_async(
6✔
80
    const std::string& name,
81
    const ParamValue& value,
82
    const SetParamCallback& callback,
83
    const void* cookie)
84
{
85
    if (name.size() > PARAM_ID_LEN) {
6✔
86
        LogErr() << "Param name too long";
×
87
        if (callback) {
×
88
            callback(Result::ParamNameTooLong);
×
89
        }
90
        return;
×
91
    }
92
    if (value.is<std::string>() && !_use_extended) {
6✔
93
        LogErr() << "String needs extended parameter protocol";
×
94
        if (callback) {
×
95
            callback(Result::StringTypeUnsupported);
×
96
        }
97
        return;
×
98
    }
99
    auto new_work = std::make_shared<WorkItem>(WorkItemSet{name, value, callback}, cookie);
18✔
100
    _work_queue.push_back(new_work);
6✔
101
}
102

103
void MavlinkParameterSender::set_param_int_async(
2✔
104
    const std::string& name, int32_t value, const SetParamCallback& callback, const void* cookie)
105
{
106
    if (name.size() > PARAM_ID_LEN) {
2✔
107
        LogErr() << "Param name too long";
×
108
        if (callback) {
×
109
            callback(Result::ParamNameTooLong);
×
110
        }
111
        return;
×
112
    }
113

114
    // PX4 only uses int32_t, so we can be sure and don't need to check the exact type first
115
    // by getting the param, or checking the cache.
116
    if (_sender.autopilot() == SystemImpl::Autopilot::Px4) {
2✔
117
        ParamValue value_to_set;
×
118
        value_to_set.set(static_cast<int32_t>(value));
×
119
        set_param_async(name, value_to_set, callback, cookie);
×
120
    } else {
121
        // We don't know which exact int type the server wants, so we have to get the param
122
        // first to see the type before setting it.
123
        auto param_opt = _param_cache.param_by_id(name, false);
2✔
124
        if (param_opt.has_value()) {
2✔
125
            // we have the parameter cached
126
            auto param = param_opt.value();
×
127
            if (param.value.set_int(value)) {
×
128
                // we have successfully written whatever int the user provided into the int type
129
                // that is actually stored
130
                set_param_async(name, param.value, callback, cookie);
×
131
            } else {
132
                // We didn't find compatibility and give up.
133
                LogErr() << "Wrong type for int in cache";
×
134
                if (callback) {
×
135
                    callback(Result::WrongType);
×
136
                }
137
                return;
×
138
            }
139
        } else {
140
            // parameter is not cached. Request it and then perform the appropriate action once we
141
            // know it
142
            auto send_message_once_type_is_known = [this, name, value, callback, cookie](
2✔
143
                                                       Result result,
144
                                                       ParamValue fetched_param_value) {
4✔
145
                if (result == Result::Success) {
2✔
146
                    if (fetched_param_value.set_int(value)) {
2✔
147
                        // Since the callback itself is called with the work queue locked, we have
148
                        // to make sure that the work queue guard is removed before we call the
149
                        // finalizing callback of a work item.
150
                        set_param_async(name, fetched_param_value, callback, cookie);
2✔
151
                    } else {
152
                        // The param type returned does is not compatible with an int, give up.
153
                        LogErr() << "Wrong type for int returned";
×
154
                        if (callback) {
×
155
                            callback(Result::WrongType);
×
156
                        }
157
                    }
158
                } else {
159
                    // Failed to get the param to get the type, pass on the error.
160
                    callback(result);
×
161
                }
162
            };
4✔
163
            get_param_async(name, send_message_once_type_is_known, cookie);
2✔
164
        }
165
    }
166
}
167

168
MavlinkParameterSender::Result
169
MavlinkParameterSender::set_param_int(const std::string& name, int32_t value)
2✔
170
{
171
    auto prom = std::promise<Result>();
4✔
172
    auto res = prom.get_future();
4✔
173
    set_param_int_async(
2✔
174
        name, value, [&prom](Result result) { prom.set_value(result); }, this);
2✔
175
    return res.get();
2✔
176
}
177

178
void MavlinkParameterSender::set_param_float_async(
2✔
179
    const std::string& name, float value, const SetParamCallback& callback, const void* cookie)
180
{
181
    ParamValue value_to_set;
4✔
182
    value_to_set.set_float(value);
2✔
183
    set_param_async(name, value_to_set, callback, cookie);
2✔
184
}
2✔
185

186
MavlinkParameterSender::Result
187
MavlinkParameterSender::set_param_float(const std::string& name, float value)
2✔
188
{
189
    auto prom = std::promise<Result>();
4✔
190
    auto res = prom.get_future();
4✔
191

192
    set_param_float_async(
2✔
193
        name, value, [&prom](Result result) { prom.set_value(result); }, this);
2✔
194

195
    return res.get();
2✔
196
}
197

198
void MavlinkParameterSender::set_param_custom_async(
2✔
199
    const std::string& name,
200
    const std::string& value,
201
    const SetParamCallback& callback,
202
    const void* cookie)
203
{
204
    if (name.size() > PARAM_ID_LEN) {
2✔
205
        LogErr() << "Param name too long";
×
206
        if (callback) {
×
207
            callback(Result::ParamNameTooLong);
×
208
        }
209
        return;
×
210
    }
211

212
    if (value.size() > sizeof(mavlink_param_ext_set_t::param_value)) {
2✔
213
        LogErr() << "Param value too long";
×
214
        if (callback) {
×
215
            callback(Result::ParamValueTooLong);
×
216
        }
217
        return;
×
218
    }
219
    ParamValue value_to_set;
4✔
220
    value_to_set.set_custom(value);
2✔
221
    set_param_async(name, value_to_set, callback, cookie);
2✔
222
}
223

224
MavlinkParameterSender::Result
225
MavlinkParameterSender::set_param_custom(const std::string& name, const std::string& value)
2✔
226
{
227
    auto prom = std::promise<Result>();
4✔
228
    auto res = prom.get_future();
4✔
229
    set_param_custom_async(
2✔
230
        name, value, [&prom](Result result) { prom.set_value(result); }, this);
2✔
231
    return res.get();
2✔
232
}
233

234
void MavlinkParameterSender::get_param_async(
16✔
235
    const std::string& name, const GetParamAnyCallback& callback, const void* cookie)
236
{
237
    if (_parameter_debugging) {
16✔
238
        LogDebug() << "Getting param " << name << ", extended: " << (_use_extended ? "yes" : "no");
×
239
    }
240
    if (name.size() > PARAM_ID_LEN) {
16✔
241
        LogErr() << "Param name too long";
×
242
        if (callback) {
×
243
            callback(Result::ParamNameTooLong, {});
×
244
        }
245
        return;
×
246
    }
247

248
    auto new_work = std::make_shared<WorkItem>(WorkItemGet{name, callback}, cookie);
48✔
249
    _work_queue.push_back(new_work);
16✔
250
}
251

252
void MavlinkParameterSender::get_param_async(
×
253
    const std::string& name,
254
    const ParamValue& value_type,
255
    const GetParamAnyCallback& callback,
256
    const void* cookie)
257
{
258
    // We need to delay the type checking until we get a response from the server.
259
    GetParamAnyCallback callback_future_result = [callback,
×
260
                                                  value_type](Result result, ParamValue value) {
261
        if (result == Result::Success) {
×
262
            if (value.is_same_type(value_type)) {
×
263
                callback(Result::Success, std::move(value));
×
264
            } else {
265
                callback(Result::WrongType, {});
×
266
            }
267
        } else {
268
            callback(result, {});
×
269
        }
270
    };
×
271
    get_param_async(name, callback_future_result, cookie);
×
272
}
×
273

274
template<class T>
275
void MavlinkParameterSender::get_param_async_typesafe(
5✔
276
    const std::string& name, const GetParamTypesafeCallback<T> callback, const void* cookie)
277
{
278
    // We need to delay the type checking until we get a response from the server.
279
    GetParamAnyCallback callback_future_result = [callback](Result result, ParamValue value) {
10✔
280
        if (result == Result::Success) {
14✔
281
            if (value.is<T>()) {
12✔
282
                callback(Result::Success, value.get<T>());
12✔
283
            } else {
284
                callback(Result::WrongType, {});
×
285
            }
286
        } else {
287
            callback(result, {});
2✔
288
        }
289
    };
290
    get_param_async(name, callback_future_result, cookie);
5✔
291
}
5✔
292

293
void MavlinkParameterSender::get_param_float_async(
5✔
294
    const std::string& name, const GetParamFloatCallback& callback, const void* cookie)
295
{
296
    get_param_async_typesafe<float>(name, callback, cookie);
5✔
297
}
5✔
298

299
void MavlinkParameterSender::get_param_int_async(
5✔
300
    const std::string& name, const GetParamIntCallback& callback, const void* cookie)
301
{
302
    get_param_async_typesafe<int32_t>(name, callback, cookie);
5✔
303
}
5✔
304

305
void MavlinkParameterSender::get_param_custom_async(
4✔
306
    const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
307
{
308
    get_param_async_typesafe<std::string>(name, callback, cookie);
4✔
309
}
4✔
310

311
std::pair<MavlinkParameterSender::Result, ParamValue>
312
MavlinkParameterSender::get_param(const std::string& name)
×
313
{
314
    auto prom = std::promise<std::pair<Result, ParamValue>>();
×
315
    auto res = prom.get_future();
×
316
    get_param_async(
×
317
        name,
318
        [&prom](Result result, ParamValue new_value) {
×
319
            prom.set_value(std::make_pair<>(result, std::move(new_value)));
×
320
        },
×
321
        this);
322
    return res.get();
×
323
}
324

325
std::pair<MavlinkParameterSender::Result, int32_t>
326
MavlinkParameterSender::get_param_int(const std::string& name)
5✔
327
{
328
    auto prom = std::promise<std::pair<Result, int32_t>>();
10✔
329
    auto res = prom.get_future();
10✔
330
    get_param_int_async(
5✔
331
        name,
332
        [&prom](Result result, int32_t value) { prom.set_value(std::make_pair<>(result, value)); },
5✔
333
        this);
334
    return res.get();
5✔
335
}
336

337
std::pair<MavlinkParameterSender::Result, float>
338
MavlinkParameterSender::get_param_float(const std::string& name)
5✔
339
{
340
    auto prom = std::promise<std::pair<Result, float>>();
10✔
341
    auto res = prom.get_future();
10✔
342
    get_param_float_async(
5✔
343
        name,
344
        [&prom](Result result, float value) { prom.set_value(std::make_pair<>(result, value)); },
5✔
345
        this);
346
    return res.get();
5✔
347
}
348

349
std::pair<MavlinkParameterSender::Result, std::string>
350
MavlinkParameterSender::get_param_custom(const std::string& name)
4✔
351
{
352
    auto prom = std::promise<std::pair<Result, std::string>>();
8✔
353
    auto res = prom.get_future();
8✔
354
    get_param_custom_async(
4✔
355
        name,
356
        [&prom](Result result, const std::string& value) {
4✔
357
            prom.set_value(std::make_pair<>(result, value));
4✔
358
        },
4✔
359
        this);
360
    return res.get();
4✔
361
}
362

363
void MavlinkParameterSender::get_all_params_async(GetAllParamsCallback callback, void* cookie)
4✔
364
{
365
    if (_parameter_debugging) {
4✔
366
        LogDebug() << "Getting all params, extended: " << (_use_extended ? "yes" : "no");
×
367
    }
368

369
    auto new_work =
4✔
370
        std::make_shared<WorkItem>(WorkItemGetAll{std::move(callback), 0, false}, cookie);
12✔
371
    _work_queue.push_back(new_work);
4✔
372
}
4✔
373

374
std::pair<MavlinkParameterSender::Result, std::map<std::string, ParamValue>>
375
MavlinkParameterSender::get_all_params()
4✔
376
{
377
    std::promise<std::pair<MavlinkParameterSender::Result, std::map<std::string, ParamValue>>> prom;
8✔
378
    auto res = prom.get_future();
8✔
379
    get_all_params_async(
4✔
380
        // Make sure to NOT use a reference for all_params here, pass by value.
381
        // Since for example on a timeout, the empty all_params result is constructed in-place and
382
        // then goes out of scope when the callback returns.
383
        [&prom](Result result, std::map<std::string, ParamValue> set) {
4✔
384
            prom.set_value({result, std::move(set)});
4✔
385
        },
4✔
386
        this);
387
    auto ret = res.get();
4✔
388
    return ret;
4✔
389
}
390

391
void MavlinkParameterSender::cancel_all_param(const void* cookie)
×
392
{
393
    LockedQueue<WorkItem>::Guard work_queue_guard(_work_queue);
×
394

395
    // We don't call any callbacks before erasing them as this is just used on destruction
396
    // where we don't care anymore.
397
    _work_queue.erase(std::remove_if(_work_queue.begin(), _work_queue.end(), [&](auto&& item) {
×
398
        return (item->cookie == cookie);
×
399
    }));
400
}
×
401

402
void MavlinkParameterSender::clear_cache()
×
403
{
404
    _param_cache.clear();
×
405
}
×
406

407
void MavlinkParameterSender::do_work()
287✔
408
{
409
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
287✔
410
    auto work = work_queue_guard->get_front();
287✔
411

412
    if (!work) {
287✔
413
        return;
58✔
414
    }
415

416
    if (work->already_requested) {
229✔
417
        return;
203✔
418
    }
419

420
    std::visit(
52✔
421
        overloaded{
26✔
422
            [&](WorkItemSet& item) {
6✔
423
                auto message = create_set_param_message(item);
6✔
424
                if (!_sender.send_message(message)) {
6✔
425
                    LogErr() << "Send message failed";
×
426
                    work_queue_guard->pop_front();
×
427
                    if (item.callback) {
×
428
                        auto callback = item.callback;
×
429
                        work_queue_guard.reset();
×
430
                        callback(Result::ConnectionError);
×
431
                    }
432
                    return;
×
433
                }
434
                work->already_requested = true;
6✔
435
                // We want to get notified if a timeout happens
436
                _timeout_handler.add(
6✔
437
                    [this] { receive_timeout(); }, _timeout_s_callback(), &_timeout_cookie);
2✔
438
            },
439
            [&](WorkItemGet& item) {
16✔
440
                auto message = create_get_param_message(item);
16✔
441
                if (!_sender.send_message(message)) {
16✔
442
                    LogErr() << "Send message failed";
×
443
                    work_queue_guard->pop_front();
×
444
                    if (item.callback) {
×
445
                        auto callback = item.callback;
×
446
                        work_queue_guard.reset();
×
447
                        item.callback(Result::ConnectionError, ParamValue{});
×
448
                    }
449
                    return;
×
450
                }
451
                work->already_requested = true;
16✔
452
                // We want to get notified if a timeout happens
453
                _timeout_handler.add(
16✔
454
                    [this] { receive_timeout(); }, _timeout_s_callback(), &_timeout_cookie);
4✔
455
            },
456
            [&](WorkItemGetAll& item) {
4✔
457
                auto message = create_request_list_message();
4✔
458

459
                if (!_sender.send_message(message)) {
4✔
460
                    LogErr() << "Send message failed";
×
461
                    work_queue_guard->pop_front();
×
462
                    if (item.callback) {
×
463
                        auto callback = item.callback;
×
464
                        work_queue_guard.reset();
×
465
                        item.callback(Result::ConnectionError, {});
×
466
                    }
467
                    return;
×
468
                }
469
                work->already_requested = true;
4✔
470
                // We want to get notified if a timeout happens
471
                _timeout_handler.add(
4✔
472
                    [this] { receive_timeout(); }, _timeout_s_callback(), &_timeout_cookie);
2✔
473
            }},
474
        work->work_item_variant);
26✔
475
}
476

477
mavlink_message_t MavlinkParameterSender::create_set_param_message(WorkItemSet& work_item)
9✔
478
{
479
    auto param_id = param_id_to_message_buffer(work_item.param_name);
9✔
480

481
    mavlink_message_t message;
482
    if (_use_extended) {
9✔
483
        const auto param_value_buf = work_item.param_value.get_128_bytes();
2✔
484
        if (_parameter_debugging) {
2✔
485
            LogDebug() << "Sending param_ext_set to:" << (int)_sender.get_own_system_id() << ":"
×
486
                       << (int)_sender.get_own_component_id();
×
487
        }
488
        mavlink_msg_param_ext_set_pack(
4✔
489
            _sender.get_own_system_id(),
2✔
490
            _sender.get_own_component_id(),
2✔
491
            &message,
492
            _sender.get_system_id(),
2✔
493
            _target_component_id,
2✔
494
            param_id.data(),
2✔
495
            param_value_buf.data(),
496
            work_item.param_value.get_mav_param_ext_type());
2✔
497
    } else {
498
        if (_parameter_debugging) {
7✔
499
            LogDebug() << "Sending param_set to:" << (int)_sender.get_own_system_id() << ":"
×
500
                       << (int)_sender.get_own_component_id();
×
501
        }
502

503
        const float value_set = (_sender.autopilot() == SystemImpl::Autopilot::ArduPilot) ?
7✔
504
                                    work_item.param_value.get_4_float_bytes_cast() :
×
505
                                    work_item.param_value.get_4_float_bytes_bytewise();
7✔
506

507
        mavlink_msg_param_set_pack(
7✔
508
            _sender.get_own_system_id(),
7✔
509
            _sender.get_own_component_id(),
7✔
510
            &message,
511
            _sender.get_system_id(),
7✔
512
            _target_component_id,
7✔
513
            param_id.data(),
7✔
514
            value_set,
515
            work_item.param_value.get_mav_param_type());
7✔
516
    }
517
    return message;
9✔
518
}
519

520
mavlink_message_t MavlinkParameterSender::create_get_param_message(WorkItemGet& work_item)
25✔
521
{
522
    std::array<char, PARAM_ID_LEN> param_id_buff{};
25✔
523
    int16_t param_index = -1;
25✔
524
    if (auto str = std::get_if<std::string>(&work_item.param_identifier)) {
25✔
525
        param_id_buff = param_id_to_message_buffer(*str);
25✔
526
    } else {
527
        // param_id_buff doesn't matter
528
        param_index = std::get<int16_t>(work_item.param_identifier);
×
529
    }
530

531
    return create_get_param_message(param_id_buff, param_index);
25✔
532
}
533

534
mavlink_message_t MavlinkParameterSender::create_get_param_message(
27✔
535
    const std::array<char, PARAM_ID_LEN>& param_id_buff, int16_t param_index)
536
{
537
    mavlink_message_t message;
538

539
    if (_use_extended) {
27✔
540
        if (_parameter_debugging) {
6✔
541
            LogDebug() << "Send param_ext_request_read: " << (int)_sender.get_own_system_id() << ":"
×
542
                       << (int)_sender.get_own_component_id() << " to "
×
543
                       << (int)_sender.get_system_id() << ":" << (int)_target_component_id;
×
544
        }
545

546
        mavlink_msg_param_ext_request_read_pack(
12✔
547
            _sender.get_own_system_id(),
6✔
548
            _sender.get_own_component_id(),
6✔
549
            &message,
550
            _sender.get_system_id(),
6✔
551
            _target_component_id,
6✔
552
            param_id_buff.data(),
553
            param_index);
554

555
    } else {
556
        if (_parameter_debugging) {
21✔
557
            LogDebug() << "Send param_request_read: " << (int)_sender.get_own_system_id() << ":"
×
558
                       << (int)_sender.get_own_component_id() << " to "
×
559
                       << (int)_sender.get_system_id() << ":" << (int)_target_component_id;
×
560
        }
561

562
        mavlink_msg_param_request_read_pack(
42✔
563
            _sender.get_own_system_id(),
21✔
564
            _sender.get_own_component_id(),
21✔
565
            &message,
566
            _sender.get_system_id(),
21✔
567
            _target_component_id,
21✔
568
            param_id_buff.data(),
569
            param_index);
570
    }
571

572
    return message;
27✔
573
}
574

575
mavlink_message_t MavlinkParameterSender::create_request_list_message()
5✔
576
{
577
    mavlink_message_t message;
578
    if (_use_extended) {
5✔
579
        if (_parameter_debugging) {
3✔
580
            LogDebug() << "Sending param_ext_request_list to:" << (int)_sender.get_own_system_id()
×
581
                       << ":" << (int)_sender.get_own_component_id();
×
582
        }
583
        mavlink_msg_param_ext_request_list_pack(
3✔
584
            _sender.get_own_system_id(),
3✔
585
            _sender.get_own_component_id(),
3✔
586
            &message,
587
            _sender.get_system_id(),
3✔
588
            _target_component_id);
3✔
589
    } else {
590
        LogDebug() << "Sending param_request_list to:" << (int)_sender.get_own_system_id() << ":"
6✔
591
                   << (int)_sender.get_own_component_id();
6✔
592
        mavlink_msg_param_request_list_pack(
2✔
593
            _sender.get_own_system_id(),
2✔
594
            _sender.get_own_component_id(),
2✔
595
            &message,
596
            _sender.get_system_id(),
2✔
597
            _target_component_id);
2✔
598
    }
599

600
    return message;
5✔
601
}
602

603
void MavlinkParameterSender::process_param_value(const mavlink_message_t& message)
26✔
604
{
605
    mavlink_param_value_t param_value;
26✔
606
    mavlink_msg_param_value_decode(&message, &param_value);
26✔
607
    const std::string safe_param_id = extract_safe_param_id(param_value.param_id);
26✔
608
    if (safe_param_id.empty()) {
26✔
609
        LogWarn() << "Got ill-formed param_value message (param_id empty)";
×
610
        return;
×
611
    }
612

613
    ParamValue received_value;
26✔
614
    const bool set_value_success = received_value.set_from_mavlink_param_value(
26✔
615
        param_value,
616
        (_sender.autopilot() == SystemImpl::Autopilot::ArduPilot) ?
26✔
617
            ParamValue::Conversion::Cast :
618
            ParamValue::Conversion::Bitwise);
26✔
619
    if (!set_value_success) {
26✔
620
        LogWarn() << "Got ill-formed param_ext_value message (param_type unknown)";
×
621
        return;
×
622
    }
623

624
    if (_parameter_debugging) {
26✔
625
        LogDebug() << "process_param_value: " << safe_param_id << " " << received_value;
×
626
    }
627

628
    // We need to use a unique pointer here to remove the lock from the work queue manually "early"
629
    // before calling the (perhaps user-provided) callback. Otherwise, we might end up in a deadlock
630
    // if the callback wants to push another work item onto the queue. By using a unique ptr there
631
    // is no risk of forgetting to remove the lock - it is destroyed (if still valid) after going
632
    // out of scope.
633
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
26✔
634
    const auto work = work_queue_guard->get_front();
26✔
635
    if (!work) {
26✔
636
        return;
×
637
    }
638

639
    if (!work->already_requested) {
26✔
640
        return;
×
641
    }
642

643
    std::visit(
52✔
644
        overloaded{
26✔
645
            [&](WorkItemSet& item) {
4✔
646
                if (item.param_name != safe_param_id) {
4✔
647
                    // No match, let's just return the borrowed work item.
648
                    return;
×
649
                }
650

651
                if (_parameter_debugging) {
4✔
652
                    LogDebug() << "Item value is: " << item.param_value
×
653
                               << ", received: " << received_value;
×
654
                }
655

656
                if (item.param_value == received_value) {
4✔
657
                    // This was successful. Inform the caller.
658
                    _timeout_handler.remove(_timeout_cookie);
4✔
659
                    // LogDebug() << "time taken: " <<
660
                    // _sender.get_time().elapsed_since_s(_last_request_time);
661
                    work_queue_guard->pop_front();
4✔
662
                    if (item.callback) {
4✔
663
                        auto callback = item.callback;
8✔
664
                        work_queue_guard.reset();
4✔
665
                        callback(MavlinkParameterSender::Result::Success);
4✔
666
                    }
667
                } else {
668
                    // We might be receiving stale param_value messages, let's just
669
                    // try again. This can happen if the timeout is chosen low and we
670
                    // get out of sync when doing a param_get just before the param_set.
671
                    // In that case we have stale param_value messages in flux and
672
                    // receive them here.
673
                    if (work->retries_to_do > 0) {
×
674
                        LogWarn() << "sending again, retries to do: " << work->retries_to_do
×
675
                                  << "  (" << item.param_name << ").";
×
676

677
                        auto set_message = create_set_param_message(item);
×
678

679
                        if (!_sender.send_message(set_message)) {
×
680
                            LogErr() << "connection send error in retransmit (" << item.param_name
×
681
                                     << ").";
×
682
                            work_queue_guard->pop_front();
×
683

684
                            if (item.callback) {
×
685
                                auto callback = item.callback;
×
686
                                work_queue_guard.reset();
×
687
                                callback(Result::ConnectionError);
×
688
                            }
689
                            _timeout_handler.refresh(_timeout_cookie);
×
690
                        } else {
691
                            --work->retries_to_do;
×
692
                            _timeout_handler.refresh(_timeout_cookie);
×
693
                        }
694
                    } else {
695
                        // We have tried retransmitting, giving up now.
696
                        LogErr() << "Error: Retrying failed set param failed: " << item.param_name;
×
697
                        work_queue_guard->pop_front();
×
698
                        if (item.callback) {
×
699
                            auto callback = item.callback;
×
700
                            work_queue_guard.reset();
×
701
                            callback(Result::Timeout);
×
702
                        }
703
                    }
704
                }
705
            },
706
            [&](WorkItemGet& item) {
10✔
707
                if (!validate_id_or_index(
10✔
708
                        item.param_identifier,
10✔
709
                        safe_param_id,
10✔
710
                        static_cast<int16_t>(param_value.param_index))) {
10✔
711
                    LogWarn() << "Got unexpected response on work item";
×
712
                    // No match, let's just return the borrowed work item.
713
                    return;
×
714
                }
715
                _timeout_handler.remove(_timeout_cookie);
10✔
716
                // LogDebug() << "time taken: " <<
717
                // _sender.get_time().elapsed_since_s(_last_request_time);
718
                work_queue_guard->pop_front();
10✔
719
                if (item.callback) {
10✔
720
                    auto callback = item.callback;
20✔
721
                    work_queue_guard.reset();
10✔
722
                    callback(Result::Success, received_value);
10✔
723
                }
724
            },
725
            [&](WorkItemGetAll& item) {
12✔
726
                switch (_param_cache.add_new_param(
12✔
727
                    safe_param_id, received_value, param_value.param_index)) {
12✔
728
                    case MavlinkParameterCache::AddNewParamResult::AlreadyExists:
12✔
729
                        // FALLTHROUGH
730
                        // We don't care if it already exists, just overwrite it and carry on.
731
                        // The reason is that this can likely happen if the very first
732
                        // request_list is sent twice and hence we get a bunch of duplicate
733
                        // params.
734
                    case MavlinkParameterCache::AddNewParamResult::Ok:
735

736
                        item.count = param_value.param_count;
12✔
737
                        if (_parameter_debugging) {
12✔
738
                            LogDebug() << "Count expected " << _param_cache.count(_use_extended)
×
739
                                       << " so far " << param_value.param_count;
×
740
                        }
741
                        if (_param_cache.count(_use_extended) == param_value.param_count) {
12✔
742
                            if (_parameter_debugging) {
2✔
743
                                LogDebug() << "Param set complete: "
×
744
                                           << (_use_extended ? "extended" : "not extended");
×
745
                            }
746
                            _timeout_handler.remove(_timeout_cookie);
2✔
747
                            work_queue_guard->pop_front();
2✔
748
                            if (item.callback) {
2✔
749
                                auto callback = item.callback;
4✔
750
                                work_queue_guard.reset();
2✔
751
                                callback(
4✔
752
                                    Result::Success,
753
                                    _param_cache.all_parameters_map(_use_extended));
4✔
754
                            }
755
                        } else {
756
                            if (item.rerequesting) {
10✔
757
                                auto maybe_next_missing_index =
×
758
                                    _param_cache.next_missing_index(item.count);
×
759
                                if (!maybe_next_missing_index.has_value()) {
×
760
                                    LogErr() << "logic error, there should a missing index";
×
761
                                    assert(false);
×
762
                                }
763

764
                                if (_parameter_debugging) {
×
765
                                    LogDebug() << "Requesting missing parameter "
×
766
                                               << (int)maybe_next_missing_index.value();
×
767
                                }
768

769
                                std::array<char, PARAM_ID_LEN> param_id_buff{};
×
770
                                auto get_message = create_get_param_message(
×
771
                                    param_id_buff, maybe_next_missing_index.value());
×
772

773
                                if (!_sender.send_message(get_message)) {
×
774
                                    LogErr() << "Send message failed";
×
775
                                    work_queue_guard->pop_front();
×
776
                                    if (item.callback) {
×
777
                                        auto callback = item.callback;
×
778
                                        work_queue_guard.reset();
×
779
                                        callback(Result::ConnectionError, {});
×
780
                                    }
781
                                    return;
×
782
                                }
783
                            } else {
784
                                // update the timeout handler, messages are still coming in.
785
                            }
786
                            _timeout_handler.refresh(&_timeout_cookie);
10✔
787
                        }
788
                        break;
12✔
789
                    case MavlinkParameterCache::AddNewParamResult::TooManyParams:
×
790
                        // We shouldn't be able to get here as the incoming type is only an
791
                        // uint16_t.
792
                        LogErr() << "Too many params received";
×
793
                        assert(false);
×
794
                        break;
795
                    default:
×
796
                        LogErr() << "Unknown AddNewParamResult";
×
797
                        assert(false);
×
798
                        break;
799
                }
800
            }},
801
        work->work_item_variant);
26✔
802

803
    // find_and_call_subscriptions_value_changed(safe_param_id, received_value);
804
}
805

806
void MavlinkParameterSender::process_param_ext_value(const mavlink_message_t& message)
28✔
807
{
808
    mavlink_param_ext_value_t param_ext_value;
28✔
809
    mavlink_msg_param_ext_value_decode(&message, &param_ext_value);
28✔
810
    const auto safe_param_id = extract_safe_param_id(param_ext_value.param_id);
28✔
811
    if (safe_param_id.empty()) {
28✔
812
        LogWarn() << "Got ill-formed param_ext_value message (param_id empty)";
×
813
        return;
×
814
    }
815
    ParamValue received_value;
28✔
816
    if (!received_value.set_from_mavlink_param_ext_value(param_ext_value)) {
28✔
817
        LogWarn() << "Got ill-formed param_ext_value message (param_type unknown)";
×
818
        return;
×
819
    }
820

821
    if (_parameter_debugging) {
28✔
822
        LogDebug() << "process param_ext_value: " << safe_param_id << " " << received_value;
×
823
    }
824

825
    // See comments on process_param_value for use of unique_ptr
826
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
28✔
827
    auto work = work_queue_guard->get_front();
28✔
828
    if (!work) {
28✔
829
        return;
×
830
    }
831
    if (!work->already_requested) {
28✔
832
        return;
×
833
    }
834

835
    std::visit(
56✔
836
        overloaded{
28✔
837
            [&](WorkItemSet&) {
×
838
                if (_parameter_debugging) {
×
839
                    LogDebug() << "Unexpected ParamExtValue response.";
×
840
                }
841
            },
×
842
            [&](WorkItemGet& item) {
4✔
843
                if (!validate_id_or_index(
4✔
844
                        item.param_identifier,
4✔
845
                        safe_param_id,
4✔
846
                        static_cast<int16_t>(param_ext_value.param_index))) {
4✔
847
                    LogWarn() << "Got unexpected response on work item";
×
848
                    // No match, let's just return the borrowed work item.
849
                    return;
×
850
                }
851
                _timeout_handler.remove(_timeout_cookie);
4✔
852
                // LogDebug() << "time taken: " <<
853
                // _sender.get_time().elapsed_since_s(_last_request_time);
854
                work_queue_guard->pop_front();
4✔
855
                if (item.callback) {
4✔
856
                    auto callback = item.callback;
8✔
857
                    work_queue_guard.reset();
4✔
858
                    callback(Result::Success, received_value);
4✔
859
                }
860
            },
861
            [&](WorkItemGetAll& item) {
24✔
862
                switch (_param_cache.add_new_param(
24✔
863
                    safe_param_id, received_value, param_ext_value.param_index)) {
24✔
864
                    case MavlinkParameterCache::AddNewParamResult::AlreadyExists:
24✔
865
                        // PASSTHROUGH.
866
                    case MavlinkParameterCache::AddNewParamResult::Ok:
867
                        if (_parameter_debugging) {
24✔
868
                            LogDebug() << "Count expected " << _param_cache.count(_use_extended)
×
869
                                       << " but is " << param_ext_value.param_count;
×
870
                        }
871
                        if (_param_cache.count(_use_extended) == param_ext_value.param_count) {
24✔
872
                            if (_parameter_debugging) {
2✔
873
                                LogDebug() << "Param set complete: "
×
874
                                           << (_use_extended ? "extended" : "not extended");
×
875
                            }
876
                            _timeout_handler.remove(_timeout_cookie);
2✔
877
                            work_queue_guard->pop_front();
2✔
878
                            if (item.callback) {
2✔
879
                                auto callback = item.callback;
4✔
880
                                work_queue_guard.reset();
2✔
881
                                callback(
4✔
882
                                    Result::Success,
883
                                    _param_cache.all_parameters_map(_use_extended));
4✔
884
                            }
885
                        } else {
886
                            // update the timeout handler, messages are still coming in.
887
                            _timeout_handler.refresh(&_timeout_cookie);
22✔
888
                        }
889
                        break;
24✔
890
                    case MavlinkParameterCache::AddNewParamResult::TooManyParams:
×
891
                        // We shouldn't be able to get here as the incoming type is only an
892
                        // uint16_t.
893
                        LogErr() << "Too many params received";
×
894
                        assert(false);
×
895
                        break;
896
                    default:
×
897
                        LogErr() << "Unknown AddNewParamResult";
×
898
                        assert(false);
×
899
                        break;
900
                }
901
            },
24✔
902
        },
903
        work->work_item_variant);
28✔
904

905
    // TODO I think we need to consider more edge cases here
906
    // find_and_call_subscriptions_value_changed(safe_param_id, received_value);
907
}
908

909
void MavlinkParameterSender::process_param_ext_ack(const mavlink_message_t& message)
2✔
910
{
911
    mavlink_param_ext_ack_t param_ext_ack;
2✔
912
    mavlink_msg_param_ext_ack_decode(&message, &param_ext_ack);
2✔
913
    const auto safe_param_id = extract_safe_param_id(param_ext_ack.param_id);
2✔
914

915
    if (_parameter_debugging) {
2✔
916
        LogDebug() << "process param_ext_ack: " << safe_param_id << " "
×
917
                   << (int)param_ext_ack.param_result;
×
918
    }
919

920
    // See comments on process_param_value for use of unique_ptr
921
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
2✔
922
    auto work = work_queue_guard->get_front();
2✔
923
    if (!work) {
2✔
924
        return;
×
925
    }
926
    if (!work->already_requested) {
2✔
927
        return;
×
928
    }
929

930
    std::visit(
4✔
931
        overloaded{
2✔
932
            [&](WorkItemSet& item) {
2✔
933
                if (item.param_name != safe_param_id) {
2✔
934
                    // No match, let's just return the borrowed work item.
935
                    return;
×
936
                }
937
                if (param_ext_ack.param_result == PARAM_ACK_ACCEPTED) {
2✔
938
                    _timeout_handler.remove(_timeout_cookie);
2✔
939
                    // LogDebug() << "time taken: " <<
940
                    // _sender.get_time().elapsed_since_s(_last_request_time);
941
                    work_queue_guard->pop_front();
2✔
942
                    if (item.callback) {
2✔
943
                        auto callback = item.callback;
4✔
944
                        // We are done, inform caller and go back to idle
945
                        work_queue_guard.reset();
2✔
946
                        callback(Result::Success);
2✔
947
                    }
948
                } else if (param_ext_ack.param_result == PARAM_ACK_IN_PROGRESS) {
×
949
                    // Reset timeout and wait again.
950
                    _timeout_handler.refresh(_timeout_cookie);
×
951

952
                } else {
953
                    LogWarn() << "Somehow we did not get an ack, we got: "
×
954
                              << int(param_ext_ack.param_result);
×
955
                    _timeout_handler.remove(_timeout_cookie);
×
956
                    // LogDebug() << "time taken: " <<
957
                    // _sender.get_time().elapsed_since_s(_last_request_time);
958
                    work_queue_guard->pop_front();
×
959
                    work_queue_guard.reset();
×
960
                    if (item.callback) {
×
961
                        auto callback = item.callback;
×
962
                        auto result = [&]() {
×
963
                            switch (param_ext_ack.param_result) {
×
964
                                case PARAM_ACK_FAILED:
×
965
                                    return Result::Failed;
×
966
                                case PARAM_ACK_VALUE_UNSUPPORTED:
×
967
                                    return Result::ValueUnsupported;
×
968
                                default:
×
969
                                    return Result::UnknownError;
×
970
                            }
971
                        }();
×
972
                        work_queue_guard.reset();
×
973
                        callback(result);
×
974
                    }
975
                }
976
            },
977
            [&](WorkItemGet&) { LogWarn() << "Unexpected ParamExtAck response."; },
×
978
            [&](WorkItemGetAll&) { LogWarn() << "Unexpected ParamExtAck response."; }},
×
979
        work->work_item_variant);
2✔
980
}
981

982
void MavlinkParameterSender::receive_timeout()
17✔
983
{
984
    // See comments on process_param_value for use of unique_ptr
985
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
17✔
986

987
    auto work = work_queue_guard->get_front();
17✔
988
    if (!work) {
17✔
989
        LogErr() << "Received timeout without work";
×
990
        return;
×
991
    }
992
    if (!work->already_requested) {
17✔
993
        LogErr() << "Received timeout without already having work requested";
×
994
        return;
×
995
    }
996

997
    std::visit(
34✔
998
        overloaded{
17✔
999
            [&](WorkItemSet& item) {
3✔
1000
                if (work->retries_to_do > 0) {
3✔
1001
                    // We're not sure the command arrived, let's retransmit.
1002
                    LogWarn() << "sending again, retries to do: " << work->retries_to_do << "  ("
6✔
1003
                              << item.param_name << ").";
6✔
1004

1005
                    auto message = create_set_param_message(item);
3✔
1006

1007
                    if (!_sender.send_message(message)) {
3✔
1008
                        LogErr() << "connection send error in retransmit (" << item.param_name
×
1009
                                 << ").";
×
1010
                        work_queue_guard->pop_front();
×
1011

1012
                        if (item.callback) {
×
1013
                            auto callback = item.callback;
×
1014
                            work_queue_guard.reset();
×
1015
                            callback(Result::ConnectionError);
×
1016
                        }
1017
                    } else {
1018
                        --work->retries_to_do;
3✔
1019
                        _timeout_handler.add(
3✔
1020
                            [this] { receive_timeout(); }, _timeout_s_callback(), &_timeout_cookie);
1✔
1021
                    }
1022
                } else {
1023
                    // We have tried retransmitting, giving up now.
1024
                    LogErr() << "Error: Retrying failed set param timeout: " << item.param_name;
×
1025
                    work_queue_guard->pop_front();
×
1026
                    if (item.callback) {
×
1027
                        auto callback = item.callback;
×
1028
                        work_queue_guard.reset();
×
1029
                        callback(Result::Timeout);
×
1030
                    }
1031
                }
1032
            },
3✔
1033
            [&](WorkItemGet& item) {
11✔
1034
                if (work->retries_to_do > 0) {
11✔
1035
                    // We're not sure the command arrived, let's retransmit.
1036
                    LogWarn() << "sending again, retries to do: " << work->retries_to_do;
9✔
1037
                    auto message = create_get_param_message(item);
9✔
1038
                    if (!_sender.send_message(message)) {
9✔
1039
                        LogErr() << "connection send error in retransmit ";
×
1040
                        work_queue_guard->pop_front();
×
1041
                        if (item.callback) {
×
1042
                            auto callback = item.callback;
×
1043
                            work_queue_guard.reset();
×
1044
                            callback(Result::ConnectionError, {});
×
1045
                        }
1046
                    } else {
1047
                        --work->retries_to_do;
9✔
1048
                        _timeout_handler.add(
9✔
1049
                            [this] { receive_timeout(); }, _timeout_s_callback(), &_timeout_cookie);
7✔
1050
                    }
1051
                } else {
1052
                    // We have tried retransmitting, giving up now.
1053
                    LogErr() << "retrying failed";
2✔
1054
                    work_queue_guard->pop_front();
2✔
1055
                    if (item.callback) {
2✔
1056
                        auto callback = item.callback;
4✔
1057
                        work_queue_guard.reset();
2✔
1058
                        callback(Result::Timeout, {});
2✔
1059
                    }
1060
                }
1061
            },
11✔
1062
            [&](WorkItemGetAll& item) {
3✔
1063
                // Request missing parameters.
1064
                // If retries are exceeded, give up with timeout.
1065

1066
                if (_parameter_debugging) {
3✔
1067
                    LogDebug() << "All params receive timeout with";
×
1068
                }
1069

1070
                if (item.count == 0) {
3✔
1071
                    // We got 0 messages back from the server (param count unknown). Most likely the
1072
                    // "list request" got lost before making it to the server,
1073
                    if (work->retries_to_do > 0) {
1✔
1074
                        --work->retries_to_do;
1✔
1075

1076
                        auto message = create_request_list_message();
1✔
1077

1078
                        if (!_sender.send_message(message)) {
1✔
1079
                            LogErr() << "Send message failed";
×
1080
                            work_queue_guard->pop_front();
×
1081
                            if (item.callback) {
×
1082
                                auto callback = item.callback;
×
1083
                                work_queue_guard.reset();
×
1084
                                item.callback(Result::ConnectionError, {});
×
1085
                            }
1086
                            return;
×
1087
                        }
1088

1089
                        // We want to get notified if a timeout happens
1090
                        _timeout_handler.add(
1✔
1091
                            [this] { receive_timeout(); }, _timeout_s_callback(), &_timeout_cookie);
×
1092
                    } else {
1093
                        if (item.callback) {
×
1094
                            auto callback = item.callback;
×
1095
                            work_queue_guard.reset();
×
1096
                            item.callback(Result::Timeout, {});
×
1097
                        }
1098
                        return;
×
1099
                    }
1100

1101
                } else {
1102
                    item.rerequesting = true;
2✔
1103
                    auto maybe_next_missing_index = _param_cache.next_missing_index(item.count);
2✔
1104
                    if (!maybe_next_missing_index.has_value()) {
2✔
1105
                        LogErr() << "logic error, there should a missing index";
×
1106
                        assert(false);
×
1107
                    }
1108

1109
                    if (_parameter_debugging) {
2✔
1110
                        LogDebug() << "Requesting missing parameter "
×
1111
                                   << (int)maybe_next_missing_index.value();
×
1112
                    }
1113

1114
                    std::array<char, PARAM_ID_LEN> param_id_buff{};
2✔
1115
                    auto message =
2✔
1116
                        create_get_param_message(param_id_buff, maybe_next_missing_index.value());
2✔
1117

1118
                    if (!_sender.send_message(message)) {
2✔
1119
                        LogErr() << "Send message failed";
×
1120
                        work_queue_guard->pop_front();
×
1121
                        if (item.callback) {
×
1122
                            auto callback = item.callback;
×
1123
                            work_queue_guard.reset();
×
1124
                            callback(Result::ConnectionError, {});
×
1125
                        }
1126
                        return;
×
1127
                    }
1128
                    _timeout_handler.add(
2✔
1129
                        [this] { receive_timeout(); }, _timeout_s_callback(), &_timeout_cookie);
1✔
1130
                }
1131
            }},
1132
        work->work_item_variant);
17✔
1133
}
1134

1135
std::ostream& operator<<(std::ostream& str, const MavlinkParameterSender::Result& result)
×
1136
{
1137
    switch (result) {
×
1138
        case MavlinkParameterSender::Result::Success:
×
1139
            return str << "Success";
×
1140
        case MavlinkParameterSender::Result::Timeout:
×
1141
            return str << "Timeout";
×
1142
        case MavlinkParameterSender::Result::ConnectionError:
×
1143
            return str << "ConnectionError";
×
1144
        case MavlinkParameterSender::Result::WrongType:
×
1145
            return str << "WrongType";
×
1146
        case MavlinkParameterSender::Result::ParamNameTooLong:
×
1147
            return str << "ParamNameTooLong";
×
1148
        case MavlinkParameterSender::Result::NotFound:
×
1149
            return str << "NotFound";
×
1150
        case MavlinkParameterSender::Result::ValueUnsupported:
×
1151
            return str << "ValueUnsupported";
×
1152
        case MavlinkParameterSender::Result::Failed:
×
1153
            return str << "Failed";
×
1154
        case MavlinkParameterSender::Result::UnknownError:
×
1155
            // Fallthrough
1156
        default:
1157
            return str << "UnknownError";
×
1158
    }
1159
}
1160

1161
bool MavlinkParameterSender::validate_id_or_index(
14✔
1162
    const std::variant<std::string, int16_t>& original,
1163
    const std::string& param_id,
1164
    const int16_t param_index)
1165
{
1166
    if (const auto str = std::get_if<std::string>(&original)) {
14✔
1167
        if (param_id != *str) {
14✔
1168
            // We requested by string id, but response doesn't match
1169
            return false;
×
1170
        }
1171
    } else {
1172
        const auto tmp = std::get<int16_t>(original);
×
1173
        if (param_index != tmp) {
×
1174
            // We requested by index, but response doesn't match
1175
            return false;
×
1176
        }
1177
    }
1178
    return true;
14✔
1179
}
1180

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