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

mavlink / MAVSDK / 7351683140

28 Dec 2023 10:20PM UTC coverage: 36.266% (+0.007%) from 36.259%
7351683140

push

github

web-flow
Merge pull request #2204 from mavlink/pr-update-alpine

CI: update to latest alpine

10037 of 27676 relevant lines covered (36.27%)

128.2 hits per line

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

56.84
/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 "timeout_handler.h"
5
#include "system_impl.h"
6
#include "plugin_base.h"
7
#include <algorithm>
8
#include <future>
9
#include <utility>
10

11
namespace mavsdk {
12

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

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

42
    if (_use_extended) {
9✔
43
        _message_handler.register_one(
4✔
44
            MAVLINK_MSG_ID_PARAM_EXT_VALUE,
45
            [this](const mavlink_message_t& message) { process_param_ext_value(message); },
22✔
46
            this);
47

48
        _message_handler.register_one(
4✔
49
            MAVLINK_MSG_ID_PARAM_EXT_ACK,
50
            [this](const mavlink_message_t& message) { process_param_ext_ack(message); },
2✔
51
            this);
52
    } else {
53
        _message_handler.register_one(
5✔
54
            MAVLINK_MSG_ID_PARAM_VALUE,
55
            [this](const mavlink_message_t& message) { process_param_value(message); },
24✔
56
            this);
57
    }
58
}
9✔
59

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

68
    _message_handler.unregister_all(this);
9✔
69
}
9✔
70

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

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

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

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

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

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

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

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

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

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

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

250
    auto new_work = std::make_shared<WorkItem>(WorkItemGet{name, callback}, cookie);
54✔
251
    _work_queue.push_back(new_work);
18✔
252
}
253

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

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

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

301
void MavlinkParameterClient::get_param_int_async(
9✔
302
    const std::string& name, const GetParamIntCallback& callback, const void* cookie)
303
{
304
    get_param_async_typesafe<int32_t>(name, callback, cookie);
9✔
305
}
9✔
306

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

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

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

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

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

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

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

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

393
void MavlinkParameterClient::cancel_all_param(const void* cookie)
×
394
{
395
    LockedQueue<WorkItem>::Guard work_queue_guard(_work_queue);
×
396

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

404
void MavlinkParameterClient::clear_cache()
×
405
{
406
    _param_cache.clear();
×
407
}
×
408

409
void MavlinkParameterClient::do_work()
385✔
410
{
411
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
385✔
412
    auto work = work_queue_guard->get_front();
385✔
413

414
    if (!work) {
385✔
415
        return;
121✔
416
    }
417

418
    if (work->already_requested) {
264✔
419
        return;
239✔
420
    }
421

422
    std::visit(
50✔
423
        overloaded{
25✔
424
            [&](WorkItemSet& item) {
6✔
425
                if (!send_set_param_message(item)) {
6✔
426
                    LogErr() << "Send message failed";
×
427
                    work_queue_guard->pop_front();
×
428
                    if (item.callback) {
×
429
                        auto callback = item.callback;
×
430
                        work_queue_guard.reset();
×
431
                        callback(Result::ConnectionError);
×
432
                    }
433
                    return;
×
434
                }
435
                work->already_requested = true;
6✔
436
                // We want to get notified if a timeout happens
437
                _timeout_handler.add(
6✔
438
                    [this] { receive_timeout(); }, _timeout_s_callback(), &_timeout_cookie);
1✔
439
            },
440
            [&](WorkItemGet& item) {
15✔
441
                if (!send_get_param_message(item)) {
15✔
442
                    LogErr() << "Send message failed";
×
443
                    work_queue_guard->pop_front();
×
444
                    if (item.callback) {
×
445
                        auto callback = item.callback;
×
446
                        work_queue_guard.reset();
×
447
                        item.callback(Result::ConnectionError, ParamValue{});
×
448
                    }
449
                    return;
×
450
                }
451
                work->already_requested = true;
15✔
452
                // We want to get notified if a timeout happens
453
                _timeout_handler.add(
15✔
454
                    [this] { receive_timeout(); }, _timeout_s_callback(), &_timeout_cookie);
4✔
455
            },
456
            [&](WorkItemGetAll& item) {
4✔
457
                if (!send_request_list_message()) {
4✔
458
                    LogErr() << "Send message failed";
×
459
                    work_queue_guard->pop_front();
×
460
                    if (item.callback) {
×
461
                        auto callback = item.callback;
×
462
                        work_queue_guard.reset();
×
463
                        item.callback(Result::ConnectionError, {});
×
464
                    }
465
                    return;
×
466
                }
467
                work->already_requested = true;
4✔
468
                // We want to get notified if a timeout happens
469
                _timeout_handler.add(
4✔
470
                    [this] { receive_timeout(); }, _timeout_s_callback(), &_timeout_cookie);
2✔
471
            }},
472
        work->work_item_variant);
25✔
473
}
474

475
bool MavlinkParameterClient::send_set_param_message(WorkItemSet& work_item)
8✔
476
{
477
    auto param_id = param_id_to_message_buffer(work_item.param_name);
8✔
478

479
    mavlink_message_t message;
8✔
480
    if (_use_extended) {
8✔
481
        const auto param_value_buf = work_item.param_value.get_128_bytes();
2✔
482
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
4✔
483
            if (_parameter_debugging) {
2✔
484
                LogDebug() << "Sending param_ext_set to:" << (int)mavlink_address.system_id << ":"
×
485
                           << (int)mavlink_address.component_id;
×
486
            }
487

488
            mavlink_msg_param_ext_set_pack_chan(
4✔
489
                mavlink_address.system_id,
2✔
490
                mavlink_address.component_id,
2✔
491
                channel,
492
                &message,
4✔
493
                _target_system_id,
2✔
494
                _target_component_id,
2✔
495
                param_id.data(),
2✔
496
                param_value_buf.data(),
2✔
497
                work_item.param_value.get_mav_param_ext_type());
2✔
498

499
            return message;
2✔
500
        });
2✔
501
    } else {
502
        const float value_set = (_sender.autopilot() == Autopilot::ArduPilot) ?
6✔
503
                                    work_item.param_value.get_4_float_bytes_cast() :
×
504
                                    work_item.param_value.get_4_float_bytes_bytewise();
6✔
505

506
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
12✔
507
            if (_parameter_debugging) {
6✔
508
                LogDebug() << "Sending param_set to:" << (int)mavlink_address.system_id << ":"
×
509
                           << (int)mavlink_address.component_id;
×
510
            }
511
            mavlink_msg_param_set_pack_chan(
12✔
512
                mavlink_address.system_id,
6✔
513
                mavlink_address.component_id,
6✔
514
                channel,
515
                &message,
12✔
516
                _target_system_id,
6✔
517
                _target_component_id,
6✔
518
                param_id.data(),
6✔
519
                value_set,
6✔
520
                work_item.param_value.get_mav_param_type());
6✔
521
            return message;
6✔
522
        });
6✔
523
    }
524
}
525

526
bool MavlinkParameterClient::send_get_param_message(WorkItemGet& work_item)
28✔
527
{
528
    std::array<char, PARAM_ID_LEN> param_id_buff{};
28✔
529
    int16_t param_index = -1;
28✔
530
    if (auto str = std::get_if<std::string>(&work_item.param_identifier)) {
28✔
531
        param_id_buff = param_id_to_message_buffer(*str);
28✔
532
    } else {
533
        // param_id_buff doesn't matter
534
        param_index = std::get<int16_t>(work_item.param_identifier);
×
535
    }
536

537
    return send_get_param_message(param_id_buff, param_index);
28✔
538
}
539

540
bool MavlinkParameterClient::send_get_param_message(
34✔
541
    const std::array<char, PARAM_ID_LEN>& param_id_buff, int16_t param_index)
542
{
543
    mavlink_message_t message;
34✔
544

545
    if (_use_extended) {
34✔
546
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
18✔
547
            if (_parameter_debugging) {
9✔
548
                LogDebug() << "Send param_ext_request_read: " << (int)mavlink_address.system_id
×
549
                           << ":" << (int)mavlink_address.component_id << " to "
×
550
                           << (int)_target_system_id << ":" << (int)_target_component_id;
×
551
            }
552
            mavlink_msg_param_ext_request_read_pack_chan(
18✔
553
                mavlink_address.system_id,
9✔
554
                mavlink_address.component_id,
9✔
555
                channel,
556
                &message,
18✔
557
                _target_system_id,
9✔
558
                _target_component_id,
9✔
559
                param_id_buff.data(),
9✔
560
                param_index);
9✔
561
            return message;
9✔
562
        });
9✔
563

564
    } else {
565
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
50✔
566
            if (_parameter_debugging) {
25✔
567
                LogDebug() << "Send param_request_read: " << (int)mavlink_address.system_id << ":"
×
568
                           << (int)mavlink_address.component_id << " to " << (int)_target_system_id
×
569
                           << ":" << (int)_target_component_id;
×
570
            }
571
            mavlink_msg_param_request_read_pack_chan(
50✔
572
                mavlink_address.system_id,
25✔
573
                mavlink_address.component_id,
25✔
574
                channel,
575
                &message,
50✔
576
                _target_system_id,
25✔
577
                _target_component_id,
25✔
578
                param_id_buff.data(),
25✔
579
                param_index);
25✔
580
            return message;
25✔
581
        });
25✔
582
    }
583
}
584

585
bool MavlinkParameterClient::send_request_list_message()
4✔
586
{
587
    if (_use_extended) {
4✔
588
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
4✔
589
            if (_parameter_debugging) {
2✔
590
                LogDebug() << "Sending param_ext_request_list to:" << (int)mavlink_address.system_id
×
591
                           << ":" << (int)mavlink_address.component_id;
×
592
            }
593
            mavlink_message_t message;
594
            mavlink_msg_param_ext_request_list_pack_chan(
2✔
595
                mavlink_address.system_id,
2✔
596
                mavlink_address.component_id,
2✔
597
                channel,
598
                &message,
599
                _target_system_id,
2✔
600
                _target_component_id);
2✔
601
            return message;
2✔
602
        });
2✔
603
    } else {
604
        return _sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
4✔
605
            if (_parameter_debugging) {
2✔
606
                LogDebug() << "Sending param_request_list to:" << (int)mavlink_address.system_id
×
607
                           << ":" << (int)mavlink_address.component_id;
×
608
            }
609
            mavlink_message_t message;
610
            mavlink_msg_param_request_list_pack_chan(
2✔
611
                mavlink_address.system_id,
2✔
612
                mavlink_address.component_id,
2✔
613
                channel,
614
                &message,
615
                _target_system_id,
2✔
616
                _target_component_id);
2✔
617
            return message;
2✔
618
        });
2✔
619
    }
620
}
621

622
void MavlinkParameterClient::process_param_value(const mavlink_message_t& message)
24✔
623
{
624
    mavlink_param_value_t param_value;
24✔
625
    mavlink_msg_param_value_decode(&message, &param_value);
24✔
626
    const std::string safe_param_id = extract_safe_param_id(param_value.param_id);
24✔
627
    if (safe_param_id.empty()) {
24✔
628
        LogWarn() << "Got ill-formed param_value message (param_id empty)";
×
629
        return;
×
630
    }
631

632
    ParamValue received_value;
24✔
633
    const bool set_value_success = received_value.set_from_mavlink_param_value(
24✔
634
        param_value,
635
        (_sender.autopilot() == Autopilot::ArduPilot) ? ParamValue::Conversion::Cast :
24✔
636
                                                        ParamValue::Conversion::Bitwise);
24✔
637
    if (!set_value_success) {
24✔
638
        LogWarn() << "Got ill-formed param_ext_value message (param_type unknown)";
×
639
        return;
×
640
    }
641

642
    if (_parameter_debugging) {
24✔
643
        LogDebug() << "process_param_value: " << safe_param_id << " " << received_value;
×
644
    }
645

646
    // We need to use a unique pointer here to remove the lock from the work queue manually "early"
647
    // before calling the (perhaps user-provided) callback. Otherwise, we might end up in a deadlock
648
    // if the callback wants to push another work item onto the queue. By using a unique ptr there
649
    // is no risk of forgetting to remove the lock - it is destroyed (if still valid) after going
650
    // out of scope.
651
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
24✔
652
    const auto work = work_queue_guard->get_front();
24✔
653
    if (!work) {
24✔
654
        return;
×
655
    }
656

657
    if (!work->already_requested) {
24✔
658
        return;
×
659
    }
660

661
    std::visit(
48✔
662
        overloaded{
24✔
663
            [&](WorkItemSet& item) {
4✔
664
                if (item.param_name != safe_param_id) {
4✔
665
                    // No match, let's just return the borrowed work item.
666
                    return;
×
667
                }
668

669
                if (_parameter_debugging) {
4✔
670
                    LogDebug() << "Item value is: " << item.param_value
×
671
                               << ", received: " << received_value;
×
672
                }
673

674
                if (item.param_value == received_value) {
4✔
675
                    // This was successful. Inform the caller.
676
                    _timeout_handler.remove(_timeout_cookie);
4✔
677
                    // LogDebug() << "time taken: " <<
678
                    // _sender.get_time().elapsed_since_s(_last_request_time);
679
                    work_queue_guard->pop_front();
4✔
680
                    if (item.callback) {
4✔
681
                        auto callback = item.callback;
8✔
682
                        work_queue_guard.reset();
4✔
683
                        callback(MavlinkParameterClient::Result::Success);
4✔
684
                    }
685
                } else {
686
                    // We might be receiving stale param_value messages, let's just
687
                    // try again. This can happen if the timeout is chosen low and we
688
                    // get out of sync when doing a param_get just before the param_set.
689
                    // In that case we have stale param_value messages in flux and
690
                    // receive them here.
691
                    if (work->retries_to_do > 0) {
×
692
                        LogWarn() << "sending again, retries to do: " << work->retries_to_do
×
693
                                  << "  (" << item.param_name << ").";
×
694

695
                        if (!send_set_param_message(item)) {
×
696
                            LogErr() << "connection send error in retransmit (" << item.param_name
×
697
                                     << ").";
×
698
                            work_queue_guard->pop_front();
×
699

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

752
                        item.count = param_value.param_count;
12✔
753
                        if (_parameter_debugging) {
12✔
754
                            LogDebug() << "Count is now " << item.count;
×
755
                        }
756
                        if (_param_cache.count(_use_extended) == param_value.param_count) {
12✔
757
                            _timeout_handler.remove(_timeout_cookie);
2✔
758
                            if (_parameter_debugging) {
2✔
759
                                LogDebug() << "Param set complete: "
×
760
                                           << (_use_extended ? "extended" : "not extended");
×
761
                            }
762
                            work_queue_guard->pop_front();
2✔
763
                            if (item.callback) {
2✔
764
                                auto callback = item.callback;
4✔
765
                                work_queue_guard.reset();
2✔
766
                                callback(
4✔
767
                                    Result::Success,
768
                                    _param_cache.all_parameters_map(_use_extended));
4✔
769
                            }
770
                        } else {
771
                            if (_parameter_debugging) {
10✔
772
                                LogDebug() << "Count expected " << _param_cache.count(_use_extended)
×
773
                                           << " so far " << param_value.param_count;
×
774
                            }
775
                            if (item.rerequesting) {
10✔
776
                                auto maybe_next_missing_index =
1✔
777
                                    _param_cache.next_missing_index(item.count);
1✔
778
                                if (!maybe_next_missing_index.has_value()) {
1✔
779
                                    LogErr() << "logic error, there should a missing index";
×
780
                                    assert(false);
×
781
                                }
782

783
                                if (_parameter_debugging) {
1✔
784
                                    LogDebug() << "Requesting missing parameter "
×
785
                                               << (int)maybe_next_missing_index.value();
×
786
                                }
787

788
                                std::array<char, PARAM_ID_LEN> param_id_buff{};
1✔
789
                                if (!send_get_param_message(
1✔
790
                                        param_id_buff, maybe_next_missing_index.value())) {
1✔
791
                                    LogErr() << "Send message failed";
×
792
                                    work_queue_guard->pop_front();
×
793
                                    if (item.callback) {
×
794
                                        auto callback = item.callback;
×
795
                                        work_queue_guard.reset();
×
796
                                        callback(Result::ConnectionError, {});
×
797
                                    }
798
                                    return;
×
799
                                }
800
                            } else {
801
                                // update the timeout handler, messages are still coming in.
802
                            }
803
                            _timeout_handler.refresh(&_timeout_cookie);
10✔
804
                        }
805
                        break;
12✔
806
                    case MavlinkParameterCache::AddNewParamResult::TooManyParams:
×
807
                        // We shouldn't be able to get here as the incoming type is only an
808
                        // uint16_t.
809
                        LogErr() << "Too many params received";
×
810
                        assert(false);
×
811
                        break;
812
                    default:
×
813
                        LogErr() << "Unknown AddNewParamResult";
×
814
                        assert(false);
×
815
                        break;
816
                }
817
            }},
818
        work->work_item_variant);
24✔
819

820
    // find_and_call_subscriptions_value_changed(safe_param_id, received_value);
821
}
822

823
void MavlinkParameterClient::process_param_ext_value(const mavlink_message_t& message)
22✔
824
{
825
    mavlink_param_ext_value_t param_ext_value;
22✔
826
    mavlink_msg_param_ext_value_decode(&message, &param_ext_value);
22✔
827
    const auto safe_param_id = extract_safe_param_id(param_ext_value.param_id);
22✔
828
    if (safe_param_id.empty()) {
22✔
829
        LogWarn() << "Got ill-formed param_ext_value message (param_id empty)";
×
830
        return;
×
831
    }
832
    ParamValue received_value;
22✔
833
    if (!received_value.set_from_mavlink_param_ext_value(param_ext_value)) {
22✔
834
        LogWarn() << "Got ill-formed param_ext_value message (param_type unknown)";
×
835
        return;
×
836
    }
837

838
    if (_parameter_debugging) {
22✔
839
        LogDebug() << "process param_ext_value: " << safe_param_id << " " << received_value;
×
840
    }
841

842
    // See comments on process_param_value for use of unique_ptr
843
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
22✔
844
    auto work = work_queue_guard->get_front();
22✔
845
    if (!work) {
22✔
846
        return;
×
847
    }
848
    if (!work->already_requested) {
22✔
849
        return;
×
850
    }
851

852
    std::visit(
44✔
853
        overloaded{
22✔
854
            [&](WorkItemSet&) {
×
855
                if (_parameter_debugging) {
×
856
                    LogDebug() << "Unexpected ParamExtValue response.";
×
857
                }
858
            },
×
859
            [&](WorkItemGet& item) {
4✔
860
                if (!validate_id_or_index(
4✔
861
                        item.param_identifier,
4✔
862
                        safe_param_id,
4✔
863
                        static_cast<int16_t>(param_ext_value.param_index))) {
4✔
864
                    LogWarn() << "Got unexpected response on work item";
×
865
                    // No match, let's just return the borrowed work item.
866
                    return;
×
867
                }
868
                _timeout_handler.remove(_timeout_cookie);
4✔
869
                // LogDebug() << "time taken: " <<
870
                // _sender.get_time().elapsed_since_s(_last_request_time);
871
                work_queue_guard->pop_front();
4✔
872
                if (item.callback) {
4✔
873
                    auto callback = item.callback;
8✔
874
                    work_queue_guard.reset();
4✔
875
                    callback(Result::Success, received_value);
4✔
876
                }
877
            },
878
            [&](WorkItemGetAll& item) {
18✔
879
                switch (_param_cache.add_new_param(
18✔
880
                    safe_param_id, received_value, param_ext_value.param_index)) {
18✔
881
                    case MavlinkParameterCache::AddNewParamResult::AlreadyExists:
18✔
882
                        // PASSTHROUGH.
883
                    case MavlinkParameterCache::AddNewParamResult::Ok:
884
                        item.count = param_ext_value.param_count;
18✔
885
                        if (_parameter_debugging) {
18✔
886
                            LogDebug() << "Count is now " << item.count;
×
887
                        }
888

889
                        if (_param_cache.count(_use_extended) == param_ext_value.param_count) {
18✔
890
                            _timeout_handler.remove(_timeout_cookie);
2✔
891
                            if (_parameter_debugging) {
2✔
892
                                LogDebug() << "Param set complete: "
×
893
                                           << (_use_extended ? "extended" : "not extended");
×
894
                            }
895
                            work_queue_guard->pop_front();
2✔
896
                            if (item.callback) {
2✔
897
                                auto callback = item.callback;
4✔
898
                                work_queue_guard.reset();
2✔
899
                                callback(
4✔
900
                                    Result::Success,
901
                                    _param_cache.all_parameters_map(_use_extended));
4✔
902
                            }
903
                        } else {
904
                            if (_parameter_debugging) {
16✔
905
                                LogDebug() << "Count expected " << _param_cache.count(_use_extended)
×
906
                                           << " but is " << param_ext_value.param_count;
×
907
                            }
908
                            // update the timeout handler, messages are still coming in.
909
                            _timeout_handler.refresh(&_timeout_cookie);
16✔
910
                        }
911
                        break;
18✔
912
                    case MavlinkParameterCache::AddNewParamResult::TooManyParams:
×
913
                        // We shouldn't be able to get here as the incoming type is only an
914
                        // uint16_t.
915
                        LogErr() << "Too many params received";
×
916
                        assert(false);
×
917
                        break;
918
                    default:
×
919
                        LogErr() << "Unknown AddNewParamResult";
×
920
                        assert(false);
×
921
                        break;
922
                }
923
            },
18✔
924
        },
925
        work->work_item_variant);
22✔
926

927
    // TODO I think we need to consider more edge cases here
928
    // find_and_call_subscriptions_value_changed(safe_param_id, received_value);
929
}
930

931
void MavlinkParameterClient::process_param_ext_ack(const mavlink_message_t& message)
2✔
932
{
933
    mavlink_param_ext_ack_t param_ext_ack;
2✔
934
    mavlink_msg_param_ext_ack_decode(&message, &param_ext_ack);
2✔
935
    const auto safe_param_id = extract_safe_param_id(param_ext_ack.param_id);
2✔
936

937
    if (_parameter_debugging) {
2✔
938
        LogDebug() << "process param_ext_ack: " << safe_param_id << " "
×
939
                   << (int)param_ext_ack.param_result;
×
940
    }
941

942
    // See comments on process_param_value for use of unique_ptr
943
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
2✔
944
    auto work = work_queue_guard->get_front();
2✔
945
    if (!work) {
2✔
946
        return;
×
947
    }
948
    if (!work->already_requested) {
2✔
949
        return;
×
950
    }
951

952
    std::visit(
4✔
953
        overloaded{
2✔
954
            [&](WorkItemSet& item) {
2✔
955
                if (item.param_name != safe_param_id) {
2✔
956
                    // No match, let's just return the borrowed work item.
957
                    return;
×
958
                }
959
                if (param_ext_ack.param_result == PARAM_ACK_ACCEPTED) {
2✔
960
                    _timeout_handler.remove(_timeout_cookie);
2✔
961
                    // LogDebug() << "time taken: " <<
962
                    // _sender.get_time().elapsed_since_s(_last_request_time);
963
                    work_queue_guard->pop_front();
2✔
964
                    if (item.callback) {
2✔
965
                        auto callback = item.callback;
4✔
966
                        // We are done, inform caller and go back to idle
967
                        work_queue_guard.reset();
2✔
968
                        callback(Result::Success);
2✔
969
                    }
970
                } else if (param_ext_ack.param_result == PARAM_ACK_IN_PROGRESS) {
×
971
                    // Reset timeout and wait again.
972
                    _timeout_handler.refresh(_timeout_cookie);
×
973

974
                } else {
975
                    LogWarn() << "Somehow we did not get an ack, we got: "
×
976
                              << int(param_ext_ack.param_result);
×
977
                    _timeout_handler.remove(_timeout_cookie);
×
978
                    // LogDebug() << "time taken: " <<
979
                    // _sender.get_time().elapsed_since_s(_last_request_time);
980
                    work_queue_guard->pop_front();
×
981
                    work_queue_guard.reset();
×
982
                    if (item.callback) {
×
983
                        auto callback = item.callback;
×
984
                        auto result = [&]() {
×
985
                            switch (param_ext_ack.param_result) {
×
986
                                case PARAM_ACK_FAILED:
×
987
                                    return Result::Failed;
×
988
                                case PARAM_ACK_VALUE_UNSUPPORTED:
×
989
                                    return Result::ValueUnsupported;
×
990
                                default:
×
991
                                    return Result::UnknownError;
×
992
                            }
993
                        }();
×
994
                        work_queue_guard.reset();
×
995
                        callback(result);
×
996
                    }
997
                }
998
            },
999
            [&](WorkItemGet&) { LogWarn() << "Unexpected ParamExtAck response."; },
×
1000
            [&](WorkItemGetAll&) { LogWarn() << "Unexpected ParamExtAck response."; }},
×
1001
        work->work_item_variant);
2✔
1002
}
1003

1004
void MavlinkParameterClient::receive_timeout()
22✔
1005
{
1006
    // See comments on process_param_value for use of unique_ptr
1007
    auto work_queue_guard = std::make_unique<LockedQueue<WorkItem>::Guard>(_work_queue);
22✔
1008

1009
    auto work = work_queue_guard->get_front();
22✔
1010
    if (!work) {
22✔
1011
        LogErr() << "Received timeout without work";
×
1012
        return;
×
1013
    }
1014
    if (!work->already_requested) {
22✔
1015
        LogErr() << "Received timeout without already having work requested";
×
1016
        return;
×
1017
    }
1018

1019
    std::visit(
44✔
1020
        overloaded{
22✔
1021
            [&](WorkItemSet& item) {
2✔
1022
                if (work->retries_to_do > 0) {
2✔
1023
                    // We're not sure the command arrived, let's retransmit.
1024
                    LogWarn() << "sending again, retries to do: " << work->retries_to_do << "  ("
4✔
1025
                              << item.param_name << ").";
4✔
1026

1027
                    if (!send_set_param_message(item)) {
2✔
1028
                        LogErr() << "connection send error in retransmit (" << item.param_name
×
1029
                                 << ").";
×
1030
                        work_queue_guard->pop_front();
×
1031

1032
                        if (item.callback) {
×
1033
                            auto callback = item.callback;
×
1034
                            work_queue_guard.reset();
×
1035
                            callback(Result::ConnectionError);
×
1036
                        }
1037
                    } else {
1038
                        --work->retries_to_do;
2✔
1039
                        _timeout_handler.add(
2✔
1040
                            [this] { receive_timeout(); }, _timeout_s_callback(), &_timeout_cookie);
1✔
1041
                    }
1042
                } else {
1043
                    // We have tried retransmitting, giving up now.
1044
                    LogErr() << "Error: Retrying failed set param timeout: " << item.param_name;
×
1045
                    work_queue_guard->pop_front();
×
1046
                    if (item.callback) {
×
1047
                        auto callback = item.callback;
×
1048
                        work_queue_guard.reset();
×
1049
                        callback(Result::Timeout);
×
1050
                    }
1051
                }
1052
            },
2✔
1053
            [&](WorkItemGet& item) {
15✔
1054
                if (work->retries_to_do > 0) {
15✔
1055
                    // We're not sure the command arrived, let's retransmit.
1056
                    LogWarn() << "sending again, retries to do: " << work->retries_to_do;
13✔
1057
                    if (!send_get_param_message(item)) {
13✔
1058
                        LogErr() << "connection send error in retransmit ";
×
1059
                        work_queue_guard->pop_front();
×
1060
                        if (item.callback) {
×
1061
                            auto callback = item.callback;
×
1062
                            work_queue_guard.reset();
×
1063
                            callback(Result::ConnectionError, {});
×
1064
                        }
1065
                    } else {
1066
                        --work->retries_to_do;
13✔
1067
                        _timeout_handler.add(
13✔
1068
                            [this] { receive_timeout(); }, _timeout_s_callback(), &_timeout_cookie);
11✔
1069
                    }
1070
                } else {
1071
                    // We have tried retransmitting, giving up now.
1072
                    LogErr() << "retrying failed";
2✔
1073
                    work_queue_guard->pop_front();
2✔
1074
                    if (item.callback) {
2✔
1075
                        auto callback = item.callback;
4✔
1076
                        work_queue_guard.reset();
2✔
1077
                        callback(Result::Timeout, {});
2✔
1078
                    }
1079
                }
1080
            },
15✔
1081
            [&](WorkItemGetAll& item) {
5✔
1082
                // Request missing parameters.
1083
                // If retries are exceeded, give up with timeout.
1084

1085
                if (_parameter_debugging) {
5✔
1086
                    LogDebug() << "All params receive timeout with";
×
1087
                }
1088

1089
                if (item.count == 0) {
5✔
1090
                    // We got 0 messages back from the server (param count unknown). Most likely the
1091
                    // "list request" got lost before making it to the server,
1092
                    if (work->retries_to_do > 0) {
×
1093
                        --work->retries_to_do;
×
1094

1095
                        if (!send_request_list_message()) {
×
1096
                            LogErr() << "Send message failed";
×
1097
                            work_queue_guard->pop_front();
×
1098
                            if (item.callback) {
×
1099
                                auto callback = item.callback;
×
1100
                                work_queue_guard.reset();
×
1101
                                item.callback(Result::ConnectionError, {});
×
1102
                            }
1103
                            return;
×
1104
                        }
1105

1106
                        // We want to get notified if a timeout happens
1107
                        _timeout_handler.add(
×
1108
                            [this] { receive_timeout(); }, _timeout_s_callback(), &_timeout_cookie);
×
1109
                    } else {
1110
                        if (item.callback) {
×
1111
                            auto callback = item.callback;
×
1112
                            work_queue_guard.reset();
×
1113
                            item.callback(Result::Timeout, {});
×
1114
                        }
1115
                        return;
×
1116
                    }
1117

1118
                } else {
1119
                    item.rerequesting = true;
5✔
1120
                    auto maybe_next_missing_index = _param_cache.next_missing_index(item.count);
5✔
1121
                    if (!maybe_next_missing_index.has_value()) {
5✔
1122
                        LogErr() << "logic error, there should a missing index";
×
1123
                        assert(false);
×
1124
                    }
1125

1126
                    if (_parameter_debugging) {
5✔
1127
                        LogDebug() << "Requesting missing parameter "
×
1128
                                   << (int)maybe_next_missing_index.value();
×
1129
                    }
1130

1131
                    std::array<char, PARAM_ID_LEN> param_id_buff{};
5✔
1132

1133
                    if (!send_get_param_message(param_id_buff, maybe_next_missing_index.value())) {
5✔
1134
                        LogErr() << "Send message failed";
×
1135
                        work_queue_guard->pop_front();
×
1136
                        if (item.callback) {
×
1137
                            auto callback = item.callback;
×
1138
                            work_queue_guard.reset();
×
1139
                            callback(Result::ConnectionError, {});
×
1140
                        }
1141
                        return;
×
1142
                    }
1143
                    _timeout_handler.add(
5✔
1144
                        [this] { receive_timeout(); }, _timeout_s_callback(), &_timeout_cookie);
3✔
1145
                }
1146
            }},
1147
        work->work_item_variant);
22✔
1148
}
1149

1150
std::ostream& operator<<(std::ostream& str, const MavlinkParameterClient::Result& result)
×
1151
{
1152
    switch (result) {
×
1153
        case MavlinkParameterClient::Result::Success:
×
1154
            return str << "Success";
×
1155
        case MavlinkParameterClient::Result::Timeout:
×
1156
            return str << "Timeout";
×
1157
        case MavlinkParameterClient::Result::ConnectionError:
×
1158
            return str << "ConnectionError";
×
1159
        case MavlinkParameterClient::Result::WrongType:
×
1160
            return str << "WrongType";
×
1161
        case MavlinkParameterClient::Result::ParamNameTooLong:
×
1162
            return str << "ParamNameTooLong";
×
1163
        case MavlinkParameterClient::Result::NotFound:
×
1164
            return str << "NotFound";
×
1165
        case MavlinkParameterClient::Result::ValueUnsupported:
×
1166
            return str << "ValueUnsupported";
×
1167
        case MavlinkParameterClient::Result::Failed:
×
1168
            return str << "Failed";
×
1169
        case MavlinkParameterClient::Result::UnknownError:
×
1170
            // Fallthrough
1171
        default:
1172
            return str << "UnknownError";
×
1173
    }
1174
}
1175

1176
bool MavlinkParameterClient::validate_id_or_index(
12✔
1177
    const std::variant<std::string, int16_t>& original,
1178
    const std::string& param_id,
1179
    const int16_t param_index)
1180
{
1181
    if (const auto str = std::get_if<std::string>(&original)) {
12✔
1182
        if (param_id != *str) {
12✔
1183
            // We requested by string id, but response doesn't match
1184
            return false;
×
1185
        }
1186
    } else {
1187
        const auto tmp = std::get<int16_t>(original);
×
1188
        if (param_index != tmp) {
×
1189
            // We requested by index, but response doesn't match
1190
            return false;
×
1191
        }
1192
    }
1193
    return true;
12✔
1194
}
1195

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