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

mavlink / MAVSDK / 4899817366

pending completion
4899817366

Pull #1772

github

GitHub
Merge c0bb90862 into e4e9c71dd
Pull Request #1772: Refactor MAVLinkParameters into client and server classes

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

7708 of 24812 relevant lines covered (31.07%)

19.96 hits per line

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

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

6
namespace mavsdk {
7

8
MavlinkParameterReceiver::MavlinkParameterReceiver(
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
    // Populate the parameter set before the first communication, if provided by the user.
16
    if (optional_param_values.has_value()) {
20✔
17
        const auto& param_values = optional_param_values.value();
×
18
        for (const auto& [key, value] : param_values) {
×
19
            const auto result = provide_server_param(key, value);
×
20
            if (result != Result::Success) {
×
21
                LogDebug() << "Cannot add parameter:" << key << ":" << value << " " << result;
×
22
            }
23
        }
24
    }
25

26
    _message_handler.register_one(
20✔
27
        MAVLINK_MSG_ID_PARAM_SET,
28
        [this](const mavlink_message_t& message) { process_param_set(message); },
7✔
29
        this);
30

31
    _message_handler.register_one(
20✔
32
        MAVLINK_MSG_ID_PARAM_EXT_SET,
33
        [this](const mavlink_message_t& message) { process_param_ext_set(message); },
2✔
34
        this);
35

36
    _message_handler.register_one(
20✔
37
        MAVLINK_MSG_ID_PARAM_REQUEST_READ,
38
        [this](const mavlink_message_t& message) { process_param_request_read(message); },
21✔
39
        this);
40

41
    _message_handler.register_one(
20✔
42
        MAVLINK_MSG_ID_PARAM_REQUEST_LIST,
43
        [this](const mavlink_message_t& message) { process_param_request_list(message); },
2✔
44
        this);
45

46
    _message_handler.register_one(
20✔
47
        MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ,
48
        [this](const mavlink_message_t& message) { process_param_ext_request_read(message); },
6✔
49
        this);
50

51
    _message_handler.register_one(
20✔
52
        MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST,
53
        [this](const mavlink_message_t& message) { process_param_ext_request_list(message); },
3✔
54
        this);
55
}
20✔
56

57
MavlinkParameterReceiver::~MavlinkParameterReceiver()
20✔
58
{
59
    _message_handler.unregister_all(this);
20✔
60
}
20✔
61

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

90
    // then, to not change the public api behaviour, try updating its value.
91
    switch (_param_cache.update_existing_param(name, param_value)) {
92
        case MavlinkParameterCache::UpdateExistingParamResult::Ok:
93
            return Result::Success;
94
        case MavlinkParameterCache::UpdateExistingParamResult::MissingParam:
95
            return Result::ParamNotFound;
96
        case MavlinkParameterCache::UpdateExistingParamResult::WrongType:
97
            return Result::WrongType;
98
        default:
99
            LogErr() << "Unknown update_existing_param result";
100
            assert(false);
101
    }
102

103
    return Result::Unknown;
104
}
105

106
MavlinkParameterReceiver::Result
107
MavlinkParameterReceiver::provide_server_param_float(const std::string& name, float value)
8✔
108
{
109
    ParamValue param_value;
16✔
110
    param_value.set(value);
8✔
111
    return provide_server_param(name, param_value);
8✔
112
}
113

114
MavlinkParameterReceiver::Result
115
MavlinkParameterReceiver::provide_server_param_int(const std::string& name, int32_t value)
8✔
116
{
117
    ParamValue param_value;
16✔
118
    param_value.set(value);
8✔
119
    return provide_server_param(name, param_value);
8✔
120
}
121

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

130
std::map<std::string, ParamValue> MavlinkParameterReceiver::retrieve_all_server_params()
2✔
131
{
132
    std::lock_guard<std::mutex> lock(_all_params_mutex);
4✔
133
    std::map<std::string, ParamValue> map_copy;
2✔
134
    for (auto entry : _param_cache.all_parameters(true)) {
6✔
135
        map_copy[entry.id] = entry.value;
4✔
136
    }
137
    return map_copy;
2✔
138
}
139

140
template<class T>
141
std::pair<MavlinkParameterReceiver::Result, T>
142
MavlinkParameterReceiver::retrieve_server_param(const std::string& name)
2✔
143
{
144
    std::lock_guard<std::mutex> lock(_all_params_mutex);
4✔
145
    const auto param_opt = _param_cache.param_by_id(name, true);
4✔
146
    if (!param_opt.has_value()) {
2✔
147
        return {Result::NotFound, {}};
×
148
    }
149
    // This parameter exists, check its type
150
    const auto& param = param_opt.value();
2✔
151
    if (param.value.is<T>()) {
2✔
152
        return {Result::Success, param.value.get<T>()};
2✔
153
    }
154
    return {Result::WrongType, {}};
×
155
}
156

157
std::pair<MavlinkParameterReceiver::Result, float>
158
MavlinkParameterReceiver::retrieve_server_param_float(const std::string& name)
2✔
159
{
160
    return retrieve_server_param<float>(name);
2✔
161
}
162

163
std::pair<MavlinkParameterReceiver::Result, std::string>
164
MavlinkParameterReceiver::retrieve_server_param_custom(const std::string& name)
2✔
165
{
166
    return retrieve_server_param<std::string>(name);
2✔
167
}
168

169
std::pair<MavlinkParameterReceiver::Result, int32_t>
170
MavlinkParameterReceiver::retrieve_server_param_int(const std::string& name)
2✔
171
{
172
    return retrieve_server_param<int32_t>(name);
2✔
173
}
174

175
void MavlinkParameterReceiver::process_param_set_internally(
9✔
176
    const std::string& param_id, const ParamValue& value_to_set, bool extended)
177
{
178
    // TODO: add debugging env
179
    LogDebug() << "Param set request" << (extended ? " extended" : "") << ": " << param_id
27✔
180
               << " with " << value_to_set;
27✔
181
    std::lock_guard<std::mutex> lock(_all_params_mutex);
9✔
182
    // for checking if the update actually changed the value
183
    const auto opt_before_update = _param_cache.param_by_id(param_id, extended);
9✔
184
    const auto result = _param_cache.update_existing_param(param_id, value_to_set);
9✔
185
    const auto param_count = _param_cache.count(extended);
9✔
186

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

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

201
            const auto curr_param = _param_cache.param_by_id(param_id, extended).value();
×
202

203
            if (extended) {
×
204
                auto new_work = std::make_shared<WorkItem>(
×
205
                    curr_param.id, curr_param.value, WorkItemAck{PARAM_ACK_FAILED});
×
206
                _work_queue.push_back(new_work);
×
207

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

244
void MavlinkParameterReceiver::process_param_set(const mavlink_message_t& message)
7✔
245
{
246
    mavlink_param_set_t set_request{};
7✔
247
    mavlink_msg_param_set_decode(&message, &set_request);
7✔
248
    if (!target_matches(set_request.target_system, set_request.target_component, false)) {
7✔
249
        log_target_mismatch(set_request.target_system, set_request.target_component);
×
250
        return;
×
251
    }
252
    const std::string safe_param_id = extract_safe_param_id(set_request.param_id);
7✔
253

254
    if (safe_param_id.empty()) {
7✔
255
        LogWarn() << "Got ill-formed param_set message (param_id empty)";
×
256
        return;
×
257
    }
258

259
    ParamValue value_to_set;
7✔
260
    if (!value_to_set.set_from_mavlink_param_set_bytewise(set_request)) {
7✔
261
        // This should never happen, the type enum in the message is unknown.
262
        LogWarn() << "Invalid Param Set Request: " << safe_param_id;
×
263
        return;
×
264
    }
265
    process_param_set_internally(safe_param_id, value_to_set, false);
7✔
266
}
267

268
void MavlinkParameterReceiver::process_param_ext_set(const mavlink_message_t& message)
2✔
269
{
270
    mavlink_param_ext_set_t set_request{};
2✔
271
    mavlink_msg_param_ext_set_decode(&message, &set_request);
2✔
272
    if (!target_matches(set_request.target_system, set_request.target_component, false)) {
2✔
273
        log_target_mismatch(set_request.target_system, set_request.target_component);
×
274
        return;
×
275
    }
276
    const std::string safe_param_id = extract_safe_param_id(set_request.param_id);
2✔
277

278
    if (safe_param_id.empty()) {
2✔
279
        LogWarn() << "Got ill-formed param_ext_set message (param_id empty)";
×
280
        return;
×
281
    }
282

283
    ParamValue value_to_set;
2✔
284
    if (!value_to_set.set_from_mavlink_param_ext_set(set_request)) {
2✔
285
        // This should never happen, the type enum in the message is unknown.
286
        LogWarn() << "Invalid Param Set ext Request: " << safe_param_id;
×
287
        return;
×
288
    }
289
    process_param_set_internally(safe_param_id, value_to_set, true);
2✔
290
}
291

292
void MavlinkParameterReceiver::process_param_request_read(const mavlink_message_t& message)
21✔
293
{
294
    LogDebug() << "process param_request_read";
21✔
295
    mavlink_param_request_read_t read_request{};
21✔
296
    mavlink_msg_param_request_read_decode(&message, &read_request);
21✔
297
    if (!target_matches(read_request.target_system, read_request.target_component, true)) {
21✔
298
        log_target_mismatch(read_request.target_system, read_request.target_component);
×
299
        return;
×
300
    }
301

302
    const auto param_id_or_index =
21✔
303
        extract_request_read_param_identifier(read_request.param_index, read_request.param_id);
42✔
304

305
    std::visit(
21✔
306
        overloaded{
21✔
307
            [&](std::monostate) { LogWarn() << "Ill-formed param_request_read message"; },
×
308
            [&](std::uint16_t index) {
2✔
309
                internal_process_param_request_read_by_index(index, false);
2✔
310
            },
2✔
311
            [&](const std::string& id) { internal_process_param_request_read_by_id(id, false); }},
19✔
312
        param_id_or_index);
313
}
314

315
void MavlinkParameterReceiver::process_param_ext_request_read(const mavlink_message_t& message)
6✔
316
{
317
    LogDebug() << "process param_ext_request_read";
6✔
318
    mavlink_param_ext_request_read_t read_request{};
6✔
319
    mavlink_msg_param_ext_request_read_decode(&message, &read_request);
6✔
320
    if (!target_matches(read_request.target_system, read_request.target_component, true)) {
6✔
321
        log_target_mismatch(read_request.target_system, read_request.target_component);
×
322
        return;
×
323
    }
324
    const auto param_id_or_index =
6✔
325
        extract_request_read_param_identifier(read_request.param_index, read_request.param_id);
12✔
326

327
    std::visit(
6✔
328
        overloaded{
6✔
329
            [&](std::monostate) { LogWarn() << "Ill-formed param_request_read message"; },
×
330
            [&](std::uint16_t index) {
×
331
                internal_process_param_request_read_by_index(index, false);
×
332
            },
×
333
            [&](const std::string& id) { internal_process_param_request_read_by_id(id, true); }},
6✔
334
        param_id_or_index);
335
}
336

337
void MavlinkParameterReceiver::internal_process_param_request_read_by_id(
25✔
338
    const std::string& id, const bool extended)
339
{
340
    std::lock_guard<std::mutex> lock(_all_params_mutex);
25✔
341
    const auto param_opt = _param_cache.param_by_id(id, extended);
25✔
342

343
    if (!param_opt.has_value()) {
25✔
344
        LogWarn() << "Ignoring request_read message " << (extended ? "extended " : "")
24✔
345
                  << "- param name not found: " << id;
24✔
346
        return;
8✔
347
    }
348
    const auto& param = param_opt.value();
17✔
349
    const auto param_count = _param_cache.count(extended);
17✔
350
    assert(param.index < param_count);
17✔
351
    auto new_work = std::make_shared<WorkItem>(
17✔
352
        param.id, param.value, WorkItemValue{param.index, param_count, extended});
34✔
353
    _work_queue.push_back(new_work);
17✔
354
}
355

356
void MavlinkParameterReceiver::internal_process_param_request_read_by_index(
2✔
357
    std::uint16_t index, bool extended)
358
{
359
    std::lock_guard<std::mutex> lock(_all_params_mutex);
2✔
360
    const auto param_opt = _param_cache.param_by_index(index, extended);
2✔
361

362
    if (!param_opt.has_value()) {
2✔
363
        LogWarn() << "Ignoring request_read message " << (extended ? "extended " : "")
×
364
                  << "- param index not found: " << index;
×
365
        return;
×
366
    }
367
    const auto& param = param_opt.value();
2✔
368
    const auto param_count = _param_cache.count(extended);
2✔
369

370
    assert(param.index < param_count);
2✔
371
    auto new_work = std::make_shared<WorkItem>(
2✔
372
        param.id, param.value, WorkItemValue{param.index, param_count, extended});
4✔
373
    _work_queue.push_back(new_work);
2✔
374
}
375

376
void MavlinkParameterReceiver::process_param_request_list(const mavlink_message_t& message)
2✔
377
{
378
    mavlink_param_request_list_t list_request{};
2✔
379
    mavlink_msg_param_request_list_decode(&message, &list_request);
2✔
380
    if (!target_matches(list_request.target_system, list_request.target_component, true)) {
2✔
381
        log_target_mismatch(list_request.target_system, list_request.target_component);
×
382
        return;
×
383
    }
384
    broadcast_all_parameters(false);
2✔
385
}
386

387
void MavlinkParameterReceiver::process_param_ext_request_list(const mavlink_message_t& message)
3✔
388
{
389
    mavlink_param_ext_request_list_t ext_list_request{};
3✔
390
    mavlink_msg_param_ext_request_list_decode(&message, &ext_list_request);
3✔
391
    if (!target_matches(ext_list_request.target_system, ext_list_request.target_component, true)) {
3✔
392
        log_target_mismatch(ext_list_request.target_system, ext_list_request.target_component);
×
393
        return;
×
394
    }
395
    broadcast_all_parameters(true);
3✔
396
}
397

398
void MavlinkParameterReceiver::broadcast_all_parameters(const bool extended)
5✔
399
{
400
    std::lock_guard<std::mutex> lock(_all_params_mutex);
10✔
401
    const auto all_params = _param_cache.all_parameters(extended);
10✔
402
    LogDebug() << "broadcast_all_parameters " << (extended ? "extended" : "") << ": "
15✔
403
               << all_params.size();
15✔
404
    for (const auto& parameter : all_params) {
44✔
405
        LogDebug() << "sending param:" << parameter.id;
39✔
406
        auto new_work = std::make_shared<WorkItem>(
39✔
407
            parameter.id,
39✔
408
            parameter.value,
39✔
409
            WorkItemValue{parameter.index, static_cast<uint16_t>(all_params.size()), extended});
78✔
410
        _work_queue.push_back(new_work);
39✔
411
    }
412
}
5✔
413

414
void MavlinkParameterReceiver::do_work()
657✔
415
{
416
    LockedQueue<WorkItem>::Guard work_queue_guard(_work_queue);
657✔
417
    auto work = work_queue_guard.get_front();
657✔
418
    if (!work) {
657✔
419
        return;
590✔
420
    }
421
    const auto param_id_message_buffer = param_id_to_message_buffer(work->param_id);
67✔
422

423
    mavlink_message_t mavlink_message;
67✔
424

425
    std::visit(
134✔
426
        overloaded{
67✔
427
            [&](const WorkItemValue& specific) {
65✔
428
                if (specific.extended) {
65✔
429
                    const auto buf = work->param_value.get_128_bytes();
33✔
430
                    mavlink_msg_param_ext_value_pack(
66✔
431
                        _sender.get_own_system_id(),
33✔
432
                        _sender.get_own_component_id(),
33✔
433
                        &mavlink_message,
33✔
434
                        param_id_message_buffer.data(),
33✔
435
                        buf.data(),
436
                        work->param_value.get_mav_param_ext_type(),
33✔
437
                        specific.param_count,
33✔
438
                        specific.param_index);
33✔
439
                } else {
440
                    float param_value;
441
                    if (_sender.autopilot() == Sender::Autopilot::ArduPilot) {
32✔
442
                        param_value = work->param_value.get_4_float_bytes_cast();
×
443
                    } else {
444
                        param_value = work->param_value.get_4_float_bytes_bytewise();
32✔
445
                    }
446
                    mavlink_msg_param_value_pack(
64✔
447
                        _sender.get_own_system_id(),
32✔
448
                        _sender.get_own_component_id(),
32✔
449
                        &mavlink_message,
450
                        param_id_message_buffer.data(),
451
                        param_value,
452
                        work->param_value.get_mav_param_type(),
32✔
453
                        specific.param_count,
32✔
454
                        specific.param_index);
32✔
455
                }
456
                if (!_sender.send_message(mavlink_message)) {
65✔
457
                    LogErr() << "Error: Send message failed";
×
458
                    work_queue_guard.pop_front();
×
459
                    return;
×
460
                }
461
                work_queue_guard.pop_front();
65✔
462
            },
463
            [&](const WorkItemAck& specific) {
2✔
464
                auto buf = work->param_value.get_128_bytes();
2✔
465
                mavlink_msg_param_ext_ack_pack(
2✔
466
                    _sender.get_own_system_id(),
2✔
467
                    _sender.get_own_component_id(),
2✔
468
                    &mavlink_message,
2✔
469
                    param_id_message_buffer.data(),
2✔
470
                    buf.data(),
2✔
471
                    work->param_value.get_mav_param_ext_type(),
2✔
472
                    specific.param_ack);
2✔
473
                if (!_sender.send_message(mavlink_message)) {
2✔
474
                    LogErr() << "Error: Send message failed";
×
475
                    work_queue_guard.pop_front();
×
476
                    return;
×
477
                }
478
                work_queue_guard.pop_front();
2✔
479
            }},
480
        work->work_item_variant);
67✔
481
}
482

483
std::ostream& operator<<(std::ostream& str, const MavlinkParameterReceiver::Result& result)
×
484
{
485
    switch (result) {
×
486
        case MavlinkParameterReceiver::Result::Success:
×
487
            return str << "Success";
×
488
        case MavlinkParameterReceiver::Result::WrongType:
×
489
            return str << "WrongType";
×
490
        case MavlinkParameterReceiver::Result::ParamNameTooLong:
×
491
            return str << "ParamNameTooLong";
×
492
        case MavlinkParameterReceiver::Result::NotFound:
×
493
            return str << "NotFound";
×
494
        case MavlinkParameterReceiver::Result::ParamValueTooLong:
×
495
            return str << ":ParamValueTooLong";
×
496
        default:
×
497
            return str << "UnknownError";
×
498
    }
499
}
500

501
bool MavlinkParameterReceiver::target_matches(
41✔
502
    const uint16_t target_sys_id, const uint16_t target_comp_id, bool is_request)
503
{
504
    if (target_sys_id != _sender.get_own_system_id()) {
41✔
505
        return false;
×
506
    }
507
    if (is_request) {
41✔
508
        return target_comp_id == _sender.get_own_component_id() ||
32✔
509
               target_comp_id == MAV_COMP_ID_ALL;
32✔
510
    }
511
    return target_comp_id == _sender.get_own_component_id();
9✔
512
}
513

514
void MavlinkParameterReceiver::log_target_mismatch(uint16_t target_sys_id, uint16_t target_comp_id)
×
515
{
516
    LogDebug() << "Ignoring message - wrong target id. Got:" << (int)target_sys_id << ":"
×
517
               << (int)target_comp_id << " Wanted:" << (int)_sender.get_own_system_id() << ":"
×
518
               << (int)_sender.get_own_component_id();
×
519
}
×
520

521
std::variant<std::monostate, std::string, std::uint16_t>
522
MavlinkParameterReceiver::extract_request_read_param_identifier(
27✔
523
    int16_t param_index, const char* param_id)
524
{
525
    if (param_index == -1) {
27✔
526
        // use param_id if index == -1
527
        const auto safe_param_id = extract_safe_param_id(param_id);
50✔
528
        if (safe_param_id.empty()) {
25✔
529
            LogErr() << "Message with param_index=-1 but no empty param id";
×
530
            return std::monostate{};
×
531
        }
532
        return {safe_param_id};
25✔
533
    } else {
534
        // if index is not -1, it should be a valid parameter index (>=0)
535
        if (param_index < 0) {
2✔
536
            LogErr() << "Param_index " << param_index << " is not a valid param index";
×
537
            return std::monostate{};
×
538
        }
539
        return {static_cast<std::uint16_t>(param_index)};
2✔
540
    }
541
}
542

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