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

mavlink / MAVSDK / 19124558934

06 Nov 2025 04:13AM UTC coverage: 48.329% (+0.2%) from 48.156%
19124558934

push

github

web-flow
Merge pull request #2682 from mavlink/pr-raw-bytes

core: add raw connection

154 of 169 new or added lines in 6 files covered. (91.12%)

381 existing lines in 8 files now uncovered.

17643 of 36506 relevant lines covered (48.33%)

469.45 hits per line

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

69.95
/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 "overloaded.h"
5
#include <cassert>
6
#include <limits>
7

8
namespace mavsdk {
9

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

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

35
    _message_handler.register_one(
135✔
36
        MAVLINK_MSG_ID_PARAM_SET,
37
        [this](const mavlink_message_t& message) { process_param_set(message); },
6✔
38
        this);
39

40
    _message_handler.register_one(
135✔
41
        MAVLINK_MSG_ID_PARAM_EXT_SET,
42
        [this](const mavlink_message_t& message) { process_param_ext_set(message); },
5✔
43
        this);
44

45
    _message_handler.register_one(
135✔
46
        MAVLINK_MSG_ID_PARAM_REQUEST_READ,
47
        [this](const mavlink_message_t& message) { process_param_request_read(message); },
17✔
48
        this);
49

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

55
    _message_handler.register_one(
135✔
56
        MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ,
57
        [this](const mavlink_message_t& message) { process_param_ext_request_read(message); },
42✔
58
        this);
59

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

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

71
MavlinkParameterServer::Result
72
MavlinkParameterServer::provide_server_param(const std::string& name, const ParamValue& param_value)
65✔
73
{
74
    if (name.size() > PARAM_ID_LEN) {
65✔
75
        LogErr() << "Error: param name too long";
×
76
        return Result::ParamNameTooLong;
×
77
    }
78
    if (param_value.is<std::string>()) {
65✔
79
        const auto s = param_value.get<std::string>();
8✔
80
        if (s.size() > sizeof(mavlink_param_ext_set_t::param_value)) {
8✔
81
            LogErr() << "Error: param value too long";
×
82
            return Result::ParamValueTooLong;
×
83
        }
84
    }
8✔
85
    std::lock_guard<std::mutex> lock(_all_params_mutex);
65✔
86
    // first we try to add it as a new parameter
87
    switch (_param_cache.add_new_param(name, param_value)) {
65✔
88
        case MavlinkParameterCache::AddNewParamResult::Ok:
50✔
89
            return Result::Ok;
50✔
90
        case MavlinkParameterCache::AddNewParamResult::AlreadyExists:
15✔
91
            // then, to not change the public api behaviour, try updating its value.
92
            switch (_param_cache.update_existing_param(name, param_value)) {
15✔
93
                case MavlinkParameterCache::UpdateExistingParamResult::Ok:
15✔
94
                    find_and_call_subscriptions_value_changed(name, param_value);
15✔
95
                    {
96
                        auto new_work = std::make_shared<WorkItem>(
97
                            name,
98
                            param_value,
99
                            WorkItemValue{
30✔
100
                                std::numeric_limits<std::uint16_t>::max(),
101
                                std::numeric_limits<std::uint16_t>::max(),
102
                                _last_extended});
15✔
103
                        _work_queue.push_back(new_work);
15✔
104
                    }
15✔
105
                    return Result::OkExistsAlready;
15✔
106
                case MavlinkParameterCache::UpdateExistingParamResult::MissingParam:
×
107
                    return Result::ParamNotFound;
×
108
                case MavlinkParameterCache::UpdateExistingParamResult::WrongType:
×
109
                    return Result::WrongType;
×
110
                default:
×
111
                    LogErr() << "Unknown update_existing_param result";
×
112
                    assert(false);
×
113
                    return Result::Unknown;
114
            }
115
        case MavlinkParameterCache::AddNewParamResult::TooManyParams:
×
116
            return Result::TooManyParams;
×
117
        default:
×
118
            LogErr() << "Unknown add_new_param result";
×
119
            assert(false);
×
120
            return Result::Unknown;
121
    }
122
}
65✔
123

124
MavlinkParameterServer::Result
125
MavlinkParameterServer::provide_server_param_float(const std::string& name, float value)
8✔
126
{
127
    ParamValue param_value;
8✔
128
    param_value.set(value);
8✔
129
    return provide_server_param(name, param_value);
8✔
130
}
8✔
131

132
MavlinkParameterServer::Result
133
MavlinkParameterServer::provide_server_param_int(const std::string& name, int32_t value)
49✔
134
{
135
    ParamValue param_value;
49✔
136
    param_value.set(value);
49✔
137
    return provide_server_param(name, param_value);
49✔
138
}
49✔
139

140
MavlinkParameterServer::Result MavlinkParameterServer::provide_server_param_custom(
8✔
141
    const std::string& name, const std::string& value)
142
{
143
    ParamValue param_value;
8✔
144
    param_value.set(value);
8✔
145
    return provide_server_param(name, param_value);
8✔
146
}
8✔
147

148
std::map<std::string, ParamValue> MavlinkParameterServer::retrieve_all_server_params()
2✔
149
{
150
    std::lock_guard<std::mutex> lock(_all_params_mutex);
2✔
151
    std::map<std::string, ParamValue> map_copy;
2✔
152
    for (auto entry : _param_cache.all_parameters(true)) {
6✔
153
        map_copy[entry.id] = entry.value;
4✔
154
    }
6✔
155
    return map_copy;
2✔
156
}
2✔
157

158
template<class T>
159
std::pair<MavlinkParameterServer::Result, T>
160
MavlinkParameterServer::retrieve_server_param(const std::string& name)
6✔
161
{
162
    std::lock_guard<std::mutex> lock(_all_params_mutex);
6✔
163
    const auto param_opt = _param_cache.param_by_id(name, true);
6✔
164
    if (!param_opt.has_value()) {
6✔
165
        return {Result::NotFound, {}};
×
166
    }
167
    // This parameter exists, check its type
168
    const auto& param = param_opt.value();
6✔
169
    if (param.value.is<T>()) {
6✔
170
        return {Result::Ok, param.value.get<T>()};
6✔
171
    }
172
    return {Result::WrongType, {}};
×
173
}
6✔
174

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

181
std::pair<MavlinkParameterServer::Result, std::string>
182
MavlinkParameterServer::retrieve_server_param_custom(const std::string& name)
2✔
183
{
184
    return retrieve_server_param<std::string>(name);
2✔
185
}
186

187
std::pair<MavlinkParameterServer::Result, int32_t>
188
MavlinkParameterServer::retrieve_server_param_int(const std::string& name)
2✔
189
{
190
    return retrieve_server_param<int32_t>(name);
2✔
191
}
192

193
void MavlinkParameterServer::process_param_set_internally(
11✔
194
    const std::string& param_id, const ParamValue& value_to_set, bool extended)
195
{
196
    if (_parameter_debugging) {
11✔
197
        LogDebug() << "Param set request" << (extended ? " extended" : "") << ": " << param_id
×
198
                   << " with " << value_to_set;
×
199
    }
200

201
    std::string error_param_id;
11✔
202
    int16_t error_param_index = -1;
11✔
203
    uint8_t error_code = 0;
11✔
204
    bool send_error = false;
11✔
205

206
    {
207
        std::lock_guard<std::mutex> lock(_all_params_mutex);
11✔
208
        // for checking if the update actually changed the value
209
        const auto opt_before_update = _param_cache.param_by_id(param_id, extended);
11✔
210
        const auto result = _param_cache.update_existing_param(param_id, value_to_set);
11✔
211
        const auto param_count = _param_cache.count(extended);
11✔
212

213
        switch (result) {
11✔
214
            case MavlinkParameterCache::UpdateExistingParamResult::MissingParam: {
×
215
                // We do not allow clients to add a new parameter to the parameter set, only to
216
                // update existing parameters. Send PARAM_ERROR for standard protocol.
UNCOV
217
                LogErr() << "Got param_set for non-existing parameter:" << param_id;
×
218

UNCOV
219
                if (!extended) {
×
220
                    // Prepare to send PARAM_ERROR outside the lock
UNCOV
221
                    error_param_id = param_id;
×
222
                    error_param_index = -1;
×
UNCOV
223
                    error_code = 1; // MAV_PARAM_ERROR_DOES_NOT_EXIST
×
224
                    send_error = true;
×
225
                }
UNCOV
226
                return;
×
227
            }
UNCOV
228
            case MavlinkParameterCache::UpdateExistingParamResult::WrongType: {
×
229
                // Non-extended: send PARAM_ERROR with TYPE_MISMATCH
230
                // Extended: we nack with failed.
231

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

234
                const auto curr_param = _param_cache.param_by_id(param_id, extended).value();
×
235

UNCOV
236
                if (extended) {
×
237
                    auto new_work = std::make_shared<WorkItem>(
UNCOV
238
                        curr_param.id, curr_param.value, WorkItemAck{PARAM_ACK_FAILED});
×
UNCOV
239
                    _work_queue.push_back(new_work);
×
240

UNCOV
241
                } else {
×
242
                    // Prepare to send PARAM_ERROR outside the lock
UNCOV
243
                    error_param_id = curr_param.id;
×
UNCOV
244
                    error_param_index = static_cast<int16_t>(curr_param.index);
×
UNCOV
245
                    error_code = 7; // MAV_PARAM_ERROR_TYPE_MISMATCH
×
UNCOV
246
                    send_error = true;
×
247
                }
UNCOV
248
                return;
×
UNCOV
249
            }
×
250
            case MavlinkParameterCache::UpdateExistingParamResult::Ok: {
11✔
251
                LogWarn() << "Update existing params!";
11✔
252
                const auto updated_parameter = _param_cache.param_by_id(param_id, extended).value();
11✔
253
                // The param set doesn't differentiate between an update that actually changed the
254
                // value e.g. 0 to 1 and an update that had no effect e.g. 0 to 0.
255
                if (opt_before_update.has_value() &&
22✔
256
                    opt_before_update.value().value == updated_parameter.value) {
11✔
257
                    LogDebug() << "Update had no effect: " << updated_parameter.value;
2✔
258
                } else {
259
                    LogDebug() << "Updated param to :" << updated_parameter.value;
9✔
260
                    find_and_call_subscriptions_value_changed(
9✔
261
                        updated_parameter.id, updated_parameter.value);
262
                }
263
                if (extended) {
11✔
264
                    auto new_work = std::make_shared<WorkItem>(
265
                        updated_parameter.id,
266
                        updated_parameter.value,
267
                        WorkItemAck{PARAM_ACK_ACCEPTED});
5✔
268
                    _work_queue.push_back(new_work);
5✔
269
                } else {
5✔
270
                    auto new_work = std::make_shared<WorkItem>(
271
                        updated_parameter.id,
272
                        updated_parameter.value,
273
                        WorkItemValue{updated_parameter.index, param_count, extended});
6✔
274
                    _work_queue.push_back(new_work);
6✔
275
                }
6✔
276
            } break;
11✔
277
        }
278
    }
11✔
279

280
    // Send PARAM_ERROR outside the lock if needed
281
    if (send_error) {
11✔
282
        send_param_error(error_param_id, error_param_index, error_code);
×
283
    }
284
}
11✔
285

286
void MavlinkParameterServer::process_param_set(const mavlink_message_t& message)
6✔
287
{
288
    mavlink_param_set_t set_request{};
6✔
289
    mavlink_msg_param_set_decode(&message, &set_request);
6✔
290
    if (!target_matches(set_request.target_system, set_request.target_component, false)) {
6✔
UNCOV
291
        log_target_mismatch(set_request.target_system, set_request.target_component);
×
UNCOV
292
        return;
×
293
    }
294
    const std::string safe_param_id = extract_safe_param_id(set_request.param_id);
6✔
295

296
    if (safe_param_id.empty()) {
6✔
UNCOV
297
        LogWarn() << "Got ill-formed param_set message (param_id empty)";
×
UNCOV
298
        return;
×
299
    }
300

301
    ParamValue value_to_set;
6✔
302
    if (!value_to_set.set_from_mavlink_param_set_bytewise(set_request)) {
6✔
303
        // This should never happen, the type enum in the message is unknown.
UNCOV
304
        LogWarn() << "Invalid Param Set Request: " << safe_param_id;
×
UNCOV
305
        return;
×
306
    }
307
    process_param_set_internally(safe_param_id, value_to_set, false);
6✔
308
}
6✔
309

310
void MavlinkParameterServer::process_param_ext_set(const mavlink_message_t& message)
5✔
311
{
312
    mavlink_param_ext_set_t set_request{};
5✔
313
    mavlink_msg_param_ext_set_decode(&message, &set_request);
5✔
314
    if (!target_matches(set_request.target_system, set_request.target_component, false)) {
5✔
UNCOV
315
        log_target_mismatch(set_request.target_system, set_request.target_component);
×
316
        return;
×
317
    }
318
    const std::string safe_param_id = extract_safe_param_id(set_request.param_id);
5✔
319

320
    if (safe_param_id.empty()) {
5✔
321
        LogWarn() << "Got ill-formed param_ext_set message (param_id empty)";
×
322
        return;
×
323
    }
324

325
    ParamValue value_to_set;
5✔
326
    if (!value_to_set.set_from_mavlink_param_ext_set(set_request)) {
5✔
327
        // This should never happen, the type enum in the message is unknown.
UNCOV
328
        LogWarn() << "Invalid Param Set ext Request: " << safe_param_id;
×
UNCOV
329
        return;
×
330
    }
331

332
    process_param_set_internally(safe_param_id, value_to_set, true);
5✔
333
}
5✔
334

335
void MavlinkParameterServer::process_param_request_read(const mavlink_message_t& message)
17✔
336
{
337
    if (_parameter_debugging) {
17✔
UNCOV
338
        LogDebug() << "process param_request_read";
×
339
    }
340
    mavlink_param_request_read_t read_request{};
17✔
341
    mavlink_msg_param_request_read_decode(&message, &read_request);
17✔
342
    if (!target_matches(read_request.target_system, read_request.target_component, true)) {
17✔
UNCOV
343
        log_target_mismatch(read_request.target_system, read_request.target_component);
×
UNCOV
344
        return;
×
345
    }
346

347
    const auto param_id_or_index =
348
        extract_request_read_param_identifier(read_request.param_index, read_request.param_id);
17✔
349

350
    std::visit(
17✔
351
        overloaded{
17✔
352
            [&](std::monostate) { LogWarn() << "Ill-formed param_request_read message"; },
×
353
            [&](std::uint16_t index) {
2✔
354
                if (_parameter_debugging) {
2✔
UNCOV
355
                    LogDebug() << "found index: " << index;
×
356
                }
357
                internal_process_param_request_read_by_index(index, false);
2✔
358
            },
2✔
359
            [&](const std::string& id) {
15✔
360
                if (_parameter_debugging) {
15✔
UNCOV
361
                    LogDebug() << "found id: " << id;
×
362
                }
363
                internal_process_param_request_read_by_id(id, false);
15✔
364
            }},
15✔
365
        param_id_or_index);
366
}
17✔
367

368
void MavlinkParameterServer::process_param_ext_request_read(const mavlink_message_t& message)
42✔
369
{
370
    mavlink_param_ext_request_read_t read_request{};
42✔
371
    mavlink_msg_param_ext_request_read_decode(&message, &read_request);
42✔
372
    if (!target_matches(read_request.target_system, read_request.target_component, true)) {
42✔
UNCOV
373
        log_target_mismatch(read_request.target_system, read_request.target_component);
×
UNCOV
374
        return;
×
375
    }
376
    const auto param_id_or_index =
377
        extract_request_read_param_identifier(read_request.param_index, read_request.param_id);
42✔
378

379
    std::visit(
42✔
380
        overloaded{
42✔
UNCOV
381
            [&](std::monostate) { LogWarn() << "Ill-formed param_request_read message"; },
×
382
            [&](std::uint16_t index) {
3✔
383
                if (_parameter_debugging) {
3✔
UNCOV
384
                    LogDebug() << "found index: " << index;
×
385
                }
386
                internal_process_param_request_read_by_index(index, true);
3✔
387
            },
3✔
388
            [&](const std::string& id) {
39✔
389
                if (_parameter_debugging) {
39✔
UNCOV
390
                    LogDebug() << "found id: " << id;
×
391
                }
392
                internal_process_param_request_read_by_id(id, true);
39✔
393
            }},
39✔
394
        param_id_or_index);
395
}
42✔
396

397
void MavlinkParameterServer::internal_process_param_request_read_by_id(
54✔
398
    const std::string& id, const bool extended)
399
{
400
    {
401
        std::lock_guard<std::mutex> lock(_all_params_mutex);
54✔
402
        const auto param_opt = _param_cache.param_by_id(id, extended);
54✔
403

404
        if (!param_opt.has_value()) {
54✔
405
            LogWarn() << "Ignoring request_read message " << (extended ? "extended " : "")
4✔
406
                      << "- param name not found: " << id;
2✔
407
            // Release lock before sending PARAM_ERROR
408
        } else {
409
            const auto& param = param_opt.value();
52✔
410
            const auto param_count = _param_cache.count(extended);
52✔
411
            assert(param.index < param_count);
52✔
412
            auto new_work = std::make_shared<WorkItem>(
413
                param.id, param.value, WorkItemValue{param.index, param_count, extended});
52✔
414
            _work_queue.push_back(new_work);
52✔
415

416
            _last_extended = extended;
52✔
417
            return;
52✔
418
        }
52✔
419
    }
106✔
420

421
    // Send PARAM_ERROR outside the lock
422
    if (!extended) {
2✔
423
        send_param_error(id, -1, 1); // MAV_PARAM_ERROR_DOES_NOT_EXIST = 1
2✔
424
    }
425
}
426

427
void MavlinkParameterServer::internal_process_param_request_read_by_index(
5✔
428
    std::uint16_t index, bool extended)
429
{
430
    {
431
        std::lock_guard<std::mutex> lock(_all_params_mutex);
5✔
432
        const auto param_opt = _param_cache.param_by_index(index, extended);
5✔
433

434
        if (!param_opt.has_value()) {
5✔
UNCOV
435
            LogWarn() << "Ignoring request_read message " << (extended ? "extended " : "")
×
436
                      << "- param index not found: " << index;
×
437
            // Release lock before sending PARAM_ERROR
438
        } else {
439
            const auto& param = param_opt.value();
5✔
440
            const auto param_count = _param_cache.count(extended);
5✔
441

442
            assert(param.index < param_count);
5✔
443
            auto new_work = std::make_shared<WorkItem>(
444
                param.id, param.value, WorkItemValue{param.index, param_count, extended});
5✔
445
            _work_queue.push_back(new_work);
5✔
446
            return;
5✔
447
        }
5✔
448
    }
10✔
449

450
    // Send PARAM_ERROR outside the lock
UNCOV
451
    if (!extended) {
×
452
        send_param_error("", static_cast<int16_t>(index), 1); // MAV_PARAM_ERROR_DOES_NOT_EXIST = 1
×
453
    }
454
}
455

456
void MavlinkParameterServer::process_param_request_list(const mavlink_message_t& message)
2✔
457
{
458
    mavlink_param_request_list_t list_request{};
2✔
459
    mavlink_msg_param_request_list_decode(&message, &list_request);
2✔
460
    if (!target_matches(list_request.target_system, list_request.target_component, true)) {
2✔
UNCOV
461
        log_target_mismatch(list_request.target_system, list_request.target_component);
×
UNCOV
462
        return;
×
463
    }
464
    broadcast_all_parameters(false);
2✔
465
}
466

467
void MavlinkParameterServer::process_param_ext_request_list(const mavlink_message_t& message)
2✔
468
{
469
    if (_parameter_debugging) {
2✔
UNCOV
470
        LogDebug() << "process param_ext_request_list";
×
471
    }
472

473
    mavlink_param_ext_request_list_t ext_list_request{};
2✔
474
    mavlink_msg_param_ext_request_list_decode(&message, &ext_list_request);
2✔
475
    if (!target_matches(ext_list_request.target_system, ext_list_request.target_component, true)) {
2✔
UNCOV
476
        log_target_mismatch(ext_list_request.target_system, ext_list_request.target_component);
×
UNCOV
477
        return;
×
478
    }
479
    broadcast_all_parameters(true);
2✔
480
}
481

482
void MavlinkParameterServer::broadcast_all_parameters(const bool extended)
4✔
483
{
484
    std::lock_guard<std::mutex> lock(_all_params_mutex);
4✔
485
    const auto all_params = _param_cache.all_parameters(extended);
4✔
486
    if (_parameter_debugging) {
4✔
UNCOV
487
        LogDebug() << "broadcast_all_parameters " << (extended ? "extended" : "") << ": "
×
UNCOV
488
                   << all_params.size();
×
489
    }
490
    for (const auto& parameter : all_params) {
34✔
491
        if (_parameter_debugging) {
30✔
492
            LogDebug() << "sending param:" << parameter.id;
×
493
        }
494
        auto new_work = std::make_shared<WorkItem>(
495
            parameter.id,
30✔
496
            parameter.value,
30✔
497
            WorkItemValue{parameter.index, static_cast<uint16_t>(all_params.size()), extended});
30✔
498
        _work_queue.push_back(new_work);
30✔
499
    }
30✔
500
}
4✔
501

502
void MavlinkParameterServer::do_work()
31,888✔
503
{
504
    LockedQueue<WorkItem>::Guard work_queue_guard(_work_queue);
31,888✔
505
    auto work = work_queue_guard.get_front();
31,414✔
506
    if (!work) {
31,351✔
507
        return;
31,316✔
508
    }
509
    const auto param_id_message_buffer = param_id_to_message_buffer(work->param_id);
113✔
510

511
    std::visit(
113✔
512
        overloaded{
226✔
513
            [&](const WorkItemValue& specific) {
108✔
514
                if (specific.extended) {
108✔
515
                    const auto buf = work->param_value.get_128_bytes();
75✔
516
                    if (!_sender.queue_message(
75✔
517
                            [&](MavlinkAddress mavlink_address, uint8_t channel) {
75✔
518
                                mavlink_message_t message;
519
                                mavlink_msg_param_ext_value_pack_chan(
300✔
520
                                    mavlink_address.system_id,
75✔
521
                                    mavlink_address.component_id,
75✔
522
                                    channel,
523
                                    &message,
524
                                    param_id_message_buffer.data(),
150✔
525
                                    buf.data(),
75✔
526
                                    work->param_value.get_mav_param_ext_type(),
75✔
527
                                    specific.param_count,
75✔
528
                                    specific.param_index);
75✔
529
                                return message;
75✔
530
                            })) {
UNCOV
531
                        LogErr() << "Error: Send message failed";
×
UNCOV
532
                        work_queue_guard.pop_front();
×
UNCOV
533
                        return;
×
534
                    }
535
                } else {
536
                    LogWarn() << "sending not extended message";
33✔
537
                    float param_value;
538
                    if (_sender.autopilot() == Autopilot::ArduPilot) {
33✔
UNCOV
539
                        param_value = work->param_value.get_4_float_bytes_cast();
×
540
                    } else {
541
                        param_value = work->param_value.get_4_float_bytes_bytewise();
33✔
542
                    }
543
                    if (!_sender.queue_message(
33✔
544
                            [&](MavlinkAddress mavlink_address, uint8_t channel) {
33✔
545
                                mavlink_message_t message;
546
                                mavlink_msg_param_value_pack_chan(
99✔
547
                                    mavlink_address.system_id,
33✔
548
                                    mavlink_address.component_id,
33✔
549
                                    channel,
550
                                    &message,
551
                                    param_id_message_buffer.data(),
33✔
552
                                    param_value,
33✔
553
                                    work->param_value.get_mav_param_type(),
33✔
554
                                    specific.param_count,
33✔
555
                                    specific.param_index);
33✔
556
                                return message;
33✔
557
                            })) {
558
                        LogErr() << "Error: Send message failed";
×
559
                        work_queue_guard.pop_front();
×
560
                        return;
×
561
                    }
562
                }
563
                work_queue_guard.pop_front();
108✔
564
            },
565
            [&](const WorkItemAck& specific) {
5✔
566
                auto buf = work->param_value.get_128_bytes();
5✔
567
                if (!_sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
5✔
568
                        mavlink_message_t message;
569
                        mavlink_msg_param_ext_ack_pack_chan(
20✔
570
                            mavlink_address.system_id,
5✔
571
                            mavlink_address.component_id,
5✔
572
                            channel,
573
                            &message,
574
                            param_id_message_buffer.data(),
10✔
575
                            buf.data(),
5✔
576
                            work->param_value.get_mav_param_ext_type(),
5✔
577
                            specific.param_ack);
5✔
578
                        return message;
5✔
579
                    })) {
UNCOV
580
                    LogErr() << "Error: Send message failed";
×
UNCOV
581
                    work_queue_guard.pop_front();
×
UNCOV
582
                    return;
×
583
                }
584
                work_queue_guard.pop_front();
5✔
585
            }},
586
        work->work_item_variant);
113✔
587
}
62,939✔
588

589
void MavlinkParameterServer::send_param_error(
2✔
590
    const std::string& param_id, int16_t param_index, uint8_t error_code)
591
{
592
    if (_parameter_debugging) {
2✔
UNCOV
593
        LogDebug() << "Sending PARAM_ERROR for " << param_id << " (index: " << param_index
×
UNCOV
594
                   << ") with error code: " << (int)error_code;
×
595
    }
596

597
    const auto param_id_buffer = param_id_to_message_buffer(param_id);
2✔
598

599
    if (!_sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
2✔
600
            mavlink_message_t message;
601
            mavlink_msg_param_error_pack_chan(
4✔
602
                mavlink_address.system_id,
2✔
603
                mavlink_address.component_id,
2✔
604
                channel,
605
                &message,
606
                0, // target_system - 0 for broadcast
607
                0, // target_component - 0 for broadcast
608
                param_id_buffer.data(),
2✔
609
                param_index,
2✔
610
                error_code);
2✔
611
            return message;
2✔
612
        })) {
UNCOV
613
        LogErr() << "Error: Send PARAM_ERROR message failed";
×
614
    }
615
}
2✔
616

UNCOV
617
std::ostream& operator<<(std::ostream& str, const MavlinkParameterServer::Result& result)
×
618
{
UNCOV
619
    switch (result) {
×
UNCOV
620
        case MavlinkParameterServer::Result::Ok:
×
UNCOV
621
            return str << "Ok";
×
UNCOV
622
        case MavlinkParameterServer::Result::OkExistsAlready:
×
UNCOV
623
            return str << "OkExistsAlready";
×
UNCOV
624
        case MavlinkParameterServer::Result::WrongType:
×
UNCOV
625
            return str << "WrongType";
×
UNCOV
626
        case MavlinkParameterServer::Result::ParamNameTooLong:
×
UNCOV
627
            return str << "ParamNameTooLong";
×
UNCOV
628
        case MavlinkParameterServer::Result::NotFound:
×
UNCOV
629
            return str << "NotFound";
×
UNCOV
630
        case MavlinkParameterServer::Result::ParamValueTooLong:
×
UNCOV
631
            return str << ":ParamValueTooLong";
×
UNCOV
632
        default:
×
UNCOV
633
            return str << "UnknownError";
×
634
    }
635
}
636

637
bool MavlinkParameterServer::target_matches(
74✔
638
    const uint16_t target_sys_id, const uint16_t target_comp_id, bool is_request)
639
{
640
    // See: https://mavlink.io/en/services/parameter.html#multi-system-and-multi-component-support
641

642
    if (target_sys_id != _sender.get_own_system_id()) {
74✔
UNCOV
643
        return false;
×
644
    }
645
    if (is_request) {
74✔
646
        return target_comp_id == _sender.get_own_component_id() ||
63✔
647
               target_comp_id == MAV_COMP_ID_ALL;
63✔
648
    }
649
    return target_comp_id == _sender.get_own_component_id();
11✔
650
}
651

UNCOV
652
void MavlinkParameterServer::log_target_mismatch(uint16_t target_sys_id, uint16_t target_comp_id)
×
653
{
UNCOV
654
    if (!_parameter_debugging) {
×
UNCOV
655
        return;
×
656
    }
657

UNCOV
658
    LogDebug() << "Ignoring message - wrong target id. Got:" << (int)target_sys_id << ":"
×
UNCOV
659
               << (int)target_comp_id << " Wanted:" << (int)_sender.get_own_system_id() << ":"
×
UNCOV
660
               << (int)_sender.get_own_component_id();
×
661
}
662

663
std::variant<std::monostate, std::string, std::uint16_t>
664
MavlinkParameterServer::extract_request_read_param_identifier(
59✔
665
    int16_t param_index, const char* param_id)
666
{
667
    // Helper for safely handling a request_read or ext_request_read message (which have the exact
668
    // same layout). returns the identifier that should be used or nothing if the message is
669
    // ill-formed. See https://mavlink.io/en/messages/common.html#PARAM_REQUEST_READ and
670
    // https://mavlink.io/en/messages/common.html#PARAM_EXT_REQUEST_READ
671

672
    if (param_index == -1) {
59✔
673
        // use param_id if index == -1
674
        const auto safe_param_id = extract_safe_param_id(param_id);
54✔
675
        if (safe_param_id.empty()) {
54✔
UNCOV
676
            LogErr() << "Message with param_index=-1 but no empty param id";
×
UNCOV
677
            return std::monostate{};
×
678
        }
679
        return {safe_param_id};
54✔
680
    } else {
54✔
681
        // if index is not -1, it should be a valid parameter index (>=0)
682
        if (param_index < 0) {
5✔
UNCOV
683
            LogErr() << "Param_index " << param_index << " is not a valid param index";
×
UNCOV
684
            return std::monostate{};
×
685
        }
686
        return {static_cast<std::uint16_t>(param_index)};
5✔
687
    }
688
}
689

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