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

mavlink / MAVSDK / 5041356744

pending completion
5041356744

push

github

GitHub
Merge pull request #1772 from mavlink/pr-split-mavlink-params

2216 of 2216 new or added lines in 34 files covered. (100.0%)

7715 of 24842 relevant lines covered (31.06%)

20.02 hits per line

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

70.12
/src/mavsdk/core/mavlink_parameter_server.cpp
1
#include "mavlink_parameter_server.h"
2
#include "mavlink_parameter_helper.h"
3
#include "plugin_base.h"
4
#include <cassert>
5

6
namespace mavsdk {
7

8
MavlinkParameterServer::MavlinkParameterServer(
20✔
9
    Sender& sender,
10
    MavlinkMessageHandler& message_handler,
11
    std::optional<std::map<std::string, ParamValue>> optional_param_values) :
20✔
12
    _sender(sender),
13
    _message_handler(message_handler)
20✔
14
{
15
    if (const char* env_p = std::getenv("MAVSDK_PARAMETER_DEBUGGING")) {
20✔
16
        if (std::string(env_p) == "1") {
×
17
            LogDebug() << "Parameter debugging is on.";
×
18
            _parameter_debugging = true;
×
19
        }
20
    }
21

22
    // Populate the parameter set before the first communication, if provided by the user.
23
    if (optional_param_values.has_value()) {
20✔
24
        const auto& param_values = optional_param_values.value();
×
25
        for (const auto& [key, value] : param_values) {
×
26
            const auto result = provide_server_param(key, value);
×
27
            if (result != Result::Success) {
×
28
                LogDebug() << "Cannot add parameter:" << key << ":" << value << " " << result;
×
29
            }
30
        }
31
    }
32

33
    _message_handler.register_one(
20✔
34
        MAVLINK_MSG_ID_PARAM_SET,
35
        [this](const mavlink_message_t& message) { process_param_set(message); },
7✔
36
        this);
37

38
    _message_handler.register_one(
20✔
39
        MAVLINK_MSG_ID_PARAM_EXT_SET,
40
        [this](const mavlink_message_t& message) { process_param_ext_set(message); },
2✔
41
        this);
42

43
    _message_handler.register_one(
20✔
44
        MAVLINK_MSG_ID_PARAM_REQUEST_READ,
45
        [this](const mavlink_message_t& message) { process_param_request_read(message); },
25✔
46
        this);
47

48
    _message_handler.register_one(
20✔
49
        MAVLINK_MSG_ID_PARAM_REQUEST_LIST,
50
        [this](const mavlink_message_t& message) { process_param_request_list(message); },
2✔
51
        this);
52

53
    _message_handler.register_one(
20✔
54
        MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ,
55
        [this](const mavlink_message_t& message) { process_param_ext_request_read(message); },
8✔
56
        this);
57

58
    _message_handler.register_one(
20✔
59
        MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST,
60
        [this](const mavlink_message_t& message) { process_param_ext_request_list(message); },
2✔
61
        this);
62
}
20✔
63

64
MavlinkParameterServer::~MavlinkParameterServer()
20✔
65
{
66
    _message_handler.unregister_all(this);
20✔
67
}
20✔
68

69
MavlinkParameterServer::Result
70
MavlinkParameterServer::provide_server_param(const std::string& name, const ParamValue& param_value)
24✔
71
{
72
    if (name.size() > PARAM_ID_LEN) {
24✔
73
        LogErr() << "Error: param name too long";
×
74
        return Result::ParamNameTooLong;
×
75
    }
76
    if (param_value.is<std::string>()) {
24✔
77
        const auto s = param_value.get<std::string>();
8✔
78
        if (s.size() > sizeof(mavlink_param_ext_set_t::param_value)) {
8✔
79
            LogErr() << "Error: param value too long";
×
80
            return Result::ParamValueTooLong;
×
81
        }
82
    }
83
    std::lock_guard<std::mutex> lock(_all_params_mutex);
48✔
84
    // first we try to add it as a new parameter
85
    switch (_param_cache.add_new_param(name, param_value)) {
24✔
86
        case MavlinkParameterCache::AddNewParamResult::Ok:
24✔
87
            return Result::Success;
24✔
88
        case MavlinkParameterCache::AddNewParamResult::AlreadyExists:
×
89
            return Result::ParamExistsAlready;
×
90
        case MavlinkParameterCache::AddNewParamResult::TooManyParams:
×
91
            return Result::TooManyParams;
×
92
        default:
×
93
            LogErr() << "Unknown add_new_param result";
×
94
            assert(false);
×
95
    }
96

97
    // then, to not change the public api behaviour, try updating its value.
98
    switch (_param_cache.update_existing_param(name, param_value)) {
99
        case MavlinkParameterCache::UpdateExistingParamResult::Ok:
100
            return Result::Success;
101
        case MavlinkParameterCache::UpdateExistingParamResult::MissingParam:
102
            return Result::ParamNotFound;
103
        case MavlinkParameterCache::UpdateExistingParamResult::WrongType:
104
            return Result::WrongType;
105
        default:
106
            LogErr() << "Unknown update_existing_param result";
107
            assert(false);
108
    }
109

110
    return Result::Unknown;
111
}
112

113
MavlinkParameterServer::Result
114
MavlinkParameterServer::provide_server_param_float(const std::string& name, float value)
8✔
115
{
116
    ParamValue param_value;
16✔
117
    param_value.set(value);
8✔
118
    return provide_server_param(name, param_value);
8✔
119
}
120

121
MavlinkParameterServer::Result
122
MavlinkParameterServer::provide_server_param_int(const std::string& name, int32_t value)
8✔
123
{
124
    ParamValue param_value;
16✔
125
    param_value.set(value);
8✔
126
    return provide_server_param(name, param_value);
8✔
127
}
128

129
MavlinkParameterServer::Result MavlinkParameterServer::provide_server_param_custom(
8✔
130
    const std::string& name, const std::string& value)
131
{
132
    ParamValue param_value;
16✔
133
    param_value.set(value);
8✔
134
    return provide_server_param(name, param_value);
8✔
135
}
136

137
std::map<std::string, ParamValue> MavlinkParameterServer::retrieve_all_server_params()
2✔
138
{
139
    std::lock_guard<std::mutex> lock(_all_params_mutex);
4✔
140
    std::map<std::string, ParamValue> map_copy;
2✔
141
    for (auto entry : _param_cache.all_parameters(true)) {
6✔
142
        map_copy[entry.id] = entry.value;
4✔
143
    }
144
    return map_copy;
2✔
145
}
146

147
template<class T>
148
std::pair<MavlinkParameterServer::Result, T>
149
MavlinkParameterServer::retrieve_server_param(const std::string& name)
2✔
150
{
151
    std::lock_guard<std::mutex> lock(_all_params_mutex);
4✔
152
    const auto param_opt = _param_cache.param_by_id(name, true);
4✔
153
    if (!param_opt.has_value()) {
2✔
154
        return {Result::NotFound, {}};
×
155
    }
156
    // This parameter exists, check its type
157
    const auto& param = param_opt.value();
2✔
158
    if (param.value.is<T>()) {
2✔
159
        return {Result::Success, param.value.get<T>()};
2✔
160
    }
161
    return {Result::WrongType, {}};
×
162
}
163

164
std::pair<MavlinkParameterServer::Result, float>
165
MavlinkParameterServer::retrieve_server_param_float(const std::string& name)
2✔
166
{
167
    return retrieve_server_param<float>(name);
2✔
168
}
169

170
std::pair<MavlinkParameterServer::Result, std::string>
171
MavlinkParameterServer::retrieve_server_param_custom(const std::string& name)
2✔
172
{
173
    return retrieve_server_param<std::string>(name);
2✔
174
}
175

176
std::pair<MavlinkParameterServer::Result, int32_t>
177
MavlinkParameterServer::retrieve_server_param_int(const std::string& name)
2✔
178
{
179
    return retrieve_server_param<int32_t>(name);
2✔
180
}
181

182
void MavlinkParameterServer::process_param_set_internally(
9✔
183
    const std::string& param_id, const ParamValue& value_to_set, bool extended)
184
{
185
    // TODO: add debugging env
186
    LogDebug() << "Param set request" << (extended ? " extended" : "") << ": " << param_id
27✔
187
               << " with " << value_to_set;
27✔
188
    std::lock_guard<std::mutex> lock(_all_params_mutex);
9✔
189
    // for checking if the update actually changed the value
190
    const auto opt_before_update = _param_cache.param_by_id(param_id, extended);
9✔
191
    const auto result = _param_cache.update_existing_param(param_id, value_to_set);
9✔
192
    const auto param_count = _param_cache.count(extended);
9✔
193

194
    switch (result) {
9✔
195
        case MavlinkParameterCache::UpdateExistingParamResult::MissingParam: {
×
196
            // We do not allow clients to add a new parameter to the parameter set, only to update
197
            // existing parameters. In this case, we cannot even respond with anything, since this
198
            // parameter simply does not exist.
199
            LogErr() << "Got param_set for non-existing parameter:" << param_id;
×
200
            return;
×
201
        }
202
        case MavlinkParameterCache::UpdateExistingParamResult::WrongType: {
×
203
            // Non-extended: we respond with the unchanged parameter.
204
            // Extended: we nack with failed.
205

206
            LogErr() << "Got param_set with wrong type for parameter: " << param_id;
×
207

208
            const auto curr_param = _param_cache.param_by_id(param_id, extended).value();
×
209

210
            if (extended) {
×
211
                auto new_work = std::make_shared<WorkItem>(
×
212
                    curr_param.id, curr_param.value, WorkItemAck{PARAM_ACK_FAILED});
×
213
                _work_queue.push_back(new_work);
×
214

215
            } else {
216
                auto new_work = std::make_shared<WorkItem>(
×
217
                    curr_param.id,
218
                    curr_param.value,
219
                    WorkItemValue{curr_param.index, param_count, extended});
×
220
                _work_queue.push_back(new_work);
×
221
            }
222
            return;
×
223
        }
224
        case MavlinkParameterCache::UpdateExistingParamResult::Ok: {
9✔
225
            const auto updated_parameter = _param_cache.param_by_id(param_id, extended).value();
27✔
226
            // The param set doesn't differentiate between an update that actually changed the value
227
            // e.g. 0 to 1 and an update that had no effect e.g. 0 to 0.
228
            if (opt_before_update.has_value() &&
18✔
229
                opt_before_update.value().value == updated_parameter.value) {
9✔
230
                LogDebug() << "Update had no effect: " << updated_parameter.value;
3✔
231
            } else {
232
                LogDebug() << "Updated param to :" << updated_parameter.value;
6✔
233
                find_and_call_subscriptions_value_changed(
6✔
234
                    updated_parameter.id, updated_parameter.value);
235
            }
236
            if (extended) {
9✔
237
                auto new_work = std::make_shared<WorkItem>(
2✔
238
                    updated_parameter.id, updated_parameter.value, WorkItemAck{PARAM_ACK_ACCEPTED});
4✔
239
                _work_queue.push_back(new_work);
2✔
240
            } else {
241
                auto new_work = std::make_shared<WorkItem>(
7✔
242
                    updated_parameter.id,
243
                    updated_parameter.value,
244
                    WorkItemValue{updated_parameter.index, param_count, extended});
14✔
245
                _work_queue.push_back(new_work);
7✔
246
            }
247
        } break;
248
    }
249
}
250

251
void MavlinkParameterServer::process_param_set(const mavlink_message_t& message)
7✔
252
{
253
    mavlink_param_set_t set_request{};
7✔
254
    mavlink_msg_param_set_decode(&message, &set_request);
7✔
255
    if (!target_matches(set_request.target_system, set_request.target_component, false)) {
7✔
256
        log_target_mismatch(set_request.target_system, set_request.target_component);
×
257
        return;
×
258
    }
259
    const std::string safe_param_id = extract_safe_param_id(set_request.param_id);
7✔
260

261
    if (safe_param_id.empty()) {
7✔
262
        LogWarn() << "Got ill-formed param_set message (param_id empty)";
×
263
        return;
×
264
    }
265

266
    ParamValue value_to_set;
7✔
267
    if (!value_to_set.set_from_mavlink_param_set_bytewise(set_request)) {
7✔
268
        // This should never happen, the type enum in the message is unknown.
269
        LogWarn() << "Invalid Param Set Request: " << safe_param_id;
×
270
        return;
×
271
    }
272
    process_param_set_internally(safe_param_id, value_to_set, false);
7✔
273
}
274

275
void MavlinkParameterServer::process_param_ext_set(const mavlink_message_t& message)
2✔
276
{
277
    mavlink_param_ext_set_t set_request{};
2✔
278
    mavlink_msg_param_ext_set_decode(&message, &set_request);
2✔
279
    if (!target_matches(set_request.target_system, set_request.target_component, false)) {
2✔
280
        log_target_mismatch(set_request.target_system, set_request.target_component);
×
281
        return;
×
282
    }
283
    const std::string safe_param_id = extract_safe_param_id(set_request.param_id);
2✔
284

285
    if (safe_param_id.empty()) {
2✔
286
        LogWarn() << "Got ill-formed param_ext_set message (param_id empty)";
×
287
        return;
×
288
    }
289

290
    ParamValue value_to_set;
2✔
291
    if (!value_to_set.set_from_mavlink_param_ext_set(set_request)) {
2✔
292
        // This should never happen, the type enum in the message is unknown.
293
        LogWarn() << "Invalid Param Set ext Request: " << safe_param_id;
×
294
        return;
×
295
    }
296
    process_param_set_internally(safe_param_id, value_to_set, true);
2✔
297
}
298

299
void MavlinkParameterServer::process_param_request_read(const mavlink_message_t& message)
25✔
300
{
301
    if (_parameter_debugging) {
25✔
302
        LogDebug() << "process param_request_read";
×
303
    }
304
    mavlink_param_request_read_t read_request{};
25✔
305
    mavlink_msg_param_request_read_decode(&message, &read_request);
25✔
306
    if (!target_matches(read_request.target_system, read_request.target_component, true)) {
25✔
307
        log_target_mismatch(read_request.target_system, read_request.target_component);
×
308
        return;
×
309
    }
310

311
    const auto param_id_or_index =
25✔
312
        extract_request_read_param_identifier(read_request.param_index, read_request.param_id);
50✔
313

314
    std::visit(
25✔
315
        overloaded{
25✔
316
            [&](std::monostate) { LogWarn() << "Ill-formed param_request_read message"; },
×
317
            [&](std::uint16_t index) {
2✔
318
                if (_parameter_debugging) {
2✔
319
                    LogDebug() << "found index: " << index;
×
320
                }
321
                internal_process_param_request_read_by_index(index, false);
2✔
322
            },
2✔
323
            [&](const std::string& id) {
23✔
324
                if (_parameter_debugging) {
23✔
325
                    LogDebug() << "found id: " << id;
×
326
                }
327
                internal_process_param_request_read_by_id(id, false);
23✔
328
            }},
23✔
329
        param_id_or_index);
330
}
331

332
void MavlinkParameterServer::process_param_ext_request_read(const mavlink_message_t& message)
8✔
333
{
334
    LogDebug() << "process param_ext_request_read";
8✔
335
    mavlink_param_ext_request_read_t read_request{};
8✔
336
    mavlink_msg_param_ext_request_read_decode(&message, &read_request);
8✔
337
    if (!target_matches(read_request.target_system, read_request.target_component, true)) {
8✔
338
        log_target_mismatch(read_request.target_system, read_request.target_component);
×
339
        return;
×
340
    }
341
    const auto param_id_or_index =
8✔
342
        extract_request_read_param_identifier(read_request.param_index, read_request.param_id);
16✔
343

344
    std::visit(
8✔
345
        overloaded{
8✔
346
            [&](std::monostate) { LogWarn() << "Ill-formed param_request_read message"; },
×
347
            [&](std::uint16_t index) {
2✔
348
                if (_parameter_debugging) {
2✔
349
                    LogDebug() << "found index: " << index;
×
350
                }
351
                internal_process_param_request_read_by_index(index, true);
2✔
352
            },
2✔
353
            [&](const std::string& id) {
6✔
354
                if (_parameter_debugging) {
6✔
355
                    LogDebug() << "found id: " << id;
×
356
                }
357
                internal_process_param_request_read_by_id(id, true);
6✔
358
            }},
6✔
359
        param_id_or_index);
360
}
361

362
void MavlinkParameterServer::internal_process_param_request_read_by_id(
29✔
363
    const std::string& id, const bool extended)
364
{
365
    std::lock_guard<std::mutex> lock(_all_params_mutex);
29✔
366
    const auto param_opt = _param_cache.param_by_id(id, extended);
29✔
367

368
    if (!param_opt.has_value()) {
29✔
369
        LogWarn() << "Ignoring request_read message " << (extended ? "extended " : "")
36✔
370
                  << "- param name not found: " << id;
36✔
371
        return;
12✔
372
    }
373
    const auto& param = param_opt.value();
17✔
374
    const auto param_count = _param_cache.count(extended);
17✔
375
    assert(param.index < param_count);
17✔
376
    auto new_work = std::make_shared<WorkItem>(
17✔
377
        param.id, param.value, WorkItemValue{param.index, param_count, extended});
34✔
378
    _work_queue.push_back(new_work);
17✔
379
}
380

381
void MavlinkParameterServer::internal_process_param_request_read_by_index(
4✔
382
    std::uint16_t index, bool extended)
383
{
384
    std::lock_guard<std::mutex> lock(_all_params_mutex);
4✔
385
    const auto param_opt = _param_cache.param_by_index(index, extended);
4✔
386

387
    if (!param_opt.has_value()) {
4✔
388
        LogWarn() << "Ignoring request_read message " << (extended ? "extended " : "")
×
389
                  << "- param index not found: " << index;
×
390
        return;
×
391
    }
392
    const auto& param = param_opt.value();
4✔
393
    const auto param_count = _param_cache.count(extended);
4✔
394

395
    assert(param.index < param_count);
4✔
396
    auto new_work = std::make_shared<WorkItem>(
4✔
397
        param.id, param.value, WorkItemValue{param.index, param_count, extended});
8✔
398
    _work_queue.push_back(new_work);
4✔
399
}
400

401
void MavlinkParameterServer::process_param_request_list(const mavlink_message_t& message)
2✔
402
{
403
    mavlink_param_request_list_t list_request{};
2✔
404
    mavlink_msg_param_request_list_decode(&message, &list_request);
2✔
405
    if (!target_matches(list_request.target_system, list_request.target_component, true)) {
2✔
406
        log_target_mismatch(list_request.target_system, list_request.target_component);
×
407
        return;
×
408
    }
409
    broadcast_all_parameters(false);
2✔
410
}
411

412
void MavlinkParameterServer::process_param_ext_request_list(const mavlink_message_t& message)
2✔
413
{
414
    if (_parameter_debugging) {
2✔
415
        LogDebug() << "process param_ext_request_list";
×
416
    }
417

418
    mavlink_param_ext_request_list_t ext_list_request{};
2✔
419
    mavlink_msg_param_ext_request_list_decode(&message, &ext_list_request);
2✔
420
    if (!target_matches(ext_list_request.target_system, ext_list_request.target_component, true)) {
2✔
421
        log_target_mismatch(ext_list_request.target_system, ext_list_request.target_component);
×
422
        return;
×
423
    }
424
    broadcast_all_parameters(true);
2✔
425
}
426

427
void MavlinkParameterServer::broadcast_all_parameters(const bool extended)
4✔
428
{
429
    std::lock_guard<std::mutex> lock(_all_params_mutex);
8✔
430
    const auto all_params = _param_cache.all_parameters(extended);
8✔
431
    if (_parameter_debugging) {
4✔
432
        LogDebug() << "broadcast_all_parameters " << (extended ? "extended" : "") << ": "
×
433
                   << all_params.size();
×
434
    }
435
    for (const auto& parameter : all_params) {
34✔
436
        if (_parameter_debugging) {
30✔
437
            LogDebug() << "sending param:" << parameter.id;
×
438
        }
439
        auto new_work = std::make_shared<WorkItem>(
30✔
440
            parameter.id,
30✔
441
            parameter.value,
30✔
442
            WorkItemValue{parameter.index, static_cast<uint16_t>(all_params.size()), extended});
60✔
443
        _work_queue.push_back(new_work);
30✔
444
    }
445
}
4✔
446

447
void MavlinkParameterServer::do_work()
745✔
448
{
449
    LockedQueue<WorkItem>::Guard work_queue_guard(_work_queue);
745✔
450
    auto work = work_queue_guard.get_front();
743✔
451
    if (!work) {
741✔
452
        return;
684✔
453
    }
454
    const auto param_id_message_buffer = param_id_to_message_buffer(work->param_id);
60✔
455

456
    mavlink_message_t mavlink_message;
60✔
457

458
    std::visit(
120✔
459
        overloaded{
60✔
460
            [&](const WorkItemValue& specific) {
58✔
461
                if (specific.extended) {
58✔
462
                    const auto buf = work->param_value.get_128_bytes();
26✔
463
                    mavlink_msg_param_ext_value_pack(
52✔
464
                        _sender.get_own_system_id(),
26✔
465
                        _sender.get_own_component_id(),
26✔
466
                        &mavlink_message,
26✔
467
                        param_id_message_buffer.data(),
26✔
468
                        buf.data(),
469
                        work->param_value.get_mav_param_ext_type(),
26✔
470
                        specific.param_count,
26✔
471
                        specific.param_index);
26✔
472
                } else {
473
                    float param_value;
474
                    if (_sender.autopilot() == Sender::Autopilot::ArduPilot) {
32✔
475
                        param_value = work->param_value.get_4_float_bytes_cast();
×
476
                    } else {
477
                        param_value = work->param_value.get_4_float_bytes_bytewise();
32✔
478
                    }
479
                    mavlink_msg_param_value_pack(
64✔
480
                        _sender.get_own_system_id(),
32✔
481
                        _sender.get_own_component_id(),
32✔
482
                        &mavlink_message,
483
                        param_id_message_buffer.data(),
484
                        param_value,
485
                        work->param_value.get_mav_param_type(),
32✔
486
                        specific.param_count,
32✔
487
                        specific.param_index);
32✔
488
                }
489
                if (!_sender.send_message(mavlink_message)) {
58✔
490
                    LogErr() << "Error: Send message failed";
×
491
                    work_queue_guard.pop_front();
×
492
                    return;
×
493
                }
494
                work_queue_guard.pop_front();
58✔
495
            },
496
            [&](const WorkItemAck& specific) {
2✔
497
                auto buf = work->param_value.get_128_bytes();
2✔
498
                mavlink_msg_param_ext_ack_pack(
2✔
499
                    _sender.get_own_system_id(),
2✔
500
                    _sender.get_own_component_id(),
2✔
501
                    &mavlink_message,
2✔
502
                    param_id_message_buffer.data(),
2✔
503
                    buf.data(),
2✔
504
                    work->param_value.get_mav_param_ext_type(),
2✔
505
                    specific.param_ack);
2✔
506
                if (!_sender.send_message(mavlink_message)) {
2✔
507
                    LogErr() << "Error: Send message failed";
×
508
                    work_queue_guard.pop_front();
×
509
                    return;
×
510
                }
511
                work_queue_guard.pop_front();
2✔
512
            }},
513
        work->work_item_variant);
60✔
514
}
515

516
std::ostream& operator<<(std::ostream& str, const MavlinkParameterServer::Result& result)
×
517
{
518
    switch (result) {
×
519
        case MavlinkParameterServer::Result::Success:
×
520
            return str << "Success";
×
521
        case MavlinkParameterServer::Result::WrongType:
×
522
            return str << "WrongType";
×
523
        case MavlinkParameterServer::Result::ParamNameTooLong:
×
524
            return str << "ParamNameTooLong";
×
525
        case MavlinkParameterServer::Result::NotFound:
×
526
            return str << "NotFound";
×
527
        case MavlinkParameterServer::Result::ParamValueTooLong:
×
528
            return str << ":ParamValueTooLong";
×
529
        default:
×
530
            return str << "UnknownError";
×
531
    }
532
}
533

534
bool MavlinkParameterServer::target_matches(
46✔
535
    const uint16_t target_sys_id, const uint16_t target_comp_id, bool is_request)
536
{
537
    // See: https://mavlink.io/en/services/parameter.html#multi-system-and-multi-component-support
538

539
    if (target_sys_id != _sender.get_own_system_id()) {
46✔
540
        return false;
×
541
    }
542
    if (is_request) {
46✔
543
        return target_comp_id == _sender.get_own_component_id() ||
37✔
544
               target_comp_id == MAV_COMP_ID_ALL;
37✔
545
    }
546
    return target_comp_id == _sender.get_own_component_id();
9✔
547
}
548

549
void MavlinkParameterServer::log_target_mismatch(uint16_t target_sys_id, uint16_t target_comp_id)
×
550
{
551
    if (!_parameter_debugging) {
×
552
        return;
×
553
    }
554

555
    LogDebug() << "Ignoring message - wrong target id. Got:" << (int)target_sys_id << ":"
×
556
               << (int)target_comp_id << " Wanted:" << (int)_sender.get_own_system_id() << ":"
×
557
               << (int)_sender.get_own_component_id();
×
558
}
559

560
std::variant<std::monostate, std::string, std::uint16_t>
561
MavlinkParameterServer::extract_request_read_param_identifier(
33✔
562
    int16_t param_index, const char* param_id)
563
{
564
    // Helper for safely handling a request_read or ext_request_read message (which have the exact
565
    // same layout). returns the identifier that should be used or nothing if the message is
566
    // ill-formed. See https://mavlink.io/en/messages/common.html#PARAM_REQUEST_READ and
567
    // https://mavlink.io/en/messages/common.html#PARAM_EXT_REQUEST_READ
568

569
    if (param_index == -1) {
33✔
570
        // use param_id if index == -1
571
        const auto safe_param_id = extract_safe_param_id(param_id);
58✔
572
        if (safe_param_id.empty()) {
29✔
573
            LogErr() << "Message with param_index=-1 but no empty param id";
×
574
            return std::monostate{};
×
575
        }
576
        return {safe_param_id};
29✔
577
    } else {
578
        // if index is not -1, it should be a valid parameter index (>=0)
579
        if (param_index < 0) {
4✔
580
            LogErr() << "Param_index " << param_index << " is not a valid param index";
×
581
            return std::monostate{};
×
582
        }
583
        return {static_cast<std::uint16_t>(param_index)};
4✔
584
    }
585
}
586

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