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

mavlink / MAVSDK / 18289523387

06 Oct 2025 05:41PM UTC coverage: 47.597% (+0.02%) from 47.58%
18289523387

push

github

web-flow
Merge pull request #2667 from irajkovic/fix-mission-progress-total

Fix updating mission item total

4 of 8 new or added lines in 1 file covered. (50.0%)

23 existing lines in 7 files now uncovered.

17035 of 35790 relevant lines covered (47.6%)

452.46 hits per line

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

58.52
/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);
9✔
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);
48✔
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
    };
32✔
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) {
27✔
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
    };
5✔
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
    get_param_float_async(
5✔
366
        name,
367
        [&prom](Result result, float value) { prom.set_value(std::make_pair<>(result, value)); },
5✔
368
        this);
369
    return res.get();
5✔
370
}
5✔
371

372
std::pair<MavlinkParameterClient::Result, std::string>
373
MavlinkParameterClient::get_param_custom(const std::string& name)
4✔
374
{
375
    auto prom = std::promise<std::pair<Result, std::string>>();
4✔
376
    auto res = prom.get_future();
4✔
377
    get_param_custom_async(
4✔
378
        name,
379
        [&prom](Result result, const std::string& value) {
4✔
380
            prom.set_value(std::make_pair<>(result, value));
4✔
381
        },
4✔
382
        this);
383
    return res.get();
4✔
384
}
4✔
385

386
void MavlinkParameterClient::get_all_params_async(GetAllParamsCallback callback, void* cookie)
4✔
387
{
388
    if (_parameter_debugging) {
4✔
389
        LogDebug() << "Getting all params, extended: " << (_use_extended ? "yes" : "no");
×
390
    }
391

392
    auto new_work =
393
        std::make_shared<WorkItem>(WorkItemGetAll{std::move(callback), 0, false}, cookie);
4✔
394
    _work_queue.push_back(new_work);
4✔
395
}
4✔
396

397
std::pair<MavlinkParameterClient::Result, std::map<std::string, ParamValue>>
398
MavlinkParameterClient::get_all_params()
4✔
399
{
400
    std::promise<std::pair<MavlinkParameterClient::Result, std::map<std::string, ParamValue>>> prom;
4✔
401
    auto res = prom.get_future();
4✔
402
    get_all_params_async(
4✔
403
        // Make sure to NOT use a reference for all_params here, pass by value.
404
        // Since for example on a timeout, the empty all_params result is constructed in-place and
405
        // then goes out of scope when the callback returns.
406
        [&prom](Result result, std::map<std::string, ParamValue> set) {
4✔
407
            prom.set_value({result, std::move(set)});
4✔
408
        },
4✔
409
        this);
410
    auto ret = res.get();
4✔
411
    return ret;
4✔
412
}
4✔
413

414
void MavlinkParameterClient::cancel_all_param(const void* cookie)
×
415
{
416
    LockedQueue<WorkItem>::Guard work_queue_guard(_work_queue);
×
417

418
    // We don't call any callbacks before erasing them as this is just used on destruction
419
    // where we don't care anymore.
420
    _work_queue.erase(std::remove_if(_work_queue.begin(), _work_queue.end(), [&](auto&& item) {
×
421
        return (item->cookie == cookie);
×
422
    }));
423
}
×
424

425
void MavlinkParameterClient::clear_cache()
52✔
426
{
427
    _param_cache.clear();
52✔
428
}
52✔
429

430
void MavlinkParameterClient::do_work()
938✔
431
{
432
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
938✔
433
    auto work = work_queue_guard->get_front();
938✔
434

435
    if (!work) {
938✔
436
        return;
590✔
437
    }
438

439
    if (work->already_requested) {
348✔
440
        return;
287✔
441
    }
442

443
    std::visit(
61✔
444
        overloaded{
122✔
445
            [&](WorkItemSet& item) {
9✔
446
                if (!send_set_param_message(item)) {
9✔
447
                    LogErr() << "Send message failed";
×
448
                    work_queue_guard->pop_front();
×
449
                    if (item.callback) {
×
450
                        auto callback = item.callback;
×
451
                        work_queue_guard.reset();
×
452
                        callback(Result::ConnectionError);
×
453
                    }
×
454
                    return;
×
455
                }
456
                work->already_requested = true;
9✔
457
                // We want to get notified if a timeout happens
458
                _timeout_cookie =
9✔
459
                    _timeout_handler.add([this] { receive_timeout(); }, _timeout_s_callback());
11✔
460
            },
461
            [&](WorkItemGet& item) {
48✔
462
                // We can't rely on the cache as we haven't implemented the hash check.
463
                clear_cache();
48✔
464
                if (!send_get_param_message(item)) {
48✔
465
                    LogErr() << "Send message failed";
×
466
                    work_queue_guard->pop_front();
×
467
                    if (item.callback) {
×
468
                        auto callback = item.callback;
×
469
                        work_queue_guard.reset();
×
470
                        callback(Result::ConnectionError, ParamValue{});
×
471
                    }
×
472
                    return;
×
473
                }
474
                work->already_requested = true;
48✔
475
                // We want to get notified if a timeout happens
476
                _timeout_cookie =
48✔
477
                    _timeout_handler.add([this] { receive_timeout(); }, _timeout_s_callback());
52✔
478
            },
479
            [&](WorkItemGetAll& item) {
4✔
480
                // We can't rely on the cache as we haven't implemented the hash check.
481
                clear_cache();
4✔
482
                if (!send_request_list_message()) {
4✔
483
                    LogErr() << "Send message failed";
×
484
                    work_queue_guard->pop_front();
×
485
                    if (item.callback) {
×
486
                        auto callback = item.callback;
×
487
                        work_queue_guard.reset();
×
488
                        callback(Result::ConnectionError, {});
×
489
                    }
×
490
                    return;
×
491
                }
492
                work->already_requested = true;
4✔
493
                // We want to get notified if a timeout happens
494
                _timeout_cookie = _timeout_handler.add(
4✔
495
                    [this] { receive_timeout(); }, _timeout_s_callback() * _get_all_timeout_factor);
6✔
496
            }},
497
        work->work_item_variant);
61✔
498
}
1,815✔
499

500
bool MavlinkParameterClient::send_set_param_message(WorkItemSet& work_item)
11✔
501
{
502
    auto param_id = param_id_to_message_buffer(work_item.param_name);
11✔
503

504
    mavlink_message_t message;
505
    if (_use_extended) {
11✔
506
        const auto param_value_buf = work_item.param_value.get_128_bytes();
5✔
507
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
10✔
508
            if (_parameter_debugging) {
5✔
509
                LogDebug() << "Sending param_ext_set from:" << (int)mavlink_address.system_id << '/'
×
510
                           << (int)mavlink_address.component_id << " to: " << (int)_target_system_id
×
511
                           << '/' << (int)_target_component_id;
×
512
            }
513

514
            mavlink_msg_param_ext_set_pack_chan(
10✔
515
                mavlink_address.system_id,
5✔
516
                mavlink_address.component_id,
5✔
517
                channel,
518
                &message,
10✔
519
                _target_system_id,
5✔
520
                _target_component_id,
5✔
521
                param_id.data(),
5✔
522
                param_value_buf.data(),
5✔
523
                work_item.param_value.get_mav_param_ext_type());
5✔
524

525
            return message;
5✔
526
        });
5✔
527
    } else {
528
        const float value_set = (_autopilot_callback() == Autopilot::ArduPilot) ?
6✔
529
                                    work_item.param_value.get_4_float_bytes_cast() :
×
530
                                    work_item.param_value.get_4_float_bytes_bytewise();
6✔
531

532
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
12✔
533
            if (_parameter_debugging) {
6✔
534
                LogDebug() << "Sending param_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
            mavlink_msg_param_set_pack_chan(
12✔
539
                mavlink_address.system_id,
6✔
540
                mavlink_address.component_id,
6✔
541
                channel,
542
                &message,
12✔
543
                _target_system_id,
6✔
544
                _target_component_id,
6✔
545
                param_id.data(),
6✔
546
                value_set,
6✔
547
                work_item.param_value.get_mav_param_type());
6✔
548
            return message;
6✔
549
        });
6✔
550
    }
551
}
552

553
bool MavlinkParameterClient::send_get_param_message(WorkItemGet& work_item)
60✔
554
{
555
    std::array<char, PARAM_ID_LEN> param_id_buff{};
60✔
556
    int16_t param_index = -1;
60✔
557
    if (auto str = std::get_if<std::string>(&work_item.param_identifier)) {
60✔
558
        param_id_buff = param_id_to_message_buffer(*str);
60✔
559
    } else {
560
        // param_id_buff doesn't matter
561
        param_index = std::get<int16_t>(work_item.param_identifier);
×
562
    }
563

564
    return send_get_param_message(param_id_buff, param_index);
60✔
565
}
566

567
bool MavlinkParameterClient::send_get_param_message(
65✔
568
    const std::array<char, PARAM_ID_LEN>& param_id_buff, int16_t param_index)
569
{
570
    mavlink_message_t message;
571

572
    if (_use_extended) {
65✔
573
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
80✔
574
            if (_parameter_debugging) {
40✔
575
                LogDebug() << "Send param_ext_request_read: " << (int)mavlink_address.system_id
×
576
                           << ":" << (int)mavlink_address.component_id << " to "
×
577
                           << (int)_target_system_id << ":" << (int)_target_component_id;
×
578
            }
579
            mavlink_msg_param_ext_request_read_pack_chan(
80✔
580
                mavlink_address.system_id,
40✔
581
                mavlink_address.component_id,
40✔
582
                channel,
583
                &message,
80✔
584
                _target_system_id,
40✔
585
                _target_component_id,
40✔
586
                param_id_buff.data(),
40✔
587
                param_index);
40✔
588
            return message;
40✔
589
        });
40✔
590

591
    } else {
592
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
50✔
593
            if (_parameter_debugging) {
25✔
594
                LogDebug() << "Send param_request_read: " << (int)mavlink_address.system_id << ":"
×
595
                           << (int)mavlink_address.component_id << " to " << (int)_target_system_id
×
596
                           << ":" << (int)_target_component_id;
×
597
            }
598
            mavlink_msg_param_request_read_pack_chan(
50✔
599
                mavlink_address.system_id,
25✔
600
                mavlink_address.component_id,
25✔
601
                channel,
602
                &message,
50✔
603
                _target_system_id,
25✔
604
                _target_component_id,
25✔
605
                param_id_buff.data(),
25✔
606
                param_index);
25✔
607
            return message;
25✔
608
        });
25✔
609
    }
610
}
611

612
bool MavlinkParameterClient::send_request_list_message()
4✔
613
{
614
    if (_use_extended) {
4✔
615
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
4✔
616
            if (_parameter_debugging) {
2✔
617
                LogDebug() << "Sending param_ext_request_list to:" << (int)mavlink_address.system_id
×
618
                           << ":" << (int)mavlink_address.component_id;
×
619
            }
620
            mavlink_message_t message;
621
            mavlink_msg_param_ext_request_list_pack_chan(
2✔
622
                mavlink_address.system_id,
2✔
623
                mavlink_address.component_id,
2✔
624
                channel,
625
                &message,
626
                _target_system_id,
2✔
627
                _target_component_id);
2✔
628
            return message;
2✔
629
        });
2✔
630
    } else {
631
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
4✔
632
            if (_parameter_debugging) {
2✔
633
                LogDebug() << "Sending param_request_list to:" << (int)mavlink_address.system_id
×
634
                           << ":" << (int)mavlink_address.component_id;
×
635
            }
636
            mavlink_message_t message;
637
            mavlink_msg_param_request_list_pack_chan(
2✔
638
                mavlink_address.system_id,
2✔
639
                mavlink_address.component_id,
2✔
640
                channel,
641
                &message,
642
                _target_system_id,
2✔
643
                _target_component_id);
2✔
644
            return message;
2✔
645
        });
2✔
646
    }
647
}
648

649
void MavlinkParameterClient::process_param_value(const mavlink_message_t& message)
26✔
650
{
651
    mavlink_param_value_t param_value;
652
    mavlink_msg_param_value_decode(&message, &param_value);
26✔
653
    const std::string safe_param_id = extract_safe_param_id(param_value.param_id);
26✔
654
    if (safe_param_id.empty()) {
26✔
655
        LogWarn() << "Got ill-formed param_value message (param_id empty)";
×
656
        return;
×
657
    }
658

659
    ParamValue received_value;
26✔
660
    const bool set_value_success = received_value.set_from_mavlink_param_value(
26✔
661
        param_value,
662
        (_autopilot_callback() == Autopilot::ArduPilot) ? ParamValue::Conversion::Cast :
26✔
663
                                                          ParamValue::Conversion::Bitwise);
664
    if (!set_value_success) {
26✔
665
        LogWarn() << "Got ill-formed param_ext_value message (param_type unknown)";
×
666
        return;
×
667
    }
668

669
    if (_parameter_debugging) {
26✔
670
        LogDebug() << "process_param_value: " << safe_param_id << " " << received_value
×
671
                   << ", index: " << param_value.param_index;
×
672
    }
673

674
    if (param_value.param_index == std::numeric_limits<uint16_t>::max() &&
26✔
675
        safe_param_id == "_HASH_CHECK") {
×
676
        // Ignore PX4's _HASH_CHECK param.
677
        return;
×
678
    }
679

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

688
    if (!work) {
26✔
689
        // Prevent deadlock by releasing the lock before doing more work.
690
        work_queue_guard.reset();
×
691
        // update existing param
692
        find_and_call_subscriptions_value_changed(safe_param_id, received_value);
×
693
        return;
×
694
    }
695

696
    if (!work->already_requested) {
26✔
697
        return;
×
698
    }
699

700
    std::visit(
26✔
701
        overloaded{
52✔
702
            [&](WorkItemSet& item) {
4✔
703
                if (item.param_name != safe_param_id) {
4✔
704
                    // No match, let's just return the borrowed work item.
705
                    return;
×
706
                }
707

708
                if (_parameter_debugging) {
4✔
709
                    LogDebug() << "Item value is: " << item.param_value
×
710
                               << ", received: " << received_value;
×
711
                }
712

713
                if (!item.param_value.is_same_type(received_value)) {
4✔
714
                    LogErr() << "Wrong type in param set";
×
715
                    _timeout_handler.remove(_timeout_cookie);
×
716
                    work_queue_guard->pop_front();
×
717
                    if (item.callback) {
×
718
                        auto callback = item.callback;
×
719
                        work_queue_guard.reset();
×
720
                        callback(MavlinkParameterClient::Result::WrongType);
×
721
                    }
×
722
                    return;
×
723
                }
724

725
                if (item.param_value == received_value) {
4✔
726
                    // This was successful. Inform the caller.
727
                    _timeout_handler.remove(_timeout_cookie);
4✔
728
                    // LogDebug() << "time taken: " <<
729
                    // _sender.get_time().elapsed_since_s(_last_request_time);
730
                    work_queue_guard->pop_front();
4✔
731
                    if (item.callback) {
4✔
732
                        auto callback = item.callback;
4✔
733
                        work_queue_guard.reset();
4✔
734
                        callback(MavlinkParameterClient::Result::Success);
4✔
735
                    }
4✔
736
                } else {
737
                    // We might be receiving stale param_value messages, let's just
738
                    // try again. This can happen if the timeout is chosen low and we
739
                    // get out of sync when doing a param_get just before the param_set.
740
                    // In that case we have stale param_value messages in flux and
741
                    // receive them here.
742
                    if (work->retries_to_do > 0) {
×
743
                        LogWarn() << "sending again, retries to do: " << work->retries_to_do
×
744
                                  << "  (" << item.param_name << ").";
×
745

746
                        if (!send_set_param_message(item)) {
×
747
                            LogErr() << "connection send error in retransmit (" << item.param_name
×
748
                                     << ").";
×
749
                            work_queue_guard->pop_front();
×
750

751
                            if (item.callback) {
×
752
                                auto callback = item.callback;
×
753
                                work_queue_guard.reset();
×
754
                                callback(Result::ConnectionError);
×
755
                            }
×
756
                            _timeout_handler.refresh(_timeout_cookie);
×
757
                        } else {
758
                            --work->retries_to_do;
×
759
                            _timeout_handler.refresh(_timeout_cookie);
×
760
                        }
761
                    } else {
762
                        // We have tried retransmitting, giving up now.
763
                        LogErr() << "Error: Retrying failed set param failed: " << item.param_name;
×
764
                        work_queue_guard->pop_front();
×
765
                        if (item.callback) {
×
766
                            auto callback = item.callback;
×
767
                            work_queue_guard.reset();
×
768
                            callback(Result::Timeout);
×
769
                        }
×
770
                    }
771
                }
772
            },
773
            [&](WorkItemGet& item) {
10✔
774
                if (!validate_id_or_index(
10✔
775
                        item.param_identifier,
10✔
776
                        safe_param_id,
10✔
777
                        static_cast<int16_t>(param_value.param_index))) {
10✔
778
                    LogWarn() << "Got unexpected response on work item";
×
779
                    // No match, let's just return the borrowed work item.
780
                    return;
×
781
                }
782
                _timeout_handler.remove(_timeout_cookie);
10✔
783
                // LogDebug() << "time taken: " <<
784
                // _sender.get_time().elapsed_since_s(_last_request_time);
785
                work_queue_guard->pop_front();
10✔
786
                if (item.callback) {
10✔
787
                    auto callback = item.callback;
10✔
788
                    work_queue_guard.reset();
10✔
789
                    callback(Result::Success, received_value);
10✔
790
                }
10✔
791
            },
792
            [&](WorkItemGetAll& item) {
12✔
793
                auto maybe_current_missing_index = _param_cache.last_missing_requested();
12✔
794

795
                switch (_param_cache.add_new_param(
12✔
796
                    safe_param_id, received_value, param_value.param_index)) {
12✔
797
                    case MavlinkParameterCache::AddNewParamResult::AlreadyExists:
12✔
798
                        // FALLTHROUGH
799
                        // We don't care if it already exists, just overwrite it and carry on.
800
                        // The reason is that this can likely happen if the very first
801
                        // request_list is sent twice and hence we get a bunch of duplicate
802
                        // params.
803
                    case MavlinkParameterCache::AddNewParamResult::Ok:
804

805
                        if (item.count != param_value.param_count) {
12✔
806
                            item.count = param_value.param_count;
2✔
807
                            if (_parameter_debugging) {
2✔
808
                                LogDebug() << "Count is now " << item.count;
×
809
                            }
810
                        }
811

812
                        if (_parameter_debugging) {
12✔
813
                            LogDebug() << "Received param: " << param_value.param_index;
×
814
                        }
815

816
                        if (_param_cache.count(_use_extended) == param_value.param_count) {
12✔
817
                            _timeout_handler.remove(_timeout_cookie);
2✔
818
                            if (_parameter_debugging) {
2✔
819
                                LogDebug() << "Getting all parameters complete: "
×
820
                                           << (_use_extended ? "extended" : "not extended");
×
821
                            }
822
                            work_queue_guard->pop_front();
2✔
823
                            if (item.callback) {
2✔
824
                                auto callback = item.callback;
2✔
825
                                work_queue_guard.reset();
2✔
826
                                callback(
2✔
827
                                    Result::Success,
828
                                    _param_cache.all_parameters_map(_use_extended));
4✔
829
                            }
2✔
830
                        } else {
831
                            if (_parameter_debugging) {
10✔
832
                                LogDebug() << "Received " << _param_cache.count(_use_extended)
×
833
                                           << " of " << param_value.param_count;
×
834
                            }
835
                            if (item.rerequesting) {
10✔
UNCOV
836
                                if (maybe_current_missing_index == param_value.param_index) {
×
837
                                    // Looks like the last one of the previous retransmission chunk
838
                                    // was done, start another one.
839
                                    if (!request_next_missing(item.count)) {
×
840
                                        work_queue_guard->pop_front();
×
841
                                        if (item.callback) {
×
842
                                            auto callback = item.callback;
×
843
                                            work_queue_guard.reset();
×
844
                                            callback(Result::ConnectionError, {});
×
845
                                        }
×
846
                                        return;
×
847
                                    }
848
                                }
849
                            } else {
850
                                // update the timeout handler, messages are still coming in.
851
                            }
852
                            _timeout_handler.refresh(_timeout_cookie);
10✔
853
                        }
854
                        break;
12✔
855
                    case MavlinkParameterCache::AddNewParamResult::TooManyParams:
×
856
                        // We shouldn't be able to get here as the incoming type is only an
857
                        // uint16_t.
858
                        LogErr() << "Too many params received";
×
859
                        assert(false);
×
860
                        break;
861
                    default:
×
862
                        LogErr() << "Unknown AddNewParamResult";
×
863
                        assert(false);
×
864
                        break;
865
                }
866
            }},
867
        work->work_item_variant);
26✔
868
}
26✔
869

870
void MavlinkParameterClient::process_param_ext_value(const mavlink_message_t& message)
67✔
871
{
872
    mavlink_param_ext_value_t param_ext_value;
873
    mavlink_msg_param_ext_value_decode(&message, &param_ext_value);
67✔
874
    const auto safe_param_id = extract_safe_param_id(param_ext_value.param_id);
67✔
875
    if (safe_param_id.empty()) {
67✔
876
        LogWarn() << "Got ill-formed param_ext_value message (param_id empty)";
×
877
        return;
×
878
    }
879
    ParamValue received_value;
67✔
880
    if (!received_value.set_from_mavlink_param_ext_value(param_ext_value)) {
67✔
881
        LogWarn() << "Got ill-formed param_ext_value message (param_type unknown)";
×
882
        return;
×
883
    }
884

885
    if (_parameter_debugging) {
67✔
886
        LogDebug() << "process param_ext_value: " << safe_param_id << " " << received_value;
×
887
    }
888

889
    // See comments on process_param_value for use of unique_ptr
890
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
67✔
891
    auto work = work_queue_guard->get_front();
67✔
892

893
    if (!work) {
67✔
894
        // Prevent deadlock by releasing the lock before doing more work.
895
        work_queue_guard.reset();
13✔
896
        // update existing param
897
        find_and_call_subscriptions_value_changed(safe_param_id, received_value);
13✔
898
        return;
13✔
899
    }
900

901
    if (!work->already_requested) {
54✔
902
        return;
×
903
    }
904

905
    std::visit(
54✔
906
        overloaded{
108✔
907
            [&](WorkItemSet&) {
×
908
                if (_parameter_debugging) {
×
909
                    LogDebug() << "Unexpected ParamExtValue response.";
×
910
                }
911
            },
×
912
            [&](WorkItemGet& item) {
36✔
913
                if (!validate_id_or_index(
36✔
914
                        item.param_identifier,
36✔
915
                        safe_param_id,
36✔
916
                        static_cast<int16_t>(param_ext_value.param_index))) {
36✔
917
                    LogWarn() << "Got unexpected response on work item";
×
918
                    // No match, let's just return the borrowed work item.
919
                    return;
×
920
                }
921
                _timeout_handler.remove(_timeout_cookie);
36✔
922
                // LogDebug() << "time taken: " <<
923
                // _sender.get_time().elapsed_since_s(_last_request_time);
924
                work_queue_guard->pop_front();
36✔
925
                if (item.callback) {
36✔
926
                    auto callback = item.callback;
36✔
927
                    work_queue_guard.reset();
36✔
928
                    callback(Result::Success, received_value);
36✔
929
                }
36✔
930
            },
931
            [&](WorkItemGetAll& item) {
18✔
932
                switch (_param_cache.add_new_param(
18✔
933
                    safe_param_id, received_value, param_ext_value.param_index)) {
18✔
934
                    case MavlinkParameterCache::AddNewParamResult::AlreadyExists:
18✔
935
                        // PASSTHROUGH.
936
                    case MavlinkParameterCache::AddNewParamResult::Ok:
937
                        item.count = param_ext_value.param_count;
18✔
938
                        if (_parameter_debugging) {
18✔
939
                            LogDebug() << "Count is now " << item.count;
×
940
                        }
941

942
                        if (_param_cache.count(_use_extended) == param_ext_value.param_count) {
18✔
943
                            _timeout_handler.remove(_timeout_cookie);
2✔
944
                            if (_parameter_debugging) {
2✔
945
                                LogDebug() << "Getting all parameters complete: "
×
946
                                           << (_use_extended ? "extended" : "not extended");
×
947
                            }
948
                            work_queue_guard->pop_front();
2✔
949
                            if (item.callback) {
2✔
950
                                auto callback = item.callback;
2✔
951
                                work_queue_guard.reset();
2✔
952
                                callback(
2✔
953
                                    Result::Success,
954
                                    _param_cache.all_parameters_map(_use_extended));
4✔
955
                            }
2✔
956
                        } else {
957
                            if (_parameter_debugging) {
16✔
958
                                LogDebug() << "Received " << _param_cache.count(_use_extended)
×
959
                                           << " of " << param_ext_value.param_count;
×
960
                            }
961
                            // update the timeout handler, messages are still coming in.
962
                            _timeout_handler.refresh(_timeout_cookie);
16✔
963
                        }
964
                        break;
18✔
965
                    case MavlinkParameterCache::AddNewParamResult::TooManyParams:
×
966
                        // We shouldn't be able to get here as the incoming type is only an
967
                        // uint16_t.
968
                        LogErr() << "Too many params received";
×
969
                        assert(false);
×
970
                        break;
971
                    default:
×
972
                        LogErr() << "Unknown AddNewParamResult";
×
973
                        assert(false);
×
974
                        break;
975
                }
976
            },
18✔
977
        },
978
        work->work_item_variant);
54✔
979
}
106✔
980

981
void MavlinkParameterClient::process_param_ext_ack(const mavlink_message_t& message)
5✔
982
{
983
    mavlink_param_ext_ack_t param_ext_ack;
984
    mavlink_msg_param_ext_ack_decode(&message, &param_ext_ack);
5✔
985
    const auto safe_param_id = extract_safe_param_id(param_ext_ack.param_id);
5✔
986

987
    if (_parameter_debugging) {
5✔
988
        LogDebug() << "process param_ext_ack: " << safe_param_id << " "
×
989
                   << (int)param_ext_ack.param_result;
×
990
    }
991

992
    // See comments on process_param_value for use of unique_ptr
993
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
5✔
994
    auto work = work_queue_guard->get_front();
5✔
995
    if (!work) {
5✔
996
        return;
×
997
    }
998
    if (!work->already_requested) {
5✔
999
        return;
×
1000
    }
1001

1002
    std::visit(
5✔
1003
        overloaded{
10✔
1004
            [&](WorkItemSet& item) {
5✔
1005
                if (item.param_name != safe_param_id) {
5✔
1006
                    // No match, let's just return the borrowed work item.
1007
                    return;
×
1008
                }
1009
                if (param_ext_ack.param_result == PARAM_ACK_ACCEPTED) {
5✔
1010
                    _timeout_handler.remove(_timeout_cookie);
5✔
1011
                    // LogDebug() << "time taken: " <<
1012
                    // _sender.get_time().elapsed_since_s(_last_request_time);
1013
                    work_queue_guard->pop_front();
5✔
1014
                    if (item.callback) {
5✔
1015
                        auto callback = item.callback;
5✔
1016
                        // We are done, inform caller and go back to idle
1017
                        work_queue_guard.reset();
5✔
1018
                        callback(Result::Success);
5✔
1019
                    }
5✔
1020
                } else if (param_ext_ack.param_result == PARAM_ACK_IN_PROGRESS) {
×
1021
                    // Reset timeout and wait again.
1022
                    _timeout_handler.refresh(_timeout_cookie);
×
1023

1024
                } else {
1025
                    LogWarn() << "Somehow we did not get an ack, we got: "
×
1026
                              << int(param_ext_ack.param_result);
×
1027
                    _timeout_handler.remove(_timeout_cookie);
×
1028
                    // LogDebug() << "time taken: " <<
1029
                    // _sender.get_time().elapsed_since_s(_last_request_time);
1030
                    work_queue_guard->pop_front();
×
1031
                    work_queue_guard.reset();
×
1032
                    if (item.callback) {
×
1033
                        auto callback = item.callback;
×
1034
                        auto result = [&]() {
×
1035
                            switch (param_ext_ack.param_result) {
×
1036
                                case PARAM_ACK_FAILED:
×
1037
                                    return Result::Failed;
×
1038
                                case PARAM_ACK_VALUE_UNSUPPORTED:
×
1039
                                    return Result::ValueUnsupported;
×
1040
                                default:
×
1041
                                    return Result::UnknownError;
×
1042
                            }
1043
                        }();
×
1044
                        work_queue_guard.reset();
×
1045
                        callback(result);
×
1046
                    }
×
1047
                }
1048
            },
1049
            [&](WorkItemGet&) { LogWarn() << "Unexpected ParamExtAck response."; },
×
1050
            [&](WorkItemGetAll&) { LogWarn() << "Unexpected ParamExtAck response."; }},
×
1051
        work->work_item_variant);
5✔
1052
}
5✔
1053

1054
void MavlinkParameterClient::receive_timeout()
20✔
1055
{
1056
    // See comments on process_param_value for use of unique_ptr
1057
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
20✔
1058

1059
    auto work = work_queue_guard->get_front();
20✔
1060
    if (!work) {
20✔
1061
        LogErr() << "Received timeout without work";
×
1062
        return;
×
1063
    }
1064
    if (!work->already_requested) {
20✔
1065
        LogErr() << "Received timeout without already having work requested";
×
1066
        return;
×
1067
    }
1068

1069
    std::visit(
20✔
1070
        overloaded{
40✔
1071
            [&](WorkItemSet& item) {
2✔
1072
                if (work->retries_to_do > 0) {
2✔
1073
                    // We're not sure the command arrived, let's retransmit.
1074
                    LogWarn() << "sending again, retries to do: " << work->retries_to_do << "  ("
4✔
1075
                              << item.param_name << ").";
2✔
1076

1077
                    if (!send_set_param_message(item)) {
2✔
1078
                        LogErr() << "connection send error in retransmit (" << item.param_name
×
1079
                                 << ").";
×
1080
                        work_queue_guard->pop_front();
×
1081

1082
                        if (item.callback) {
×
1083
                            auto callback = item.callback;
×
1084
                            work_queue_guard.reset();
×
1085
                            callback(Result::ConnectionError);
×
1086
                        }
×
1087
                    } else {
1088
                        --work->retries_to_do;
2✔
1089
                        _timeout_cookie = _timeout_handler.add(
2✔
1090
                            [this] { receive_timeout(); }, _timeout_s_callback());
×
1091
                    }
1092
                } else {
1093
                    // We have tried retransmitting, giving up now.
1094
                    LogErr() << "Error: Retrying failed set param timeout: " << item.param_name;
×
1095
                    work_queue_guard->pop_front();
×
1096
                    if (item.callback) {
×
1097
                        auto callback = item.callback;
×
1098
                        work_queue_guard.reset();
×
1099
                        callback(Result::Timeout);
×
1100
                    }
×
1101
                }
1102
            },
2✔
1103
            [&](WorkItemGet& item) {
14✔
1104
                if (work->retries_to_do > 0) {
14✔
1105
                    // We're not sure the command arrived, let's retransmit.
1106
                    LogWarn() << "sending again, retries to do: " << work->retries_to_do;
12✔
1107
                    if (!send_get_param_message(item)) {
12✔
1108
                        LogErr() << "connection send error in retransmit ";
×
1109
                        work_queue_guard->pop_front();
×
1110
                        if (item.callback) {
×
1111
                            auto callback = item.callback;
×
1112
                            work_queue_guard.reset();
×
1113
                            callback(Result::ConnectionError, {});
×
1114
                        }
×
1115
                    } else {
1116
                        --work->retries_to_do;
12✔
1117
                        _timeout_cookie = _timeout_handler.add(
12✔
1118
                            [this] { receive_timeout(); }, _timeout_s_callback());
10✔
1119
                    }
1120
                } else {
1121
                    // We have tried retransmitting, giving up now.
1122
                    LogErr() << "retrying failed";
2✔
1123
                    work_queue_guard->pop_front();
2✔
1124
                    if (item.callback) {
2✔
1125
                        auto callback = item.callback;
2✔
1126
                        work_queue_guard.reset();
2✔
1127
                        callback(Result::Timeout, {});
2✔
1128
                    }
2✔
1129
                }
1130
            },
14✔
1131
            [&](WorkItemGetAll& item) {
4✔
1132
                // Request missing parameters.
1133
                // If retries are exceeded, give up with timeout.
1134

1135
                if (_parameter_debugging) {
4✔
1136
                    LogDebug() << "All params receive timeout with";
×
1137
                }
1138

1139
                if (item.count == 0) {
4✔
1140
                    // We got 0 messages back from the server (param count unknown). Most likely the
1141
                    // "list request" got lost before making it to the server,
UNCOV
1142
                    if (work->retries_to_do > 0) {
×
UNCOV
1143
                        --work->retries_to_do;
×
1144

UNCOV
1145
                        if (!send_request_list_message()) {
×
1146
                            LogErr() << "Send message failed";
×
1147
                            work_queue_guard->pop_front();
×
1148
                            if (item.callback) {
×
1149
                                auto callback = item.callback;
×
1150
                                work_queue_guard.reset();
×
1151
                                callback(Result::ConnectionError, {});
×
1152
                            }
×
1153
                            return;
×
1154
                        }
1155

1156
                        // We want to get notified if a timeout happens.
UNCOV
1157
                        _timeout_cookie = _timeout_handler.add(
×
UNCOV
1158
                            [this] { receive_timeout(); },
×
UNCOV
1159
                            _timeout_s_callback() * _get_all_timeout_factor);
×
1160
                    } else {
1161
                        if (item.callback) {
×
1162
                            auto callback = item.callback;
×
1163
                            work_queue_guard.reset();
×
1164
                            callback(Result::Timeout, {});
×
1165
                        }
×
1166
                        return;
×
1167
                    }
1168

1169
                } else {
1170
                    item.rerequesting = true;
4✔
1171

1172
                    LogInfo() << "Requesting " << _param_cache.missing_count(item.count) << " of "
8✔
1173
                              << item.count << " parameters missed during initial burst.";
4✔
1174

1175
                    if (_parameter_debugging) {
4✔
1176
                        _param_cache.print_missing(item.count);
×
1177
                    }
1178

1179
                    // To speed retransmissions up, we request params in chunks, otherwise the
1180
                    // latency back and forth makes this quite slow.
1181
                    if (!request_next_missing(item.count)) {
4✔
1182
                        work_queue_guard->pop_front();
×
1183
                        if (item.callback) {
×
1184
                            auto callback = item.callback;
×
1185
                            work_queue_guard.reset();
×
1186
                            callback(Result::ConnectionError, {});
×
1187
                        }
×
1188
                        return;
×
1189
                    }
1190

1191
                    _timeout_cookie =
4✔
1192
                        _timeout_handler.add([this] { receive_timeout(); }, _timeout_s_callback());
6✔
1193
                }
1194
            }},
1195
        work->work_item_variant);
20✔
1196
}
20✔
1197

1198
bool MavlinkParameterClient::request_next_missing(uint16_t count)
4✔
1199
{
1200
    // Requesting 10 at a time seems to work on SiK radios.
1201
    const uint16_t chunk_size = 10;
4✔
1202

1203
    auto next_missing_indices = _param_cache.next_missing_indices(count, chunk_size);
4✔
1204
    if (next_missing_indices.empty()) {
4✔
1205
        LogErr() << "logic error, there should a missing index";
×
1206
        return false;
×
1207
    }
1208

1209
    for (auto next_missing_index : next_missing_indices) {
9✔
1210
        if (_parameter_debugging) {
5✔
1211
            LogDebug() << "Requesting missing parameter " << (int)next_missing_index;
×
1212
        }
1213

1214
        std::array<char, PARAM_ID_LEN> param_id_buff{};
5✔
1215

1216
        if (!send_get_param_message(param_id_buff, next_missing_index)) {
5✔
1217
            LogErr() << "Send message failed";
×
1218
            return false;
×
1219
        }
1220
    }
1221
    return true;
4✔
1222
}
4✔
1223

1224
std::ostream& operator<<(std::ostream& str, const MavlinkParameterClient::Result& result)
×
1225
{
1226
    switch (result) {
×
1227
        case MavlinkParameterClient::Result::Success:
×
1228
            return str << "Success";
×
1229
        case MavlinkParameterClient::Result::Timeout:
×
1230
            return str << "Timeout";
×
1231
        case MavlinkParameterClient::Result::ConnectionError:
×
1232
            return str << "ConnectionError";
×
1233
        case MavlinkParameterClient::Result::WrongType:
×
1234
            return str << "WrongType";
×
1235
        case MavlinkParameterClient::Result::ParamNameTooLong:
×
1236
            return str << "ParamNameTooLong";
×
1237
        case MavlinkParameterClient::Result::NotFound:
×
1238
            return str << "NotFound";
×
1239
        case MavlinkParameterClient::Result::ValueUnsupported:
×
1240
            return str << "ValueUnsupported";
×
1241
        case MavlinkParameterClient::Result::Failed:
×
1242
            return str << "Failed";
×
1243
        case MavlinkParameterClient::Result::UnknownError:
×
1244
            // Fallthrough
1245
        default:
1246
            return str << "UnknownError";
×
1247
    }
1248
}
1249

1250
bool MavlinkParameterClient::validate_id_or_index(
46✔
1251
    const std::variant<std::string, int16_t>& original,
1252
    const std::string& param_id,
1253
    const int16_t param_index)
1254
{
1255
    if (const auto str = std::get_if<std::string>(&original)) {
46✔
1256
        if (param_id != *str) {
46✔
1257
            // We requested by string id, but response doesn't match
1258
            return false;
×
1259
        }
1260
    } else {
1261
        const auto tmp = std::get<int16_t>(original);
×
1262
        if (param_index != tmp) {
×
1263
            // We requested by index, but response doesn't match
1264
            return false;
×
1265
        }
1266
    }
1267
    return true;
46✔
1268
}
1269

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