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

mavlink / MAVSDK / 12451437031

22 Dec 2024 05:05AM UTC coverage: 44.651% (+0.03%) from 44.626%
12451437031

push

github

web-flow
Merge pull request #2480 from mavlink/pr-param-fixes

Fix set param regression, improve param example

2 of 12 new or added lines in 1 file covered. (16.67%)

5 existing lines in 1 file now uncovered.

14597 of 32691 relevant lines covered (44.65%)

286.34 hits per line

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

59.06
/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 "plugin_base.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); },
68✔
48
            this);
49

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

360
std::pair<MavlinkParameterClient::Result, float>
361
MavlinkParameterClient::get_param_float(const std::string& name)
5✔
362
{
363
    auto prom = std::promise<std::pair<Result, float>>();
5✔
364
    auto res = prom.get_future();
5✔
365
    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 =
4✔
393
        std::make_shared<WorkItem>(WorkItemGetAll{std::move(callback), 0, false}, cookie);
8✔
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()
53✔
426
{
427
    _param_cache.clear();
53✔
428
}
53✔
429

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

435
    if (!work) {
740✔
436
        return;
378✔
437
    }
438

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

443
    std::visit(
124✔
444
        overloaded{
62✔
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());
19✔
460
            },
461
            [&](WorkItemGet& item) {
49✔
462
                // We can't rely on the cache as we haven't implemented the hash check.
463
                clear_cache();
49✔
464
                if (!send_get_param_message(item)) {
49✔
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
                        item.callback(Result::ConnectionError, ParamValue{});
×
471
                    }
×
472
                    return;
×
473
                }
474
                work->already_requested = true;
49✔
475
                // We want to get notified if a timeout happens
476
                _timeout_cookie =
49✔
477
                    _timeout_handler.add([this] { receive_timeout(); }, _timeout_s_callback());
103✔
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
                        item.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);
62✔
498
}
1,418✔
499

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

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

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

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

531
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
8✔
532
            if (_parameter_debugging) {
4✔
533
                LogDebug() << "Sending param_set to:" << (int)mavlink_address.system_id << ":"
×
534
                           << (int)mavlink_address.component_id;
×
535
            }
536
            mavlink_msg_param_set_pack_chan(
8✔
537
                mavlink_address.system_id,
4✔
538
                mavlink_address.component_id,
4✔
539
                channel,
540
                &message,
8✔
541
                _target_system_id,
4✔
542
                _target_component_id,
4✔
543
                param_id.data(),
4✔
544
                value_set,
4✔
545
                work_item.param_value.get_mav_param_type());
4✔
546
            return message;
4✔
547
        });
4✔
548
    }
549
}
550

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

562
    return send_get_param_message(param_id_buff, param_index);
62✔
563
}
564

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

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

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

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

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

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

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

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

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

686
    if (!work) {
26✔
687
        // update existing param
688
        find_and_call_subscriptions_value_changed(safe_param_id, received_value);
×
689
        return;
×
690
    }
691

692
    if (!work->already_requested) {
26✔
693
        return;
×
694
    }
695

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

704
                if (_parameter_debugging) {
4✔
705
                    LogDebug() << "Item value is: " << item.param_value
×
706
                               << ", received: " << received_value;
×
707
                }
708

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

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

742
                        if (!send_set_param_message(item)) {
×
743
                            LogErr() << "connection send error in retransmit (" << item.param_name
×
744
                                     << ").";
×
745
                            work_queue_guard->pop_front();
×
746

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

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

801
                        if (item.count != param_value.param_count) {
12✔
802
                            item.count = param_value.param_count;
2✔
803
                            if (_parameter_debugging) {
2✔
804
                                LogDebug() << "Count is now " << item.count;
×
805
                            }
806
                        }
807

808
                        if (_parameter_debugging) {
12✔
809
                            LogDebug() << "Received param: " << param_value.param_index;
×
810
                        }
811

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

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

881
    if (_parameter_debugging) {
68✔
882
        LogDebug() << "process param_ext_value: " << safe_param_id << " " << received_value;
×
883
    }
884

885
    // See comments on process_param_value for use of unique_ptr
886
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
68✔
887
    auto work = work_queue_guard->get_front();
68✔
888

889
    if (!work) {
68✔
890
        // update existing param
891
        find_and_call_subscriptions_value_changed(safe_param_id, received_value);
13✔
892
        return;
13✔
893
    }
894

895
    if (!work->already_requested) {
55✔
896
        return;
×
897
    }
898

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

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

975
void MavlinkParameterClient::process_param_ext_ack(const mavlink_message_t& message)
5✔
976
{
977
    mavlink_param_ext_ack_t param_ext_ack;
5✔
978
    mavlink_msg_param_ext_ack_decode(&message, &param_ext_ack);
5✔
979
    const auto safe_param_id = extract_safe_param_id(param_ext_ack.param_id);
5✔
980

981
    if (_parameter_debugging) {
5✔
982
        LogDebug() << "process param_ext_ack: " << safe_param_id << " "
×
983
                   << (int)param_ext_ack.param_result;
×
984
    }
985

986
    // See comments on process_param_value for use of unique_ptr
987
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
5✔
988
    auto work = work_queue_guard->get_front();
5✔
989
    if (!work) {
5✔
990
        return;
×
991
    }
992
    if (!work->already_requested) {
5✔
993
        return;
×
994
    }
995

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

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

1048
void MavlinkParameterClient::receive_timeout()
20✔
1049
{
1050
    // See comments on process_param_value for use of unique_ptr
1051
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
20✔
1052

1053
    auto work = work_queue_guard->get_front();
20✔
1054
    if (!work) {
20✔
1055
        LogErr() << "Received timeout without work";
×
1056
        return;
×
1057
    }
1058
    if (!work->already_requested) {
20✔
1059
        LogErr() << "Received timeout without already having work requested";
×
1060
        return;
×
1061
    }
1062

1063
    std::visit(
40✔
1064
        overloaded{
20✔
1065
            [&](WorkItemSet& item) {
1✔
1066
                if (work->retries_to_do > 0) {
1✔
1067
                    // We're not sure the command arrived, let's retransmit.
1068
                    LogWarn() << "sending again, retries to do: " << work->retries_to_do << "  ("
2✔
1069
                              << item.param_name << ").";
2✔
1070

1071
                    if (!send_set_param_message(item)) {
1✔
1072
                        LogErr() << "connection send error in retransmit (" << item.param_name
×
1073
                                 << ").";
×
1074
                        work_queue_guard->pop_front();
×
1075

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

1129
                if (_parameter_debugging) {
4✔
1130
                    LogDebug() << "All params receive timeout with";
×
1131
                }
1132

1133
                if (item.count == 0) {
4✔
1134
                    // We got 0 messages back from the server (param count unknown). Most likely the
1135
                    // "list request" got lost before making it to the server,
1136
                    if (work->retries_to_do > 0) {
×
1137
                        --work->retries_to_do;
×
1138

1139
                        if (!send_request_list_message()) {
×
1140
                            LogErr() << "Send message failed";
×
1141
                            work_queue_guard->pop_front();
×
1142
                            if (item.callback) {
×
1143
                                auto callback = item.callback;
×
1144
                                work_queue_guard.reset();
×
1145
                                item.callback(Result::ConnectionError, {});
×
1146
                            }
×
1147
                            return;
×
1148
                        }
1149

1150
                        // We want to get notified if a timeout happens.
1151
                        _timeout_cookie = _timeout_handler.add(
×
1152
                            [this] { receive_timeout(); },
×
1153
                            _timeout_s_callback() * _get_all_timeout_factor);
×
1154
                    } else {
1155
                        if (item.callback) {
×
1156
                            auto callback = item.callback;
×
1157
                            work_queue_guard.reset();
×
1158
                            item.callback(Result::Timeout, {});
×
1159
                        }
×
1160
                        return;
×
1161
                    }
1162

1163
                } else {
1164
                    item.rerequesting = true;
4✔
1165

1166
                    LogInfo() << "Requesting " << _param_cache.missing_count(item.count) << " of "
12✔
1167
                              << item.count << " parameters missed during initial burst.";
12✔
1168

1169
                    if (_parameter_debugging) {
4✔
1170
                        _param_cache.print_missing(item.count);
×
1171
                    }
1172

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

1185
                    _timeout_cookie =
4✔
1186
                        _timeout_handler.add([this] { receive_timeout(); }, _timeout_s_callback());
10✔
1187
                }
1188
            }},
1189
        work->work_item_variant);
20✔
1190
}
20✔
1191

1192
bool MavlinkParameterClient::request_next_missing(uint16_t count)
4✔
1193
{
1194
    // Requesting 10 at a time seems to work on SiK radios.
1195
    const uint16_t chunk_size = 10;
4✔
1196

1197
    auto next_missing_indices = _param_cache.next_missing_indices(count, chunk_size);
4✔
1198
    if (next_missing_indices.empty()) {
4✔
1199
        LogErr() << "logic error, there should a missing index";
×
1200
        return false;
×
1201
    }
1202

1203
    for (auto next_missing_index : next_missing_indices) {
9✔
1204
        if (_parameter_debugging) {
5✔
1205
            LogDebug() << "Requesting missing parameter " << (int)next_missing_index;
×
1206
        }
1207

1208
        std::array<char, PARAM_ID_LEN> param_id_buff{};
5✔
1209

1210
        if (!send_get_param_message(param_id_buff, next_missing_index)) {
5✔
1211
            LogErr() << "Send message failed";
×
1212
            return false;
×
1213
        }
1214
    }
1215
    return true;
4✔
1216
}
4✔
1217

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

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

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