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

mavlink / MAVSDK / 11588508005

30 Oct 2024 07:04AM UTC coverage: 37.921% (+0.003%) from 37.918%
11588508005

push

github

web-flow
action: remove max speed settings (#2435)

This API is confusing as it only works for PX4 quads but not PX4
fixedwing or anything ArduPilot based.

The reason is that this just sets a PX4 parameter that is not
standardized via MAVLink.

Therefore, I suggest to remove the API and instead recommend to use
the param plugin to set the specific params specifically.

11431 of 30144 relevant lines covered (37.92%)

263.0 hits per line

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

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

7
namespace mavsdk {
8

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

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

34
    _message_handler.register_one(
72✔
35
        MAVLINK_MSG_ID_PARAM_SET,
36
        [this](const mavlink_message_t& message) { process_param_set(message); },
4✔
37
        this);
38

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

44
    _message_handler.register_one(
72✔
45
        MAVLINK_MSG_ID_PARAM_REQUEST_READ,
46
        [this](const mavlink_message_t& message) { process_param_request_read(message); },
26✔
47
        this);
48

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

54
    _message_handler.register_one(
72✔
55
        MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ,
56
        [this](const mavlink_message_t& message) { process_param_ext_request_read(message); },
9✔
57
        this);
58

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

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

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

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

111
    return Result::Unknown;
112
}
113

114
MavlinkParameterServer::Result
115
MavlinkParameterServer::provide_server_param_float(const std::string& name, float 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
MavlinkParameterServer::Result
123
MavlinkParameterServer::provide_server_param_int(const std::string& name, int32_t value)
8✔
124
{
125
    ParamValue param_value;
16✔
126
    param_value.set(value);
8✔
127
    return provide_server_param(name, param_value);
8✔
128
}
129

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

312
    const auto param_id_or_index =
26✔
313
        extract_request_read_param_identifier(read_request.param_index, read_request.param_id);
52✔
314

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

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

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

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

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

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

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

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

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

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

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

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

448
void MavlinkParameterServer::do_work()
11,731✔
449
{
450
    LockedQueue<WorkItem>::Guard work_queue_guard(_work_queue);
11,731✔
451
    auto work = work_queue_guard.get_front();
11,320✔
452
    if (!work) {
10,467✔
453
        return;
10,025✔
454
    }
455
    const auto param_id_message_buffer = param_id_to_message_buffer(work->param_id);
59✔
456

457
    std::visit(
118✔
458
        overloaded{
59✔
459
            [&](const WorkItemValue& specific) {
57✔
460
                if (specific.extended) {
57✔
461
                    const auto buf = work->param_value.get_128_bytes();
27✔
462
                    if (!_sender.queue_message(
27✔
463
                            [&](MavlinkAddress mavlink_address, uint8_t channel) {
27✔
464
                                mavlink_message_t message;
465
                                mavlink_msg_param_ext_value_pack_chan(
108✔
466
                                    mavlink_address.system_id,
27✔
467
                                    mavlink_address.component_id,
27✔
468
                                    channel,
469
                                    &message,
470
                                    param_id_message_buffer.data(),
54✔
471
                                    buf.data(),
27✔
472
                                    work->param_value.get_mav_param_ext_type(),
27✔
473
                                    specific.param_count,
27✔
474
                                    specific.param_index);
27✔
475
                                return message;
27✔
476
                            })) {
27✔
477
                        LogErr() << "Error: Send message failed";
×
478
                        work_queue_guard.pop_front();
×
479
                        return;
×
480
                    }
481
                } else {
482
                    float param_value;
30✔
483
                    if (_sender.autopilot() == Autopilot::ArduPilot) {
30✔
484
                        param_value = work->param_value.get_4_float_bytes_cast();
×
485
                    } else {
486
                        param_value = work->param_value.get_4_float_bytes_bytewise();
30✔
487
                    }
488
                    if (!_sender.queue_message(
30✔
489
                            [&](MavlinkAddress mavlink_address, uint8_t channel) {
30✔
490
                                mavlink_message_t message;
491
                                mavlink_msg_param_value_pack_chan(
90✔
492
                                    mavlink_address.system_id,
30✔
493
                                    mavlink_address.component_id,
30✔
494
                                    channel,
495
                                    &message,
496
                                    param_id_message_buffer.data(),
30✔
497
                                    param_value,
30✔
498
                                    work->param_value.get_mav_param_type(),
30✔
499
                                    specific.param_count,
30✔
500
                                    specific.param_index);
30✔
501
                                return message;
30✔
502
                            })) {
30✔
503
                        LogErr() << "Error: Send message failed";
×
504
                        work_queue_guard.pop_front();
×
505
                        return;
×
506
                    }
507
                }
508
                work_queue_guard.pop_front();
57✔
509
            },
510
            [&](const WorkItemAck& specific) {
2✔
511
                auto buf = work->param_value.get_128_bytes();
2✔
512
                if (!_sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
2✔
513
                        mavlink_message_t message;
514
                        mavlink_msg_param_ext_ack_pack_chan(
8✔
515
                            mavlink_address.system_id,
2✔
516
                            mavlink_address.component_id,
2✔
517
                            channel,
518
                            &message,
519
                            param_id_message_buffer.data(),
4✔
520
                            buf.data(),
2✔
521
                            work->param_value.get_mav_param_ext_type(),
2✔
522
                            specific.param_ack);
2✔
523
                        return message;
2✔
524
                    })) {
2✔
525
                    LogErr() << "Error: Send message failed";
×
526
                    work_queue_guard.pop_front();
×
527
                    return;
×
528
                }
529
                work_queue_guard.pop_front();
2✔
530
            }},
531
        work->work_item_variant);
59✔
532
}
533

534
std::ostream& operator<<(std::ostream& str, const MavlinkParameterServer::Result& result)
×
535
{
536
    switch (result) {
×
537
        case MavlinkParameterServer::Result::Success:
×
538
            return str << "Success";
×
539
        case MavlinkParameterServer::Result::WrongType:
×
540
            return str << "WrongType";
×
541
        case MavlinkParameterServer::Result::ParamNameTooLong:
×
542
            return str << "ParamNameTooLong";
×
543
        case MavlinkParameterServer::Result::NotFound:
×
544
            return str << "NotFound";
×
545
        case MavlinkParameterServer::Result::ParamValueTooLong:
×
546
            return str << ":ParamValueTooLong";
×
547
        default:
×
548
            return str << "UnknownError";
×
549
    }
550
}
551

552
bool MavlinkParameterServer::target_matches(
45✔
553
    const uint16_t target_sys_id, const uint16_t target_comp_id, bool is_request)
554
{
555
    // See: https://mavlink.io/en/services/parameter.html#multi-system-and-multi-component-support
556

557
    if (target_sys_id != _sender.get_own_system_id()) {
45✔
558
        return false;
×
559
    }
560
    if (is_request) {
45✔
561
        return target_comp_id == _sender.get_own_component_id() ||
39✔
562
               target_comp_id == MAV_COMP_ID_ALL;
39✔
563
    }
564
    return target_comp_id == _sender.get_own_component_id();
6✔
565
}
566

567
void MavlinkParameterServer::log_target_mismatch(uint16_t target_sys_id, uint16_t target_comp_id)
×
568
{
569
    if (!_parameter_debugging) {
×
570
        return;
×
571
    }
572

573
    LogDebug() << "Ignoring message - wrong target id. Got:" << (int)target_sys_id << ":"
×
574
               << (int)target_comp_id << " Wanted:" << (int)_sender.get_own_system_id() << ":"
×
575
               << (int)_sender.get_own_component_id();
×
576
}
577

578
std::variant<std::monostate, std::string, std::uint16_t>
579
MavlinkParameterServer::extract_request_read_param_identifier(
35✔
580
    int16_t param_index, const char* param_id)
581
{
582
    // Helper for safely handling a request_read or ext_request_read message (which have the exact
583
    // same layout). returns the identifier that should be used or nothing if the message is
584
    // ill-formed. See https://mavlink.io/en/messages/common.html#PARAM_REQUEST_READ and
585
    // https://mavlink.io/en/messages/common.html#PARAM_EXT_REQUEST_READ
586

587
    if (param_index == -1) {
35✔
588
        // use param_id if index == -1
589
        const auto safe_param_id = extract_safe_param_id(param_id);
64✔
590
        if (safe_param_id.empty()) {
32✔
591
            LogErr() << "Message with param_index=-1 but no empty param id";
×
592
            return std::monostate{};
×
593
        }
594
        return {safe_param_id};
32✔
595
    } else {
596
        // if index is not -1, it should be a valid parameter index (>=0)
597
        if (param_index < 0) {
3✔
598
            LogErr() << "Param_index " << param_index << " is not a valid param index";
×
599
            return std::monostate{};
×
600
        }
601
        return {static_cast<std::uint16_t>(param_index)};
3✔
602
    }
603
}
604

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