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

mavlink / MAVSDK / 16636200771

30 Jul 2025 11:46PM UTC coverage: 44.271% (-2.0%) from 46.31%
16636200771

Pull #2626

github

web-flow
Merge bfd339d18 into c0a7c02a0
Pull Request #2626: core: flush after each Log* line

237 of 350 new or added lines in 32 files covered. (67.71%)

405 existing lines in 18 files now uncovered.

15319 of 34603 relevant lines covered (44.27%)

293.66 hits per line

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

59.33
/src/mavsdk/core/mavlink_parameter_client.cpp
1
#include "mavlink_parameter_helper.h"
2
#include "mavlink_parameter_client.h"
3
#include "mavlink_message_handler.h"
4
#include "system_impl.h"
5
#include "overloaded.h"
6
#include <algorithm>
7
#include <future>
8
#include <limits>
9
#include <utility>
10

11
namespace mavsdk {
12

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

38
    if (_parameter_debugging) {
10✔
39
        LogDebug() << "MavlinkParameterClient created for target compid: "
×
40
                   << (int)_target_component_id << " and "
×
41
                   << (_use_extended ? "extended" : "not extended");
×
42
    }
43

44
    if (_use_extended) {
10✔
45
        _message_handler.register_one(
6✔
46
            MAVLINK_MSG_ID_PARAM_EXT_VALUE,
47
            [this](const mavlink_message_t& message) { process_param_ext_value(message); },
67✔
48
            this);
49

50
        _message_handler.register_one(
6✔
51
            MAVLINK_MSG_ID_PARAM_EXT_ACK,
52
            [this](const mavlink_message_t& message) { process_param_ext_ack(message); },
5✔
53
            this);
54
    } else {
55
        _message_handler.register_one(
4✔
56
            MAVLINK_MSG_ID_PARAM_VALUE,
57
            [this](const mavlink_message_t& message) { process_param_value(message); },
26✔
58
            this);
59
    }
60
}
10✔
61

62
MavlinkParameterClient::~MavlinkParameterClient()
10✔
63
{
64
    if (_parameter_debugging) {
10✔
65
        LogDebug() << "MavlinkParameterClient destructed for target compid: "
×
66
                   << (int)_target_component_id << " and "
×
67
                   << (_use_extended ? "extended" : "not extended");
×
68
    }
69

70
    _message_handler.unregister_all(this);
10✔
71
}
10✔
72

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

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

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

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

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

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

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

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

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

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

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

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

234
void MavlinkParameterClient::get_param_async(
48✔
235
    const std::string& name, const GetParamAnyCallback& callback, const void* cookie)
236
{
237
    if (_parameter_debugging) {
48✔
238
        LogDebug() << "Getting param " << name << ", extended: " << (_use_extended ? "yes" : "no");
×
239
    }
240
    if (name.size() > PARAM_ID_LEN) {
48✔
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);
96✔
249
    _work_queue.push_back(new_work);
48✔
250
}
48✔
251

252
void MavlinkParameterClient::get_param_async(
32✔
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,
32✔
260
                                                  value_type](Result result, ParamValue value) {
261
        if (result == Result::Success) {
32✔
262
            if (value.is_same_type(value_type)) {
32✔
263
                callback(Result::Success, std::move(value));
32✔
264
            } else {
265
                callback(Result::WrongType, {});
×
266
            }
267
        } else {
268
            callback(result, {});
×
269
        }
270
    };
64✔
271
    get_param_async(name, callback_future_result, cookie);
32✔
272
}
32✔
273

274
template<class T>
275
void MavlinkParameterClient::get_param_async_typesafe(
9✔
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) {
36✔
280
        if (result == Result::Success) {
9✔
281
            if (value.is<T>()) {
8✔
282
                callback(Result::Success, value.get<T>());
8✔
283
            } else {
284
                callback(Result::WrongType, {});
×
285
            }
286
        } else {
287
            callback(result, {});
1✔
288
        }
289
    };
290
    get_param_async(name, callback_future_result, cookie);
9✔
291
}
9✔
292

293
template<>
294
void MavlinkParameterClient::get_param_async_typesafe(
5✔
295
    const std::string& name, const GetParamTypesafeCallback<int32_t> callback, const void* cookie)
296
{
297
    // We need to delay the type checking until we get a response from the server.
298
    GetParamAnyCallback callback_future_result = [callback](Result result, ParamValue value) {
5✔
299
        if (result == Result::Success) {
5✔
300
            if (value.is<int32_t>()) {
4✔
301
                callback(Result::Success, value.get<int32_t>());
4✔
302
            } else if (value.is<int16_t>()) {
×
303
                callback(Result::Success, value.get<int16_t>());
×
304
            } else if (value.is<int8_t>()) {
×
305
                callback(Result::Success, value.get<int8_t>());
×
306
            } else {
307
                callback(Result::WrongType, {});
×
308
            }
309
        } else {
310
            callback(result, {});
1✔
311
        }
312
    };
10✔
313
    get_param_async(name, callback_future_result, cookie);
5✔
314
}
5✔
315

316
void MavlinkParameterClient::get_param_float_async(
5✔
317
    const std::string& name, const GetParamFloatCallback& callback, const void* cookie)
318
{
319
    get_param_async_typesafe<float>(name, callback, cookie);
5✔
320
}
5✔
321

322
void MavlinkParameterClient::get_param_int_async(
5✔
323
    const std::string& name, const GetParamIntCallback& callback, const void* cookie)
324
{
325
    get_param_async_typesafe<int32_t>(name, callback, cookie);
5✔
326
}
5✔
327

328
void MavlinkParameterClient::get_param_custom_async(
4✔
329
    const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
330
{
331
    get_param_async_typesafe<std::string>(name, callback, cookie);
4✔
332
}
4✔
333

334
std::pair<MavlinkParameterClient::Result, ParamValue>
335
MavlinkParameterClient::get_param(const std::string& name)
×
336
{
337
    auto prom = std::promise<std::pair<Result, ParamValue>>();
×
338
    auto res = prom.get_future();
×
339
    get_param_async(
×
340
        name,
341
        [&prom](Result result, ParamValue new_value) {
×
342
            prom.set_value(std::make_pair<>(result, std::move(new_value)));
×
343
        },
×
344
        this);
345
    return res.get();
×
346
}
×
347

348
std::pair<MavlinkParameterClient::Result, int32_t>
349
MavlinkParameterClient::get_param_int(const std::string& name)
5✔
350
{
351
    auto prom = std::promise<std::pair<Result, int32_t>>();
5✔
352
    auto res = prom.get_future();
5✔
353
    get_param_int_async(
5✔
354
        name,
355
        [&prom](Result result, int32_t value) { prom.set_value(std::make_pair<>(result, value)); },
5✔
356
        this);
357
    return res.get();
5✔
358
}
5✔
359

360
std::pair<MavlinkParameterClient::Result, float>
361
MavlinkParameterClient::get_param_float(const std::string& name)
5✔
362
{
363
    auto prom = std::promise<std::pair<Result, float>>();
5✔
364
    auto res = prom.get_future();
5✔
365

366
    // Store addresses for corruption detection
367
    void* prom_addr = &prom;
5✔
368
    void* fut_addr = &res;
5✔
369

370
    LogInfo() << "Parameter get_param_float('" << name << "') - prom: " << prom_addr
10✔
371
              << " fut: " << fut_addr;
10✔
372

373
    get_param_float_async(
5✔
374
        name,
375
        [&prom, prom_addr, fut_addr, name](Result result, float value) {
20✔
376
            LogInfo() << "Parameter callback for '" << name << "' - prom: " << &prom
15✔
377
                      << " (orig: " << prom_addr << ") result: " << (int)result;
15✔
378

379
            if (&prom != prom_addr) {
5✔
NEW
380
                LogErr() << "CORRUPTION DETECTED: Promise address changed from " << prom_addr
×
NEW
381
                         << " to " << &prom;
×
NEW
382
                std::abort();
×
383
            }
384

385
            prom.set_value(std::make_pair<>(result, value));
5✔
386
            LogInfo() << "Promise set_value completed for '" << name << "'";
5✔
387
        },
5✔
388
        this);
389

390
    LogInfo() << "About to call fut.get() for '" << name << "'";
5✔
391
    auto result = res.get();
5✔
392
    LogInfo() << "fut.get() returned for '" << name << "' - result: " << (int)result.first;
5✔
393

394
    return result;
10✔
395
}
5✔
396

397
std::pair<MavlinkParameterClient::Result, std::string>
398
MavlinkParameterClient::get_param_custom(const std::string& name)
4✔
399
{
400
    auto prom = std::promise<std::pair<Result, std::string>>();
4✔
401
    auto res = prom.get_future();
4✔
402
    get_param_custom_async(
4✔
403
        name,
404
        [&prom](Result result, const std::string& value) {
4✔
405
            prom.set_value(std::make_pair<>(result, value));
4✔
406
        },
4✔
407
        this);
408
    return res.get();
4✔
409
}
4✔
410

411
void MavlinkParameterClient::get_all_params_async(GetAllParamsCallback callback, void* cookie)
4✔
412
{
413
    if (_parameter_debugging) {
4✔
414
        LogDebug() << "Getting all params, extended: " << (_use_extended ? "yes" : "no");
×
415
    }
416

417
    auto new_work =
4✔
418
        std::make_shared<WorkItem>(WorkItemGetAll{std::move(callback), 0, false}, cookie);
8✔
419
    _work_queue.push_back(new_work);
4✔
420
}
4✔
421

422
std::pair<MavlinkParameterClient::Result, std::map<std::string, ParamValue>>
423
MavlinkParameterClient::get_all_params()
4✔
424
{
425
    std::promise<std::pair<MavlinkParameterClient::Result, std::map<std::string, ParamValue>>> prom;
4✔
426
    auto res = prom.get_future();
4✔
427
    get_all_params_async(
4✔
428
        // Make sure to NOT use a reference for all_params here, pass by value.
429
        // Since for example on a timeout, the empty all_params result is constructed in-place and
430
        // then goes out of scope when the callback returns.
431
        [&prom](Result result, std::map<std::string, ParamValue> set) {
4✔
432
            prom.set_value({result, std::move(set)});
4✔
433
        },
4✔
434
        this);
435
    auto ret = res.get();
4✔
436
    return ret;
4✔
437
}
4✔
438

439
void MavlinkParameterClient::cancel_all_param(const void* cookie)
×
440
{
441
    LockedQueue<WorkItem>::Guard work_queue_guard(_work_queue);
×
442

443
    // We don't call any callbacks before erasing them as this is just used on destruction
444
    // where we don't care anymore.
445
    _work_queue.erase(std::remove_if(_work_queue.begin(), _work_queue.end(), [&](auto&& item) {
×
446
        return (item->cookie == cookie);
×
447
    }));
448
}
×
449

450
void MavlinkParameterClient::clear_cache()
52✔
451
{
452
    _param_cache.clear();
52✔
453
}
52✔
454

455
void MavlinkParameterClient::do_work()
1,104✔
456
{
457
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
1,104✔
458
    auto work = work_queue_guard->get_front();
1,104✔
459

460
    if (!work) {
1,104✔
461
        return;
754✔
462
    }
463

464
    if (work->already_requested) {
350✔
465
        return;
289✔
466
    }
467

468
    std::visit(
122✔
469
        overloaded{
61✔
470
            [&](WorkItemSet& item) {
9✔
471
                if (!send_set_param_message(item)) {
9✔
472
                    LogErr() << "Send message failed";
×
473
                    work_queue_guard->pop_front();
×
474
                    if (item.callback) {
×
475
                        auto callback = item.callback;
×
476
                        work_queue_guard.reset();
×
477
                        callback(Result::ConnectionError);
×
478
                    }
×
479
                    return;
×
480
                }
481
                work->already_requested = true;
9✔
482
                // We want to get notified if a timeout happens
483
                _timeout_cookie =
9✔
484
                    _timeout_handler.add([this] { receive_timeout(); }, _timeout_s_callback());
20✔
485
            },
486
            [&](WorkItemGet& item) {
48✔
487
                // We can't rely on the cache as we haven't implemented the hash check.
488
                clear_cache();
48✔
489
                if (!send_get_param_message(item)) {
48✔
490
                    LogErr() << "Send message failed";
×
491
                    work_queue_guard->pop_front();
×
492
                    if (item.callback) {
×
493
                        auto callback = item.callback;
×
494
                        work_queue_guard.reset();
×
NEW
495
                        callback(Result::ConnectionError, ParamValue{});
×
496
                    }
×
497
                    return;
×
498
                }
499
                work->already_requested = true;
48✔
500
                // We want to get notified if a timeout happens
501
                _timeout_cookie =
48✔
502
                    _timeout_handler.add([this] { receive_timeout(); }, _timeout_s_callback());
100✔
503
            },
504
            [&](WorkItemGetAll& item) {
4✔
505
                // We can't rely on the cache as we haven't implemented the hash check.
506
                clear_cache();
4✔
507
                if (!send_request_list_message()) {
4✔
508
                    LogErr() << "Send message failed";
×
509
                    work_queue_guard->pop_front();
×
510
                    if (item.callback) {
×
511
                        auto callback = item.callback;
×
512
                        work_queue_guard.reset();
×
NEW
513
                        callback(Result::ConnectionError, {});
×
514
                    }
×
515
                    return;
×
516
                }
517
                work->already_requested = true;
4✔
518
                // We want to get notified if a timeout happens
519
                _timeout_cookie = _timeout_handler.add(
4✔
520
                    [this] { receive_timeout(); }, _timeout_s_callback() * _get_all_timeout_factor);
6✔
521
            }},
522
        work->work_item_variant);
61✔
523
}
2,147✔
524

525
bool MavlinkParameterClient::send_set_param_message(WorkItemSet& work_item)
11✔
526
{
527
    auto param_id = param_id_to_message_buffer(work_item.param_name);
11✔
528

529
    mavlink_message_t message;
11✔
530
    if (_use_extended) {
11✔
531
        const auto param_value_buf = work_item.param_value.get_128_bytes();
5✔
532
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
10✔
533
            if (_parameter_debugging) {
5✔
534
                LogDebug() << "Sending param_ext_set from:" << (int)mavlink_address.system_id << '/'
×
535
                           << (int)mavlink_address.component_id << " to: " << (int)_target_system_id
×
536
                           << '/' << (int)_target_component_id;
×
537
            }
538

539
            mavlink_msg_param_ext_set_pack_chan(
10✔
540
                mavlink_address.system_id,
5✔
541
                mavlink_address.component_id,
5✔
542
                channel,
543
                &message,
10✔
544
                _target_system_id,
5✔
545
                _target_component_id,
5✔
546
                param_id.data(),
5✔
547
                param_value_buf.data(),
5✔
548
                work_item.param_value.get_mav_param_ext_type());
5✔
549

550
            return message;
5✔
551
        });
5✔
552
    } else {
553
        const float value_set = (_autopilot_callback() == Autopilot::ArduPilot) ?
6✔
554
                                    work_item.param_value.get_4_float_bytes_cast() :
×
555
                                    work_item.param_value.get_4_float_bytes_bytewise();
6✔
556

557
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
12✔
558
            if (_parameter_debugging) {
6✔
559
                LogDebug() << "Sending param_set from:" << (int)mavlink_address.system_id << '/'
×
560
                           << (int)mavlink_address.component_id << " to: " << (int)_target_system_id
×
561
                           << '/' << (int)_target_component_id;
×
562
            }
563
            mavlink_msg_param_set_pack_chan(
12✔
564
                mavlink_address.system_id,
6✔
565
                mavlink_address.component_id,
6✔
566
                channel,
567
                &message,
12✔
568
                _target_system_id,
6✔
569
                _target_component_id,
6✔
570
                param_id.data(),
6✔
571
                value_set,
6✔
572
                work_item.param_value.get_mav_param_type());
6✔
573
            return message;
6✔
574
        });
6✔
575
    }
576
}
577

578
bool MavlinkParameterClient::send_get_param_message(WorkItemGet& work_item)
60✔
579
{
580
    std::array<char, PARAM_ID_LEN> param_id_buff{};
60✔
581
    int16_t param_index = -1;
60✔
582
    if (auto str = std::get_if<std::string>(&work_item.param_identifier)) {
60✔
583
        param_id_buff = param_id_to_message_buffer(*str);
60✔
584
    } else {
585
        // param_id_buff doesn't matter
586
        param_index = std::get<int16_t>(work_item.param_identifier);
×
587
    }
588

589
    return send_get_param_message(param_id_buff, param_index);
60✔
590
}
591

592
bool MavlinkParameterClient::send_get_param_message(
65✔
593
    const std::array<char, PARAM_ID_LEN>& param_id_buff, int16_t param_index)
594
{
595
    mavlink_message_t message;
65✔
596

597
    if (_use_extended) {
65✔
598
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
78✔
599
            if (_parameter_debugging) {
39✔
600
                LogDebug() << "Send param_ext_request_read: " << (int)mavlink_address.system_id
×
601
                           << ":" << (int)mavlink_address.component_id << " to "
×
602
                           << (int)_target_system_id << ":" << (int)_target_component_id;
×
603
            }
604
            mavlink_msg_param_ext_request_read_pack_chan(
78✔
605
                mavlink_address.system_id,
39✔
606
                mavlink_address.component_id,
39✔
607
                channel,
608
                &message,
78✔
609
                _target_system_id,
39✔
610
                _target_component_id,
39✔
611
                param_id_buff.data(),
39✔
612
                param_index);
39✔
613
            return message;
39✔
614
        });
39✔
615

616
    } else {
617
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
52✔
618
            if (_parameter_debugging) {
26✔
619
                LogDebug() << "Send param_request_read: " << (int)mavlink_address.system_id << ":"
×
620
                           << (int)mavlink_address.component_id << " to " << (int)_target_system_id
×
621
                           << ":" << (int)_target_component_id;
×
622
            }
623
            mavlink_msg_param_request_read_pack_chan(
52✔
624
                mavlink_address.system_id,
26✔
625
                mavlink_address.component_id,
26✔
626
                channel,
627
                &message,
52✔
628
                _target_system_id,
26✔
629
                _target_component_id,
26✔
630
                param_id_buff.data(),
26✔
631
                param_index);
26✔
632
            return message;
26✔
633
        });
26✔
634
    }
635
}
636

637
bool MavlinkParameterClient::send_request_list_message()
4✔
638
{
639
    if (_use_extended) {
4✔
640
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
4✔
641
            if (_parameter_debugging) {
2✔
642
                LogDebug() << "Sending param_ext_request_list to:" << (int)mavlink_address.system_id
×
643
                           << ":" << (int)mavlink_address.component_id;
×
644
            }
645
            mavlink_message_t message;
646
            mavlink_msg_param_ext_request_list_pack_chan(
2✔
647
                mavlink_address.system_id,
2✔
648
                mavlink_address.component_id,
2✔
649
                channel,
650
                &message,
651
                _target_system_id,
2✔
652
                _target_component_id);
2✔
653
            return message;
2✔
654
        });
2✔
655
    } else {
656
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
4✔
657
            if (_parameter_debugging) {
2✔
658
                LogDebug() << "Sending param_request_list to:" << (int)mavlink_address.system_id
×
659
                           << ":" << (int)mavlink_address.component_id;
×
660
            }
661
            mavlink_message_t message;
662
            mavlink_msg_param_request_list_pack_chan(
2✔
663
                mavlink_address.system_id,
2✔
664
                mavlink_address.component_id,
2✔
665
                channel,
666
                &message,
667
                _target_system_id,
2✔
668
                _target_component_id);
2✔
669
            return message;
2✔
670
        });
2✔
671
    }
672
}
673

674
void MavlinkParameterClient::process_param_value(const mavlink_message_t& message)
26✔
675
{
676
    mavlink_param_value_t param_value;
26✔
677
    mavlink_msg_param_value_decode(&message, &param_value);
26✔
678
    const std::string safe_param_id = extract_safe_param_id(param_value.param_id);
26✔
679
    if (safe_param_id.empty()) {
26✔
680
        LogWarn() << "Got ill-formed param_value message (param_id empty)";
×
681
        return;
×
682
    }
683

684
    ParamValue received_value;
26✔
685
    const bool set_value_success = received_value.set_from_mavlink_param_value(
26✔
686
        param_value,
687
        (_autopilot_callback() == Autopilot::ArduPilot) ? ParamValue::Conversion::Cast :
26✔
688
                                                          ParamValue::Conversion::Bitwise);
26✔
689
    if (!set_value_success) {
26✔
690
        LogWarn() << "Got ill-formed param_ext_value message (param_type unknown)";
×
691
        return;
×
692
    }
693

694
    if (_parameter_debugging) {
26✔
695
        LogDebug() << "process_param_value: " << safe_param_id << " " << received_value
×
696
                   << ", index: " << param_value.param_index;
×
697
    }
698

699
    if (param_value.param_index == std::numeric_limits<uint16_t>::max() &&
26✔
700
        safe_param_id == "_HASH_CHECK") {
×
701
        // Ignore PX4's _HASH_CHECK param.
702
        return;
×
703
    }
704

705
    // We need to use a unique pointer here to remove the lock from the work queue manually "early"
706
    // before calling the (perhaps user-provided) callback. Otherwise, we might end up in a deadlock
707
    // if the callback wants to push another work item onto the queue. By using a unique ptr there
708
    // is no risk of forgetting to remove the lock - it is destroyed (if still valid) after going
709
    // out of scope.
710
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
26✔
711
    const auto work = work_queue_guard->get_front();
26✔
712

713
    if (!work) {
26✔
714
        // Prevent deadlock by releasing the lock before doing more work.
715
        work_queue_guard.reset();
×
716
        // update existing param
717
        find_and_call_subscriptions_value_changed(safe_param_id, received_value);
×
718
        return;
×
719
    }
720

721
    if (!work->already_requested) {
26✔
722
        return;
×
723
    }
724

725
    std::visit(
52✔
726
        overloaded{
26✔
727
            [&](WorkItemSet& item) {
4✔
728
                if (item.param_name != safe_param_id) {
4✔
729
                    // No match, let's just return the borrowed work item.
730
                    return;
×
731
                }
732

733
                if (_parameter_debugging) {
4✔
734
                    LogDebug() << "Item value is: " << item.param_value
×
735
                               << ", received: " << received_value;
×
736
                }
737

738
                if (!item.param_value.is_same_type(received_value)) {
4✔
739
                    LogErr() << "Wrong type in param set";
×
740
                    _timeout_handler.remove(_timeout_cookie);
×
741
                    work_queue_guard->pop_front();
×
742
                    if (item.callback) {
×
743
                        auto callback = item.callback;
×
744
                        work_queue_guard.reset();
×
745
                        callback(MavlinkParameterClient::Result::WrongType);
×
746
                    }
×
747
                    return;
×
748
                }
749

750
                if (item.param_value == received_value) {
4✔
751
                    // This was successful. Inform the caller.
752
                    _timeout_handler.remove(_timeout_cookie);
4✔
753
                    // LogDebug() << "time taken: " <<
754
                    // _sender.get_time().elapsed_since_s(_last_request_time);
755
                    work_queue_guard->pop_front();
4✔
756
                    if (item.callback) {
4✔
757
                        auto callback = item.callback;
4✔
758
                        work_queue_guard.reset();
4✔
759
                        callback(MavlinkParameterClient::Result::Success);
4✔
760
                    }
4✔
761
                } else {
762
                    // We might be receiving stale param_value messages, let's just
763
                    // try again. This can happen if the timeout is chosen low and we
764
                    // get out of sync when doing a param_get just before the param_set.
765
                    // In that case we have stale param_value messages in flux and
766
                    // receive them here.
767
                    if (work->retries_to_do > 0) {
×
768
                        LogWarn() << "sending again, retries to do: " << work->retries_to_do
×
769
                                  << "  (" << item.param_name << ").";
×
770

771
                        if (!send_set_param_message(item)) {
×
772
                            LogErr() << "connection send error in retransmit (" << item.param_name
×
773
                                     << ").";
×
774
                            work_queue_guard->pop_front();
×
775

776
                            if (item.callback) {
×
777
                                auto callback = item.callback;
×
778
                                work_queue_guard.reset();
×
779
                                callback(Result::ConnectionError);
×
780
                            }
×
781
                            _timeout_handler.refresh(_timeout_cookie);
×
782
                        } else {
783
                            --work->retries_to_do;
×
784
                            _timeout_handler.refresh(_timeout_cookie);
×
785
                        }
786
                    } else {
787
                        // We have tried retransmitting, giving up now.
788
                        LogErr() << "Error: Retrying failed set param failed: " << item.param_name;
×
789
                        work_queue_guard->pop_front();
×
790
                        if (item.callback) {
×
791
                            auto callback = item.callback;
×
792
                            work_queue_guard.reset();
×
793
                            callback(Result::Timeout);
×
794
                        }
×
795
                    }
796
                }
797
            },
798
            [&](WorkItemGet& item) {
10✔
799
                if (!validate_id_or_index(
10✔
800
                        item.param_identifier,
10✔
801
                        safe_param_id,
10✔
802
                        static_cast<int16_t>(param_value.param_index))) {
10✔
803
                    LogWarn() << "Got unexpected response on work item";
×
804
                    // No match, let's just return the borrowed work item.
805
                    return;
×
806
                }
807
                _timeout_handler.remove(_timeout_cookie);
10✔
808
                // LogDebug() << "time taken: " <<
809
                // _sender.get_time().elapsed_since_s(_last_request_time);
810
                work_queue_guard->pop_front();
10✔
811
                if (item.callback) {
10✔
812
                    auto callback = item.callback;
10✔
813
                    work_queue_guard.reset();
10✔
814
                    callback(Result::Success, received_value);
10✔
815
                }
10✔
816
            },
817
            [&](WorkItemGetAll& item) {
12✔
818
                auto maybe_current_missing_index = _param_cache.last_missing_requested();
12✔
819

820
                switch (_param_cache.add_new_param(
12✔
821
                    safe_param_id, received_value, param_value.param_index)) {
12✔
822
                    case MavlinkParameterCache::AddNewParamResult::AlreadyExists:
12✔
823
                        // FALLTHROUGH
824
                        // We don't care if it already exists, just overwrite it and carry on.
825
                        // The reason is that this can likely happen if the very first
826
                        // request_list is sent twice and hence we get a bunch of duplicate
827
                        // params.
828
                    case MavlinkParameterCache::AddNewParamResult::Ok:
829

830
                        if (item.count != param_value.param_count) {
12✔
831
                            item.count = param_value.param_count;
2✔
832
                            if (_parameter_debugging) {
2✔
833
                                LogDebug() << "Count is now " << item.count;
×
834
                            }
835
                        }
836

837
                        if (_parameter_debugging) {
12✔
838
                            LogDebug() << "Received param: " << param_value.param_index;
×
839
                        }
840

841
                        if (_param_cache.count(_use_extended) == param_value.param_count) {
12✔
842
                            _timeout_handler.remove(_timeout_cookie);
2✔
843
                            if (_parameter_debugging) {
2✔
844
                                LogDebug() << "Getting all parameters complete: "
×
845
                                           << (_use_extended ? "extended" : "not extended");
×
846
                            }
847
                            work_queue_guard->pop_front();
2✔
848
                            if (item.callback) {
2✔
849
                                auto callback = item.callback;
2✔
850
                                work_queue_guard.reset();
2✔
851
                                callback(
4✔
852
                                    Result::Success,
853
                                    _param_cache.all_parameters_map(_use_extended));
4✔
854
                            }
2✔
855
                        } else {
856
                            if (_parameter_debugging) {
10✔
857
                                LogDebug() << "Received " << _param_cache.count(_use_extended)
×
858
                                           << " of " << param_value.param_count;
×
859
                            }
860
                            if (item.rerequesting) {
10✔
861
                                if (maybe_current_missing_index == param_value.param_index) {
×
862
                                    // Looks like the last one of the previous retransmission chunk
863
                                    // was done, start another one.
864
                                    if (!request_next_missing(item.count)) {
×
865
                                        work_queue_guard->pop_front();
×
866
                                        if (item.callback) {
×
867
                                            auto callback = item.callback;
×
868
                                            work_queue_guard.reset();
×
869
                                            callback(Result::ConnectionError, {});
×
870
                                        }
×
871
                                        return;
×
872
                                    }
873
                                }
874
                            } else {
875
                                // update the timeout handler, messages are still coming in.
876
                            }
877
                            _timeout_handler.refresh(_timeout_cookie);
10✔
878
                        }
879
                        break;
12✔
880
                    case MavlinkParameterCache::AddNewParamResult::TooManyParams:
×
881
                        // We shouldn't be able to get here as the incoming type is only an
882
                        // uint16_t.
883
                        LogErr() << "Too many params received";
×
884
                        assert(false);
×
885
                        break;
886
                    default:
×
887
                        LogErr() << "Unknown AddNewParamResult";
×
888
                        assert(false);
×
889
                        break;
890
                }
891
            }},
892
        work->work_item_variant);
26✔
893
}
26✔
894

895
void MavlinkParameterClient::process_param_ext_value(const mavlink_message_t& message)
67✔
896
{
897
    mavlink_param_ext_value_t param_ext_value;
67✔
898
    mavlink_msg_param_ext_value_decode(&message, &param_ext_value);
67✔
899
    const auto safe_param_id = extract_safe_param_id(param_ext_value.param_id);
67✔
900
    if (safe_param_id.empty()) {
67✔
901
        LogWarn() << "Got ill-formed param_ext_value message (param_id empty)";
×
902
        return;
×
903
    }
904
    ParamValue received_value;
67✔
905
    if (!received_value.set_from_mavlink_param_ext_value(param_ext_value)) {
67✔
906
        LogWarn() << "Got ill-formed param_ext_value message (param_type unknown)";
×
907
        return;
×
908
    }
909

910
    if (_parameter_debugging) {
67✔
911
        LogDebug() << "process param_ext_value: " << safe_param_id << " " << received_value;
×
912
    }
913

914
    // See comments on process_param_value for use of unique_ptr
915
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
67✔
916
    auto work = work_queue_guard->get_front();
67✔
917

918
    if (!work) {
67✔
919
        // Prevent deadlock by releasing the lock before doing more work.
920
        work_queue_guard.reset();
13✔
921
        // update existing param
922
        find_and_call_subscriptions_value_changed(safe_param_id, received_value);
13✔
923
        return;
13✔
924
    }
925

926
    if (!work->already_requested) {
54✔
927
        return;
×
928
    }
929

930
    std::visit(
108✔
931
        overloaded{
54✔
932
            [&](WorkItemSet&) {
×
933
                if (_parameter_debugging) {
×
934
                    LogDebug() << "Unexpected ParamExtValue response.";
×
935
                }
936
            },
×
937
            [&](WorkItemGet& item) {
36✔
938
                if (!validate_id_or_index(
36✔
939
                        item.param_identifier,
36✔
940
                        safe_param_id,
36✔
941
                        static_cast<int16_t>(param_ext_value.param_index))) {
36✔
942
                    LogWarn() << "Got unexpected response on work item";
×
943
                    // No match, let's just return the borrowed work item.
944
                    return;
×
945
                }
946
                _timeout_handler.remove(_timeout_cookie);
36✔
947
                // LogDebug() << "time taken: " <<
948
                // _sender.get_time().elapsed_since_s(_last_request_time);
949
                work_queue_guard->pop_front();
36✔
950
                if (item.callback) {
36✔
951
                    auto callback = item.callback;
36✔
952
                    work_queue_guard.reset();
36✔
953
                    callback(Result::Success, received_value);
36✔
954
                }
36✔
955
            },
956
            [&](WorkItemGetAll& item) {
18✔
957
                switch (_param_cache.add_new_param(
18✔
958
                    safe_param_id, received_value, param_ext_value.param_index)) {
18✔
959
                    case MavlinkParameterCache::AddNewParamResult::AlreadyExists:
18✔
960
                        // PASSTHROUGH.
961
                    case MavlinkParameterCache::AddNewParamResult::Ok:
962
                        item.count = param_ext_value.param_count;
18✔
963
                        if (_parameter_debugging) {
18✔
964
                            LogDebug() << "Count is now " << item.count;
×
965
                        }
966

967
                        if (_param_cache.count(_use_extended) == param_ext_value.param_count) {
18✔
968
                            _timeout_handler.remove(_timeout_cookie);
2✔
969
                            if (_parameter_debugging) {
2✔
970
                                LogDebug() << "Getting all parameters complete: "
×
971
                                           << (_use_extended ? "extended" : "not extended");
×
972
                            }
973
                            work_queue_guard->pop_front();
2✔
974
                            if (item.callback) {
2✔
975
                                auto callback = item.callback;
2✔
976
                                work_queue_guard.reset();
2✔
977
                                callback(
4✔
978
                                    Result::Success,
979
                                    _param_cache.all_parameters_map(_use_extended));
4✔
980
                            }
2✔
981
                        } else {
982
                            if (_parameter_debugging) {
16✔
983
                                LogDebug() << "Received " << _param_cache.count(_use_extended)
×
984
                                           << " of " << param_ext_value.param_count;
×
985
                            }
986
                            // update the timeout handler, messages are still coming in.
987
                            _timeout_handler.refresh(_timeout_cookie);
16✔
988
                        }
989
                        break;
18✔
990
                    case MavlinkParameterCache::AddNewParamResult::TooManyParams:
×
991
                        // We shouldn't be able to get here as the incoming type is only an
992
                        // uint16_t.
993
                        LogErr() << "Too many params received";
×
994
                        assert(false);
×
995
                        break;
996
                    default:
×
997
                        LogErr() << "Unknown AddNewParamResult";
×
998
                        assert(false);
×
999
                        break;
1000
                }
1001
            },
18✔
1002
        },
1003
        work->work_item_variant);
54✔
1004
}
106✔
1005

1006
void MavlinkParameterClient::process_param_ext_ack(const mavlink_message_t& message)
5✔
1007
{
1008
    mavlink_param_ext_ack_t param_ext_ack;
5✔
1009
    mavlink_msg_param_ext_ack_decode(&message, &param_ext_ack);
5✔
1010
    const auto safe_param_id = extract_safe_param_id(param_ext_ack.param_id);
5✔
1011

1012
    if (_parameter_debugging) {
5✔
1013
        LogDebug() << "process param_ext_ack: " << safe_param_id << " "
×
1014
                   << (int)param_ext_ack.param_result;
×
1015
    }
1016

1017
    // See comments on process_param_value for use of unique_ptr
1018
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
5✔
1019
    auto work = work_queue_guard->get_front();
5✔
1020
    if (!work) {
5✔
1021
        return;
×
1022
    }
1023
    if (!work->already_requested) {
5✔
1024
        return;
×
1025
    }
1026

1027
    std::visit(
10✔
1028
        overloaded{
5✔
1029
            [&](WorkItemSet& item) {
5✔
1030
                if (item.param_name != safe_param_id) {
5✔
1031
                    // No match, let's just return the borrowed work item.
1032
                    return;
×
1033
                }
1034
                if (param_ext_ack.param_result == PARAM_ACK_ACCEPTED) {
5✔
1035
                    _timeout_handler.remove(_timeout_cookie);
5✔
1036
                    // LogDebug() << "time taken: " <<
1037
                    // _sender.get_time().elapsed_since_s(_last_request_time);
1038
                    work_queue_guard->pop_front();
5✔
1039
                    if (item.callback) {
5✔
1040
                        auto callback = item.callback;
5✔
1041
                        // We are done, inform caller and go back to idle
1042
                        work_queue_guard.reset();
5✔
1043
                        callback(Result::Success);
5✔
1044
                    }
5✔
1045
                } else if (param_ext_ack.param_result == PARAM_ACK_IN_PROGRESS) {
×
1046
                    // Reset timeout and wait again.
1047
                    _timeout_handler.refresh(_timeout_cookie);
×
1048

1049
                } else {
1050
                    LogWarn() << "Somehow we did not get an ack, we got: "
×
1051
                              << int(param_ext_ack.param_result);
×
1052
                    _timeout_handler.remove(_timeout_cookie);
×
1053
                    // LogDebug() << "time taken: " <<
1054
                    // _sender.get_time().elapsed_since_s(_last_request_time);
1055
                    work_queue_guard->pop_front();
×
1056
                    work_queue_guard.reset();
×
1057
                    if (item.callback) {
×
1058
                        auto callback = item.callback;
×
1059
                        auto result = [&]() {
×
1060
                            switch (param_ext_ack.param_result) {
×
1061
                                case PARAM_ACK_FAILED:
×
1062
                                    return Result::Failed;
×
1063
                                case PARAM_ACK_VALUE_UNSUPPORTED:
×
1064
                                    return Result::ValueUnsupported;
×
1065
                                default:
×
1066
                                    return Result::UnknownError;
×
1067
                            }
1068
                        }();
×
1069
                        work_queue_guard.reset();
×
1070
                        callback(result);
×
1071
                    }
×
1072
                }
1073
            },
1074
            [&](WorkItemGet&) { LogWarn() << "Unexpected ParamExtAck response."; },
×
1075
            [&](WorkItemGetAll&) { LogWarn() << "Unexpected ParamExtAck response."; }},
×
1076
        work->work_item_variant);
5✔
1077
}
5✔
1078

1079
void MavlinkParameterClient::receive_timeout()
20✔
1080
{
1081
    // See comments on process_param_value for use of unique_ptr
1082
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
20✔
1083

1084
    auto work = work_queue_guard->get_front();
20✔
1085
    if (!work) {
20✔
1086
        LogErr() << "Received timeout without work";
×
1087
        return;
×
1088
    }
1089
    if (!work->already_requested) {
20✔
1090
        LogErr() << "Received timeout without already having work requested";
×
1091
        return;
×
1092
    }
1093

1094
    std::visit(
40✔
1095
        overloaded{
20✔
1096
            [&](WorkItemSet& item) {
2✔
1097
                if (work->retries_to_do > 0) {
2✔
1098
                    // We're not sure the command arrived, let's retransmit.
1099
                    LogWarn() << "sending again, retries to do: " << work->retries_to_do << "  ("
4✔
1100
                              << item.param_name << ").";
4✔
1101

1102
                    if (!send_set_param_message(item)) {
2✔
1103
                        LogErr() << "connection send error in retransmit (" << item.param_name
×
1104
                                 << ").";
×
1105
                        work_queue_guard->pop_front();
×
1106

1107
                        if (item.callback) {
×
1108
                            auto callback = item.callback;
×
1109
                            work_queue_guard.reset();
×
1110
                            callback(Result::ConnectionError);
×
1111
                        }
×
1112
                    } else {
1113
                        --work->retries_to_do;
2✔
1114
                        _timeout_cookie = _timeout_handler.add(
2✔
1115
                            [this] { receive_timeout(); }, _timeout_s_callback());
×
1116
                    }
1117
                } else {
1118
                    // We have tried retransmitting, giving up now.
1119
                    LogErr() << "Error: Retrying failed set param timeout: " << item.param_name;
×
1120
                    work_queue_guard->pop_front();
×
1121
                    if (item.callback) {
×
1122
                        auto callback = item.callback;
×
1123
                        work_queue_guard.reset();
×
1124
                        callback(Result::Timeout);
×
1125
                    }
×
1126
                }
1127
            },
2✔
1128
            [&](WorkItemGet& item) {
14✔
1129
                if (work->retries_to_do > 0) {
14✔
1130
                    // We're not sure the command arrived, let's retransmit.
1131
                    LogWarn() << "sending again, retries to do: " << work->retries_to_do;
12✔
1132
                    if (!send_get_param_message(item)) {
12✔
1133
                        LogErr() << "connection send error in retransmit ";
×
1134
                        work_queue_guard->pop_front();
×
1135
                        if (item.callback) {
×
1136
                            auto callback = item.callback;
×
1137
                            work_queue_guard.reset();
×
1138
                            callback(Result::ConnectionError, {});
×
1139
                        }
×
1140
                    } else {
1141
                        --work->retries_to_do;
12✔
1142
                        _timeout_cookie = _timeout_handler.add(
12✔
1143
                            [this] { receive_timeout(); }, _timeout_s_callback());
10✔
1144
                    }
1145
                } else {
1146
                    // We have tried retransmitting, giving up now.
1147
                    LogErr() << "retrying failed";
2✔
1148
                    work_queue_guard->pop_front();
2✔
1149
                    if (item.callback) {
2✔
1150
                        auto callback = item.callback;
2✔
1151
                        work_queue_guard.reset();
2✔
1152
                        callback(Result::Timeout, {});
2✔
1153
                    }
2✔
1154
                }
1155
            },
14✔
1156
            [&](WorkItemGetAll& item) {
4✔
1157
                // Request missing parameters.
1158
                // If retries are exceeded, give up with timeout.
1159

1160
                if (_parameter_debugging) {
4✔
1161
                    LogDebug() << "All params receive timeout with";
×
1162
                }
1163

1164
                if (item.count == 0) {
4✔
1165
                    // We got 0 messages back from the server (param count unknown). Most likely the
1166
                    // "list request" got lost before making it to the server,
1167
                    if (work->retries_to_do > 0) {
×
1168
                        --work->retries_to_do;
×
1169

1170
                        if (!send_request_list_message()) {
×
1171
                            LogErr() << "Send message failed";
×
1172
                            work_queue_guard->pop_front();
×
1173
                            if (item.callback) {
×
1174
                                auto callback = item.callback;
×
1175
                                work_queue_guard.reset();
×
NEW
1176
                                callback(Result::ConnectionError, {});
×
1177
                            }
×
1178
                            return;
×
1179
                        }
1180

1181
                        // We want to get notified if a timeout happens.
1182
                        _timeout_cookie = _timeout_handler.add(
×
1183
                            [this] { receive_timeout(); },
×
1184
                            _timeout_s_callback() * _get_all_timeout_factor);
×
1185
                    } else {
1186
                        if (item.callback) {
×
1187
                            auto callback = item.callback;
×
1188
                            work_queue_guard.reset();
×
NEW
1189
                            callback(Result::Timeout, {});
×
1190
                        }
×
1191
                        return;
×
1192
                    }
1193

1194
                } else {
1195
                    item.rerequesting = true;
4✔
1196

1197
                    LogInfo() << "Requesting " << _param_cache.missing_count(item.count) << " of "
12✔
1198
                              << item.count << " parameters missed during initial burst.";
12✔
1199

1200
                    if (_parameter_debugging) {
4✔
1201
                        _param_cache.print_missing(item.count);
×
1202
                    }
1203

1204
                    // To speed retransmissions up, we request params in chunks, otherwise the
1205
                    // latency back and forth makes this quite slow.
1206
                    if (!request_next_missing(item.count)) {
4✔
1207
                        work_queue_guard->pop_front();
×
1208
                        if (item.callback) {
×
1209
                            auto callback = item.callback;
×
1210
                            work_queue_guard.reset();
×
1211
                            callback(Result::ConnectionError, {});
×
1212
                        }
×
1213
                        return;
×
1214
                    }
1215

1216
                    _timeout_cookie =
4✔
1217
                        _timeout_handler.add([this] { receive_timeout(); }, _timeout_s_callback());
10✔
1218
                }
1219
            }},
1220
        work->work_item_variant);
20✔
1221
}
20✔
1222

1223
bool MavlinkParameterClient::request_next_missing(uint16_t count)
4✔
1224
{
1225
    // Requesting 10 at a time seems to work on SiK radios.
1226
    const uint16_t chunk_size = 10;
4✔
1227

1228
    auto next_missing_indices = _param_cache.next_missing_indices(count, chunk_size);
4✔
1229
    if (next_missing_indices.empty()) {
4✔
1230
        LogErr() << "logic error, there should a missing index";
×
1231
        return false;
×
1232
    }
1233

1234
    for (auto next_missing_index : next_missing_indices) {
9✔
1235
        if (_parameter_debugging) {
5✔
1236
            LogDebug() << "Requesting missing parameter " << (int)next_missing_index;
×
1237
        }
1238

1239
        std::array<char, PARAM_ID_LEN> param_id_buff{};
5✔
1240

1241
        if (!send_get_param_message(param_id_buff, next_missing_index)) {
5✔
1242
            LogErr() << "Send message failed";
×
1243
            return false;
×
1244
        }
1245
    }
1246
    return true;
4✔
1247
}
4✔
1248

1249
std::ostream& operator<<(std::ostream& str, const MavlinkParameterClient::Result& result)
×
1250
{
1251
    switch (result) {
×
1252
        case MavlinkParameterClient::Result::Success:
×
1253
            return str << "Success";
×
1254
        case MavlinkParameterClient::Result::Timeout:
×
1255
            return str << "Timeout";
×
1256
        case MavlinkParameterClient::Result::ConnectionError:
×
1257
            return str << "ConnectionError";
×
1258
        case MavlinkParameterClient::Result::WrongType:
×
1259
            return str << "WrongType";
×
1260
        case MavlinkParameterClient::Result::ParamNameTooLong:
×
1261
            return str << "ParamNameTooLong";
×
1262
        case MavlinkParameterClient::Result::NotFound:
×
1263
            return str << "NotFound";
×
1264
        case MavlinkParameterClient::Result::ValueUnsupported:
×
1265
            return str << "ValueUnsupported";
×
1266
        case MavlinkParameterClient::Result::Failed:
×
1267
            return str << "Failed";
×
1268
        case MavlinkParameterClient::Result::UnknownError:
×
1269
            // Fallthrough
1270
        default:
1271
            return str << "UnknownError";
×
1272
    }
1273
}
1274

1275
bool MavlinkParameterClient::validate_id_or_index(
46✔
1276
    const std::variant<std::string, int16_t>& original,
1277
    const std::string& param_id,
1278
    const int16_t param_index)
1279
{
1280
    if (const auto str = std::get_if<std::string>(&original)) {
46✔
1281
        if (param_id != *str) {
46✔
1282
            // We requested by string id, but response doesn't match
1283
            return false;
×
1284
        }
1285
    } else {
1286
        const auto tmp = std::get<int16_t>(original);
×
1287
        if (param_index != tmp) {
×
1288
            // We requested by index, but response doesn't match
1289
            return false;
×
1290
        }
1291
    }
1292
    return true;
46✔
1293
}
1294

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