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

mavlink / MAVSDK / 20513670813

26 Dec 2025 01:20AM UTC coverage: 48.078% (-0.02%) from 48.097%
20513670813

push

github

web-flow
Merge pull request #2744 from mavlink/pr-example-fixup-hz

examples: fixup rate calculation in sniffer

17745 of 36909 relevant lines covered (48.08%)

464.57 hits per line

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

57.34
/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(
12✔
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) :
12✔
22
    _sender(sender),
12✔
23
    _message_handler(message_handler),
12✔
24
    _timeout_handler(timeout_handler),
12✔
25
    _timeout_s_callback(std::move(timeout_s_callback)),
12✔
26
    _autopilot_callback(std::move(autopilot_callback)),
12✔
27
    _target_system_id(target_system_id),
12✔
28
    _target_component_id(target_component_id),
12✔
29
    _use_extended(use_extended)
24✔
30
{
31
    if (const char* env_p = std::getenv("MAVSDK_PARAMETER_DEBUGGING")) {
12✔
32
        if (std::string(env_p) == "1") {
×
33
            LogDebug() << "Parameter debugging is on.";
×
34
            _parameter_debugging = true;
×
35
        }
36
    }
37

38
    if (_parameter_debugging) {
12✔
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) {
12✔
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(
6✔
56
            MAVLINK_MSG_ID_PARAM_VALUE,
57
            [this](const mavlink_message_t& message) { process_param_value(message); },
34✔
58
            this);
59

60
        // PARAM_ERROR is only for standard protocol (not extended)
61
        _message_handler.register_one(
6✔
62
            MAVLINK_MSG_ID_PARAM_ERROR,
63
            [this](const mavlink_message_t& message) { process_param_error(message); },
4✔
64
            this);
65
    }
66
}
12✔
67

68
MavlinkParameterClient::~MavlinkParameterClient()
12✔
69
{
70
    if (_parameter_debugging) {
12✔
71
        LogDebug() << "MavlinkParameterClient destructed for target compid: "
×
72
                   << (int)_target_component_id << " and "
×
73
                   << (_use_extended ? "extended" : "not extended");
×
74
    }
75

76
    _message_handler.unregister_all(this);
12✔
77
}
12✔
78

79
MavlinkParameterClient::Result
80
MavlinkParameterClient::set_param(const std::string& name, const ParamValue& value)
×
81
{
82
    auto prom = std::promise<Result>();
×
83
    auto res = prom.get_future();
×
84
    set_param_async(name, value, [&prom](Result result) { prom.set_value(result); }, this);
×
85
    return res.get();
×
86
}
×
87

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

112
void MavlinkParameterClient::set_param_int_async(
2✔
113
    const std::string& name, int32_t value, const SetParamCallback& callback, const void* cookie)
114
{
115
    if (name.size() > PARAM_ID_LEN) {
2✔
116
        LogErr() << "Param name too long";
×
117
        if (callback) {
×
118
            callback(Result::ParamNameTooLong);
×
119
        }
120
        return;
×
121
    }
122

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

177
MavlinkParameterClient::Result
178
MavlinkParameterClient::set_param_int(const std::string& name, int32_t value)
2✔
179
{
180
    auto prom = std::promise<Result>();
2✔
181
    auto res = prom.get_future();
2✔
182
    set_param_int_async(name, value, [&prom](Result result) { prom.set_value(result); }, this);
4✔
183
    return res.get();
2✔
184
}
2✔
185

186
void MavlinkParameterClient::set_param_float_async(
2✔
187
    const std::string& name, float value, const SetParamCallback& callback, const void* cookie)
188
{
189
    ParamValue value_to_set;
2✔
190
    value_to_set.set_float(value);
2✔
191
    set_param_async(name, value_to_set, callback, cookie);
2✔
192
}
2✔
193

194
MavlinkParameterClient::Result
195
MavlinkParameterClient::set_param_float(const std::string& name, float value)
2✔
196
{
197
    auto prom = std::promise<Result>();
2✔
198
    auto res = prom.get_future();
2✔
199

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

202
    return res.get();
2✔
203
}
2✔
204

205
void MavlinkParameterClient::set_param_custom_async(
2✔
206
    const std::string& name,
207
    const std::string& value,
208
    const SetParamCallback& callback,
209
    const void* cookie)
210
{
211
    if (name.size() > PARAM_ID_LEN) {
2✔
212
        LogErr() << "Param name too long";
×
213
        if (callback) {
×
214
            callback(Result::ParamNameTooLong);
×
215
        }
216
        return;
×
217
    }
218

219
    if (value.size() > sizeof(mavlink_param_ext_set_t::param_value)) {
2✔
220
        LogErr() << "Param value too long";
×
221
        if (callback) {
×
222
            callback(Result::ParamValueTooLong);
×
223
        }
224
        return;
×
225
    }
226
    ParamValue value_to_set;
2✔
227
    value_to_set.set_custom(value);
2✔
228
    set_param_async(name, value_to_set, callback, cookie);
2✔
229
}
2✔
230

231
MavlinkParameterClient::Result
232
MavlinkParameterClient::set_param_custom(const std::string& name, const std::string& value)
2✔
233
{
234
    auto prom = std::promise<Result>();
2✔
235
    auto res = prom.get_future();
2✔
236
    set_param_custom_async(name, value, [&prom](Result result) { prom.set_value(result); }, this);
4✔
237
    return res.get();
2✔
238
}
2✔
239

240
void MavlinkParameterClient::get_param_async(
54✔
241
    const std::string& name, const GetParamAnyCallback& callback, const void* cookie)
242
{
243
    if (_parameter_debugging) {
54✔
244
        LogDebug() << "Getting param " << name << ", extended: " << (_use_extended ? "yes" : "no");
×
245
    }
246
    if (name.size() > PARAM_ID_LEN) {
54✔
247
        LogErr() << "Param name too long";
×
248
        if (callback) {
×
249
            callback(Result::ParamNameTooLong, {});
×
250
        }
251
        return;
×
252
    }
253

254
    auto new_work = std::make_shared<WorkItem>(WorkItemGet{name, callback}, cookie);
54✔
255
    _work_queue.push_back(new_work);
54✔
256
}
54✔
257

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

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

299
template<>
300
void MavlinkParameterClient::get_param_async_typesafe(
8✔
301
    const std::string& name, const GetParamTypesafeCallback<int32_t> callback, const void* cookie)
302
{
303
    // We need to delay the type checking until we get a response from the server.
304
    GetParamAnyCallback callback_future_result = [callback](Result result, ParamValue value) {
8✔
305
        if (result == Result::Success) {
8✔
306
            if (value.is<int32_t>()) {
6✔
307
                callback(Result::Success, value.get<int32_t>());
6✔
308
            } else if (value.is<int16_t>()) {
×
309
                callback(Result::Success, value.get<int16_t>());
×
310
            } else if (value.is<int8_t>()) {
×
311
                callback(Result::Success, value.get<int8_t>());
×
312
            } else {
313
                callback(Result::WrongType, {});
×
314
            }
315
        } else {
316
            callback(result, {});
2✔
317
        }
318
    };
8✔
319
    get_param_async(name, callback_future_result, cookie);
8✔
320
}
8✔
321

322
void MavlinkParameterClient::get_param_float_async(
8✔
323
    const std::string& name, const GetParamFloatCallback& callback, const void* cookie)
324
{
325
    get_param_async_typesafe<float>(name, callback, cookie);
8✔
326
}
8✔
327

328
void MavlinkParameterClient::get_param_int_async(
8✔
329
    const std::string& name, const GetParamIntCallback& callback, const void* cookie)
330
{
331
    get_param_async_typesafe<int32_t>(name, callback, cookie);
8✔
332
}
8✔
333

334
void MavlinkParameterClient::get_param_custom_async(
4✔
335
    const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
336
{
337
    get_param_async_typesafe<std::string>(name, callback, cookie);
4✔
338
}
4✔
339

340
std::pair<MavlinkParameterClient::Result, ParamValue>
341
MavlinkParameterClient::get_param(const std::string& name)
×
342
{
343
    auto prom = std::promise<std::pair<Result, ParamValue>>();
×
344
    auto res = prom.get_future();
×
345
    get_param_async(
×
346
        name,
347
        [&prom](Result result, ParamValue new_value) {
×
348
            prom.set_value(std::make_pair<>(result, std::move(new_value)));
×
349
        },
×
350
        this);
351
    return res.get();
×
352
}
×
353

354
std::pair<MavlinkParameterClient::Result, int32_t>
355
MavlinkParameterClient::get_param_int(const std::string& name)
8✔
356
{
357
    auto prom = std::promise<std::pair<Result, int32_t>>();
8✔
358
    auto res = prom.get_future();
8✔
359
    get_param_int_async(
8✔
360
        name,
361
        [&prom](Result result, int32_t value) { prom.set_value(std::make_pair<>(result, value)); },
8✔
362
        this);
363
    return res.get();
8✔
364
}
8✔
365

366
std::pair<MavlinkParameterClient::Result, float>
367
MavlinkParameterClient::get_param_float(const std::string& name)
8✔
368
{
369
    auto prom = std::promise<std::pair<Result, float>>();
8✔
370
    auto res = prom.get_future();
8✔
371
    get_param_float_async(
8✔
372
        name,
373
        [&prom](Result result, float value) { prom.set_value(std::make_pair<>(result, value)); },
8✔
374
        this);
375
    return res.get();
8✔
376
}
8✔
377

378
std::pair<MavlinkParameterClient::Result, std::string>
379
MavlinkParameterClient::get_param_custom(const std::string& name)
4✔
380
{
381
    auto prom = std::promise<std::pair<Result, std::string>>();
4✔
382
    auto res = prom.get_future();
4✔
383
    get_param_custom_async(
4✔
384
        name,
385
        [&prom](Result result, const std::string& value) {
4✔
386
            prom.set_value(std::make_pair<>(result, value));
4✔
387
        },
4✔
388
        this);
389
    return res.get();
4✔
390
}
4✔
391

392
void MavlinkParameterClient::get_all_params_async(GetAllParamsCallback callback, void* cookie)
5✔
393
{
394
    if (_parameter_debugging) {
5✔
395
        LogDebug() << "Getting all params, extended: " << (_use_extended ? "yes" : "no");
×
396
    }
397

398
    auto new_work =
399
        std::make_shared<WorkItem>(WorkItemGetAll{std::move(callback), 0, false}, cookie);
5✔
400
    _work_queue.push_back(new_work);
5✔
401
}
5✔
402

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

420
void MavlinkParameterClient::cancel_all_param(const void* cookie)
×
421
{
422
    LockedQueue<WorkItem>::Guard work_queue_guard(_work_queue);
×
423

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

431
void MavlinkParameterClient::clear_cache()
59✔
432
{
433
    _param_cache.clear();
59✔
434
}
59✔
435

436
void MavlinkParameterClient::do_work()
926✔
437
{
438
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
926✔
439
    auto work = work_queue_guard->get_front();
926✔
440

441
    if (!work) {
926✔
442
        return;
690✔
443
    }
444

445
    if (work->already_requested) {
236✔
446
        return;
168✔
447
    }
448

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

506
bool MavlinkParameterClient::send_set_param_message(WorkItemSet& work_item)
11✔
507
{
508
    auto param_id = param_id_to_message_buffer(work_item.param_name);
11✔
509

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

520
            mavlink_msg_param_ext_set_pack_chan(
10✔
521
                mavlink_address.system_id,
5✔
522
                mavlink_address.component_id,
5✔
523
                channel,
524
                &message,
10✔
525
                _target_system_id,
5✔
526
                _target_component_id,
5✔
527
                param_id.data(),
5✔
528
                param_value_buf.data(),
5✔
529
                work_item.param_value.get_mav_param_ext_type());
5✔
530

531
            return message;
5✔
532
        });
5✔
533
    } else {
534
        const float value_set = (_autopilot_callback() == Autopilot::ArduPilot) ?
6✔
535
                                    work_item.param_value.get_4_float_bytes_cast() :
×
536
                                    work_item.param_value.get_4_float_bytes_bytewise();
6✔
537

538
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
12✔
539
            if (_parameter_debugging) {
6✔
540
                LogDebug() << "Sending param_set from:" << (int)mavlink_address.system_id << '/'
×
541
                           << (int)mavlink_address.component_id << " to: " << (int)_target_system_id
×
542
                           << '/' << (int)_target_component_id;
×
543
            }
544
            mavlink_msg_param_set_pack_chan(
12✔
545
                mavlink_address.system_id,
6✔
546
                mavlink_address.component_id,
6✔
547
                channel,
548
                &message,
12✔
549
                _target_system_id,
6✔
550
                _target_component_id,
6✔
551
                param_id.data(),
6✔
552
                value_set,
6✔
553
                work_item.param_value.get_mav_param_type());
6✔
554
            return message;
6✔
555
        });
6✔
556
    }
557
}
558

559
bool MavlinkParameterClient::send_get_param_message(WorkItemGet& work_item)
56✔
560
{
561
    std::array<char, PARAM_ID_LEN> param_id_buff{};
56✔
562
    int16_t param_index = -1;
56✔
563
    if (auto str = std::get_if<std::string>(&work_item.param_identifier)) {
56✔
564
        param_id_buff = param_id_to_message_buffer(*str);
56✔
565
    } else {
566
        // param_id_buff doesn't matter
567
        param_index = std::get<int16_t>(work_item.param_identifier);
×
568
    }
569

570
    return send_get_param_message(param_id_buff, param_index);
56✔
571
}
572

573
bool MavlinkParameterClient::send_get_param_message(
61✔
574
    const std::array<char, PARAM_ID_LEN>& param_id_buff, int16_t param_index)
575
{
576
    mavlink_message_t message;
577

578
    if (_use_extended) {
61✔
579
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
80✔
580
            if (_parameter_debugging) {
40✔
581
                LogDebug() << "Send param_ext_request_read: " << (int)mavlink_address.system_id
×
582
                           << ":" << (int)mavlink_address.component_id << " to "
×
583
                           << (int)_target_system_id << ":" << (int)_target_component_id;
×
584
            }
585
            mavlink_msg_param_ext_request_read_pack_chan(
80✔
586
                mavlink_address.system_id,
40✔
587
                mavlink_address.component_id,
40✔
588
                channel,
589
                &message,
80✔
590
                _target_system_id,
40✔
591
                _target_component_id,
40✔
592
                param_id_buff.data(),
40✔
593
                param_index);
40✔
594
            return message;
40✔
595
        });
40✔
596

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

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

655
void MavlinkParameterClient::process_param_value(const mavlink_message_t& message)
34✔
656
{
657
    mavlink_param_value_t param_value;
658
    mavlink_msg_param_value_decode(&message, &param_value);
34✔
659
    const std::string safe_param_id = extract_safe_param_id(param_value.param_id);
34✔
660
    if (safe_param_id.empty()) {
34✔
661
        LogWarn() << "Got ill-formed param_value message (param_id empty)";
×
662
        return;
×
663
    }
664

665
    ParamValue received_value;
34✔
666
    const bool set_value_success = received_value.set_from_mavlink_param_value(
34✔
667
        param_value,
668
        (_autopilot_callback() == Autopilot::ArduPilot) ? ParamValue::Conversion::Cast :
34✔
669
                                                          ParamValue::Conversion::Bitwise);
670
    if (!set_value_success) {
34✔
671
        LogWarn() << "Got ill-formed param_ext_value message (param_type unknown)";
×
672
        return;
×
673
    }
674

675
    if (_parameter_debugging) {
34✔
676
        LogDebug() << "process_param_value: " << safe_param_id << " " << received_value
×
677
                   << ", index: " << param_value.param_index;
×
678
    }
679

680
    if (param_value.param_index == std::numeric_limits<uint16_t>::max() &&
36✔
681
        safe_param_id == "_HASH_CHECK") {
2✔
682
        // Ignore PX4's _HASH_CHECK param.
683
        return;
×
684
    }
685

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

694
    if (!work) {
34✔
695
        // Prevent deadlock by releasing the lock before doing more work.
696
        work_queue_guard.reset();
×
697
        // update existing param
698
        find_and_call_subscriptions_value_changed(safe_param_id, received_value);
×
699
        return;
×
700
    }
701

702
    if (!work->already_requested) {
34✔
703
        return;
1✔
704
    }
705

706
    std::visit(
33✔
707
        overloaded{
66✔
708
            [&](WorkItemSet& item) {
4✔
709
                if (item.param_name != safe_param_id) {
4✔
710
                    // No match, let's just return the borrowed work item.
711
                    return;
×
712
                }
713

714
                if (_parameter_debugging) {
4✔
715
                    LogDebug() << "Item value is: " << item.param_value
×
716
                               << ", received: " << received_value;
×
717
                }
718

719
                if (!item.param_value.is_same_type(received_value)) {
4✔
720
                    LogErr() << "Wrong type in param set";
×
721
                    _timeout_handler.remove(_timeout_cookie);
×
722
                    work_queue_guard->pop_front();
×
723
                    if (item.callback) {
×
724
                        auto callback = item.callback;
×
725
                        work_queue_guard.reset();
×
726
                        callback(MavlinkParameterClient::Result::WrongType);
×
727
                    }
×
728
                    return;
×
729
                }
730

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

752
                        if (!send_set_param_message(item)) {
×
753
                            LogErr() << "connection send error in retransmit (" << item.param_name
×
754
                                     << ").";
×
755
                            work_queue_guard->pop_front();
×
756

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

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

811
                        if (item.count != param_value.param_count) {
14✔
812
                            item.count = param_value.param_count;
3✔
813
                            if (_parameter_debugging) {
3✔
814
                                LogDebug() << "Count is now " << item.count;
×
815
                            }
816
                        }
817

818
                        if (_parameter_debugging) {
14✔
819
                            LogDebug() << "Received param: " << param_value.param_index;
×
820
                        }
821

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

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

891
    if (_parameter_debugging) {
67✔
892
        LogDebug() << "process param_ext_value: " << safe_param_id << " " << received_value;
×
893
    }
894

895
    // See comments on process_param_value for use of unique_ptr
896
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
67✔
897
    auto work = work_queue_guard->get_front();
67✔
898

899
    if (!work) {
67✔
900
        // Prevent deadlock by releasing the lock before doing more work.
901
        work_queue_guard.reset();
13✔
902
        // update existing param
903
        find_and_call_subscriptions_value_changed(safe_param_id, received_value);
13✔
904
        return;
13✔
905
    }
906

907
    if (!work->already_requested) {
54✔
908
        return;
×
909
    }
910

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

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

987
void MavlinkParameterClient::process_param_ext_ack(const mavlink_message_t& message)
5✔
988
{
989
    mavlink_param_ext_ack_t param_ext_ack;
990
    mavlink_msg_param_ext_ack_decode(&message, &param_ext_ack);
5✔
991
    const auto safe_param_id = extract_safe_param_id(param_ext_ack.param_id);
5✔
992

993
    if (_parameter_debugging) {
5✔
994
        LogDebug() << "process param_ext_ack: " << safe_param_id << " "
×
995
                   << (int)param_ext_ack.param_result;
×
996
    }
997

998
    // See comments on process_param_value for use of unique_ptr
999
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
5✔
1000
    auto work = work_queue_guard->get_front();
5✔
1001
    if (!work) {
5✔
1002
        return;
×
1003
    }
1004
    if (!work->already_requested) {
5✔
1005
        return;
×
1006
    }
1007

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

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

1060
void MavlinkParameterClient::process_param_error(const mavlink_message_t& message)
4✔
1061
{
1062
    mavlink_param_error_t param_error;
1063
    mavlink_msg_param_error_decode(&message, &param_error);
4✔
1064
    const auto safe_param_id = extract_safe_param_id(param_error.param_id);
4✔
1065

1066
    if (_parameter_debugging) {
4✔
1067
        LogDebug() << "process param_error: " << safe_param_id
×
1068
                   << " error code: " << (int)param_error.error;
×
1069
    }
1070

1071
    // See comments on process_param_value for use of unique_ptr
1072
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
4✔
1073
    auto work = work_queue_guard->get_front();
4✔
1074
    if (!work) {
4✔
1075
        return;
×
1076
    }
1077
    if (!work->already_requested) {
4✔
1078
        return;
×
1079
    }
1080

1081
    // Map MAV_PARAM_ERROR to Result
1082
    auto map_param_error_to_result = [](uint8_t error_code) -> Result {
4✔
1083
        switch (error_code) {
4✔
1084
            case 1: // MAV_PARAM_ERROR_DOES_NOT_EXIST
4✔
1085
                return Result::DoesNotExist;
4✔
1086
            case 2: // MAV_PARAM_ERROR_VALUE_OUT_OF_RANGE
×
1087
                return Result::ValueOutOfRange;
×
1088
            case 3: // MAV_PARAM_ERROR_PERMISSION_DENIED
×
1089
                return Result::PermissionDenied;
×
1090
            case 4: // MAV_PARAM_ERROR_COMPONENT_NOT_FOUND
×
1091
                return Result::ComponentNotFound;
×
1092
            case 5: // MAV_PARAM_ERROR_READ_ONLY
×
1093
                return Result::ReadOnly;
×
1094
            case 6: // MAV_PARAM_ERROR_TYPE_UNSUPPORTED
×
1095
                return Result::TypeUnsupported;
×
1096
            case 7: // MAV_PARAM_ERROR_TYPE_MISMATCH
×
1097
                return Result::TypeMismatch;
×
1098
            case 8: // MAV_PARAM_ERROR_READ_FAIL
×
1099
                return Result::ReadFail;
×
1100
            default:
×
1101
                return Result::UnknownError;
×
1102
        }
1103
    };
1104

1105
    std::visit(
4✔
1106
        overloaded{
8✔
1107
            [&](WorkItemSet& item) {
×
1108
                if (item.param_name != safe_param_id) {
×
1109
                    // No match, let's just return the borrowed work item.
1110
                    return;
×
1111
                }
1112
                _timeout_handler.remove(_timeout_cookie);
×
1113
                work_queue_guard->pop_front();
×
1114
                if (item.callback) {
×
1115
                    auto callback = item.callback;
×
1116
                    auto result = map_param_error_to_result(param_error.error);
×
1117
                    work_queue_guard.reset();
×
1118
                    callback(result);
×
1119
                }
×
1120
            },
1121
            [&](WorkItemGet& item) {
4✔
1122
                if (!validate_id_or_index(
4✔
1123
                        item.param_identifier,
4✔
1124
                        safe_param_id,
4✔
1125
                        static_cast<int16_t>(param_error.param_index))) {
4✔
1126
                    LogWarn() << "Got unexpected PARAM_ERROR on work item";
×
1127
                    // No match, let's just return the borrowed work item.
1128
                    return;
×
1129
                }
1130
                _timeout_handler.remove(_timeout_cookie);
4✔
1131
                work_queue_guard->pop_front();
4✔
1132
                if (item.callback) {
4✔
1133
                    auto callback = item.callback;
4✔
1134
                    auto result = map_param_error_to_result(param_error.error);
4✔
1135
                    work_queue_guard.reset();
4✔
1136
                    callback(result, ParamValue{});
4✔
1137
                }
4✔
1138
            },
1139
            [&](WorkItemGetAll&) { LogWarn() << "Unexpected PARAM_ERROR response for GetAll."; }},
×
1140
        work->work_item_variant);
4✔
1141
}
4✔
1142

1143
void MavlinkParameterClient::receive_timeout()
8✔
1144
{
1145
    // See comments on process_param_value for use of unique_ptr
1146
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
8✔
1147

1148
    auto work = work_queue_guard->get_front();
8✔
1149
    if (!work) {
8✔
1150
        LogErr() << "Received timeout without work";
×
1151
        return;
×
1152
    }
1153
    if (!work->already_requested) {
8✔
1154
        LogErr() << "Received timeout without already having work requested";
×
1155
        return;
×
1156
    }
1157

1158
    std::visit(
8✔
1159
        overloaded{
16✔
1160
            [&](WorkItemSet& item) {
2✔
1161
                if (work->retries_to_do > 0) {
2✔
1162
                    // We're not sure the command arrived, let's retransmit.
1163
                    LogWarn() << "sending again, retries to do: " << work->retries_to_do << "  ("
4✔
1164
                              << item.param_name << ").";
2✔
1165

1166
                    if (!send_set_param_message(item)) {
2✔
1167
                        LogErr() << "connection send error in retransmit (" << item.param_name
×
1168
                                 << ").";
×
1169
                        work_queue_guard->pop_front();
×
1170

1171
                        if (item.callback) {
×
1172
                            auto callback = item.callback;
×
1173
                            work_queue_guard.reset();
×
1174
                            callback(Result::ConnectionError);
×
1175
                        }
×
1176
                    } else {
1177
                        --work->retries_to_do;
2✔
1178
                        _timeout_cookie = _timeout_handler.add(
2✔
1179
                            [this] { receive_timeout(); }, _timeout_s_callback());
×
1180
                    }
1181
                } else {
1182
                    // We have tried retransmitting, giving up now.
1183
                    LogErr() << "Error: Retrying failed set param timeout: " << item.param_name;
×
1184
                    work_queue_guard->pop_front();
×
1185
                    if (item.callback) {
×
1186
                        auto callback = item.callback;
×
1187
                        work_queue_guard.reset();
×
1188
                        callback(Result::Timeout);
×
1189
                    }
×
1190
                }
1191
            },
2✔
1192
            [&](WorkItemGet& item) {
2✔
1193
                if (work->retries_to_do > 0) {
2✔
1194
                    // We're not sure the command arrived, let's retransmit.
1195
                    LogWarn() << "sending again, retries to do: " << work->retries_to_do;
2✔
1196
                    if (!send_get_param_message(item)) {
2✔
1197
                        LogErr() << "connection send error in retransmit ";
×
1198
                        work_queue_guard->pop_front();
×
1199
                        if (item.callback) {
×
1200
                            auto callback = item.callback;
×
1201
                            work_queue_guard.reset();
×
1202
                            callback(Result::ConnectionError, {});
×
1203
                        }
×
1204
                    } else {
1205
                        --work->retries_to_do;
2✔
1206
                        _timeout_cookie = _timeout_handler.add(
2✔
1207
                            [this] { receive_timeout(); }, _timeout_s_callback());
×
1208
                    }
1209
                } else {
1210
                    // We have tried retransmitting, giving up now.
1211
                    LogErr() << "retrying failed";
×
1212
                    work_queue_guard->pop_front();
×
1213
                    if (item.callback) {
×
1214
                        auto callback = item.callback;
×
1215
                        work_queue_guard.reset();
×
1216
                        callback(Result::Timeout, {});
×
1217
                    }
×
1218
                }
1219
            },
2✔
1220
            [&](WorkItemGetAll& item) {
4✔
1221
                // Request missing parameters.
1222
                // If retries are exceeded, give up with timeout.
1223

1224
                if (_parameter_debugging) {
4✔
1225
                    LogDebug() << "All params receive timeout with";
×
1226
                }
1227

1228
                if (item.count == 0) {
4✔
1229
                    // We got 0 messages back from the server (param count unknown). Most likely the
1230
                    // "list request" got lost before making it to the server,
1231
                    if (work->retries_to_do > 0) {
×
1232
                        --work->retries_to_do;
×
1233

1234
                        if (!send_request_list_message()) {
×
1235
                            LogErr() << "Send message failed";
×
1236
                            work_queue_guard->pop_front();
×
1237
                            if (item.callback) {
×
1238
                                auto callback = item.callback;
×
1239
                                work_queue_guard.reset();
×
1240
                                callback(Result::ConnectionError, {});
×
1241
                            }
×
1242
                            return;
×
1243
                        }
1244

1245
                        // We want to get notified if a timeout happens.
1246
                        _timeout_cookie = _timeout_handler.add(
×
1247
                            [this] { receive_timeout(); },
×
1248
                            _timeout_s_callback() * _get_all_timeout_factor);
×
1249
                    } else {
1250
                        if (item.callback) {
×
1251
                            auto callback = item.callback;
×
1252
                            work_queue_guard.reset();
×
1253
                            callback(Result::Timeout, {});
×
1254
                        }
×
1255
                        return;
×
1256
                    }
1257

1258
                } else {
1259
                    item.rerequesting = true;
4✔
1260

1261
                    LogInfo() << "Requesting " << _param_cache.missing_count(item.count) << " of "
8✔
1262
                              << item.count << " parameters missed during initial burst.";
4✔
1263

1264
                    if (_parameter_debugging) {
4✔
1265
                        _param_cache.print_missing(item.count);
×
1266
                    }
1267

1268
                    // To speed retransmissions up, we request params in chunks, otherwise the
1269
                    // latency back and forth makes this quite slow.
1270
                    if (!request_next_missing(item.count)) {
4✔
1271
                        work_queue_guard->pop_front();
×
1272
                        if (item.callback) {
×
1273
                            auto callback = item.callback;
×
1274
                            work_queue_guard.reset();
×
1275
                            callback(Result::ConnectionError, {});
×
1276
                        }
×
1277
                        return;
×
1278
                    }
1279

1280
                    _timeout_cookie =
4✔
1281
                        _timeout_handler.add([this] { receive_timeout(); }, _timeout_s_callback());
6✔
1282
                }
1283
            }},
1284
        work->work_item_variant);
8✔
1285
}
8✔
1286

1287
bool MavlinkParameterClient::request_next_missing(uint16_t count)
4✔
1288
{
1289
    // Requesting 10 at a time seems to work on SiK radios.
1290
    const uint16_t chunk_size = 10;
4✔
1291

1292
    auto next_missing_indices = _param_cache.next_missing_indices(count, chunk_size);
4✔
1293
    if (next_missing_indices.empty()) {
4✔
1294
        LogErr() << "logic error, there should a missing index";
×
1295
        return false;
×
1296
    }
1297

1298
    for (auto next_missing_index : next_missing_indices) {
9✔
1299
        if (_parameter_debugging) {
5✔
1300
            LogDebug() << "Requesting missing parameter " << (int)next_missing_index;
×
1301
        }
1302

1303
        std::array<char, PARAM_ID_LEN> param_id_buff{};
5✔
1304

1305
        if (!send_get_param_message(param_id_buff, next_missing_index)) {
5✔
1306
            LogErr() << "Send message failed";
×
1307
            return false;
×
1308
        }
1309
    }
1310
    return true;
4✔
1311
}
4✔
1312

1313
std::ostream& operator<<(std::ostream& str, const MavlinkParameterClient::Result& result)
×
1314
{
1315
    switch (result) {
×
1316
        case MavlinkParameterClient::Result::Success:
×
1317
            return str << "Success";
×
1318
        case MavlinkParameterClient::Result::Timeout:
×
1319
            return str << "Timeout";
×
1320
        case MavlinkParameterClient::Result::ConnectionError:
×
1321
            return str << "ConnectionError";
×
1322
        case MavlinkParameterClient::Result::WrongType:
×
1323
            return str << "WrongType";
×
1324
        case MavlinkParameterClient::Result::ParamNameTooLong:
×
1325
            return str << "ParamNameTooLong";
×
1326
        case MavlinkParameterClient::Result::NotFound:
×
1327
            return str << "NotFound";
×
1328
        case MavlinkParameterClient::Result::ValueUnsupported:
×
1329
            return str << "ValueUnsupported";
×
1330
        case MavlinkParameterClient::Result::Failed:
×
1331
            return str << "Failed";
×
1332
        case MavlinkParameterClient::Result::UnknownError:
×
1333
            // Fallthrough
1334
        default:
1335
            return str << "UnknownError";
×
1336
    }
1337
}
1338

1339
bool MavlinkParameterClient::validate_id_or_index(
55✔
1340
    const std::variant<std::string, int16_t>& original,
1341
    const std::string& param_id,
1342
    const int16_t param_index)
1343
{
1344
    if (const auto str = std::get_if<std::string>(&original)) {
55✔
1345
        if (param_id != *str) {
55✔
1346
            // We requested by string id, but response doesn't match
1347
            return false;
1✔
1348
        }
1349
    } else {
1350
        const auto tmp = std::get<int16_t>(original);
×
1351
        if (param_index != tmp) {
×
1352
            // We requested by index, but response doesn't match
1353
            return false;
×
1354
        }
1355
    }
1356
    return true;
54✔
1357
}
1358

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

© 2025 Coveralls, Inc