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

mavlink / MAVSDK / 18256562203

05 Oct 2025 08:57AM UTC coverage: 47.58% (+0.02%) from 47.563%
18256562203

push

github

web-flow
Merge pull request #2670 from reedev/MavlinkPath

Added capability to specify the path to the mavlink xml files

17025 of 35782 relevant lines covered (47.58%)

452.26 hits per line

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

45.29
/src/mavsdk/core/param_value.cpp
1
#include "param_value.h"
2

3
#include <cassert>
4
#include <sstream>
5

6
namespace mavsdk {
7

8
// std::to_string doesn't work for std::string, so we need this workaround.
9
template<typename T> std::string to_string(T&& value)
316✔
10
{
11
    return std::to_string(std::forward<T>(value));
316✔
12
}
13

14
inline std::string& to_string(std::string& value)
4✔
15
{
16
    return value;
4✔
17
}
18

19
bool ParamValue::set_from_mavlink_param_value_bytewise(const mavlink_param_value_t& mavlink_value)
32✔
20
{
21
    switch (mavlink_value.param_type) {
32✔
22
        case MAV_PARAM_TYPE_UINT8: {
×
23
            uint8_t temp;
24
            memcpy(&temp, &mavlink_value.param_value, sizeof(temp));
×
25
            _value = temp;
×
26
        } break;
×
27

28
        case MAV_PARAM_TYPE_INT8: {
×
29
            int8_t temp;
30
            memcpy(&temp, &mavlink_value.param_value, sizeof(temp));
×
31
            _value = temp;
×
32
        } break;
×
33

34
        case MAV_PARAM_TYPE_UINT16: {
×
35
            uint16_t temp;
36
            memcpy(&temp, &mavlink_value.param_value, sizeof(temp));
×
37
            _value = temp;
×
38
        } break;
×
39

40
        case MAV_PARAM_TYPE_INT16: {
×
41
            int16_t temp;
42
            memcpy(&temp, &mavlink_value.param_value, sizeof(temp));
×
43
            _value = temp;
×
44
        } break;
×
45

46
        case MAV_PARAM_TYPE_UINT32: {
×
47
            uint32_t temp;
48
            memcpy(&temp, &mavlink_value.param_value, sizeof(temp));
×
49
            _value = temp;
×
50
        } break;
×
51

52
        case MAV_PARAM_TYPE_INT32: {
17✔
53
            int32_t temp;
54
            memcpy(&temp, &mavlink_value.param_value, sizeof(temp));
17✔
55
            _value = temp;
17✔
56
        } break;
17✔
57

58
        case MAV_PARAM_TYPE_REAL32: {
15✔
59
            _value = mavlink_value.param_value;
15✔
60
        } break;
15✔
61

62
        default:
×
63
            // This would be worrying
64
            LogErr() << "Error: unknown mavlink param type: "
×
65
                     << std::to_string(mavlink_value.param_type);
×
66
            return false;
×
67
    }
68
    return true;
32✔
69
}
70

71
bool ParamValue::set_from_mavlink_param_value_cast(const mavlink_param_value_t& mavlink_value)
×
72
{
73
    switch (mavlink_value.param_type) {
×
74
        case MAV_PARAM_TYPE_UINT8: {
×
75
            _value = static_cast<uint8_t>(mavlink_value.param_value);
×
76
        } break;
×
77

78
        case MAV_PARAM_TYPE_INT8: {
×
79
            _value = static_cast<int8_t>(mavlink_value.param_value);
×
80
        } break;
×
81

82
        case MAV_PARAM_TYPE_UINT16: {
×
83
            _value = static_cast<uint16_t>(mavlink_value.param_value);
×
84
        } break;
×
85

86
        case MAV_PARAM_TYPE_INT16: {
×
87
            _value = static_cast<int16_t>(mavlink_value.param_value);
×
88
        } break;
×
89

90
        case MAV_PARAM_TYPE_UINT32: {
×
91
            _value = static_cast<uint32_t>(mavlink_value.param_value);
×
92
        } break;
×
93

94
        case MAV_PARAM_TYPE_INT32: {
×
95
            _value = static_cast<int32_t>(mavlink_value.param_value);
×
96
        } break;
×
97

98
        case MAV_PARAM_TYPE_REAL32: {
×
99
            float temp = mavlink_value.param_value;
×
100
            _value = temp;
×
101
        } break;
×
102

103
        default:
×
104
            // This would be worrying
105
            LogErr() << "Error: unknown mavlink param type: "
×
106
                     << std::to_string(mavlink_value.param_type);
×
107
            return false;
×
108
    }
109
    return true;
×
110
}
111

112
bool ParamValue::set_from_mavlink_param_value(
26✔
113
    const mavlink_param_value_t& mavlink_value, const ParamValue::Conversion& conversion)
114
{
115
    if (conversion == Conversion::Cast) {
26✔
116
        return set_from_mavlink_param_value_cast(mavlink_value);
×
117
    } else {
118
        return set_from_mavlink_param_value_bytewise(mavlink_value);
26✔
119
    }
120
}
121

122
bool ParamValue::set_from_mavlink_param_set_bytewise(const mavlink_param_set_t& mavlink_set)
6✔
123
{
124
    mavlink_param_value_t mavlink_value{};
6✔
125
    mavlink_value.param_value = mavlink_set.param_value;
6✔
126
    mavlink_value.param_type = mavlink_set.param_type;
6✔
127

128
    return set_from_mavlink_param_value_bytewise(mavlink_value);
6✔
129
}
130

131
bool ParamValue::set_from_mavlink_param_ext_set(const mavlink_param_ext_set_t& mavlink_ext_set)
5✔
132
{
133
    switch (mavlink_ext_set.param_type) {
5✔
134
        case MAV_PARAM_EXT_TYPE_UINT8: {
×
135
            uint8_t temp;
136
            memcpy(&temp, &mavlink_ext_set.param_value[0], sizeof(temp));
×
137
            _value = temp;
×
138
        } break;
×
139
        case MAV_PARAM_EXT_TYPE_INT8: {
×
140
            int8_t temp;
141
            memcpy(&temp, &mavlink_ext_set.param_value[0], sizeof(temp));
×
142
            _value = temp;
×
143
        } break;
×
144
        case MAV_PARAM_EXT_TYPE_UINT16: {
×
145
            uint16_t temp;
146
            memcpy(&temp, &mavlink_ext_set.param_value[0], sizeof(temp));
×
147
            _value = temp;
×
148
        } break;
×
149
        case MAV_PARAM_EXT_TYPE_INT16: {
×
150
            int16_t temp;
151
            memcpy(&temp, &mavlink_ext_set.param_value[0], sizeof(temp));
×
152
            _value = temp;
×
153
        } break;
×
154
        case MAV_PARAM_EXT_TYPE_UINT32: {
×
155
            uint32_t temp;
156
            memcpy(&temp, &mavlink_ext_set.param_value[0], sizeof(temp));
×
157
            _value = temp;
×
158
        } break;
×
159
        case MAV_PARAM_EXT_TYPE_INT32: {
3✔
160
            int32_t temp;
161
            memcpy(&temp, &mavlink_ext_set.param_value[0], sizeof(temp));
3✔
162
            _value = temp;
3✔
163
        } break;
3✔
164
        case MAV_PARAM_EXT_TYPE_UINT64: {
×
165
            uint64_t temp;
166
            memcpy(&temp, &mavlink_ext_set.param_value[0], sizeof(temp));
×
167
            _value = temp;
×
168
        } break;
×
169
        case MAV_PARAM_EXT_TYPE_INT64: {
×
170
            int64_t temp;
171
            memcpy(&temp, &mavlink_ext_set.param_value[0], sizeof(temp));
×
172
            _value = temp;
×
173
        } break;
×
174
        case MAV_PARAM_EXT_TYPE_REAL32: {
×
175
            float temp;
176
            memcpy(&temp, &mavlink_ext_set.param_value[0], sizeof(temp));
×
177
            _value = temp;
×
178
        } break;
×
179
        case MAV_PARAM_EXT_TYPE_REAL64: {
×
180
            double temp;
181
            memcpy(&temp, &mavlink_ext_set.param_value[0], sizeof(temp));
×
182
            _value = temp;
×
183
        } break;
×
184
        case MAV_PARAM_EXT_TYPE_CUSTOM: {
2✔
185
            std::size_t len = std::min(std::size_t(128), strlen(mavlink_ext_set.param_value));
2✔
186
            _value = std::string(mavlink_ext_set.param_value, mavlink_ext_set.param_value + len);
2✔
187
        } break;
2✔
188
        default:
×
189
            // This would be worrying
190
            LogErr() << "Error: unknown mavlink ext param type";
×
191
            assert(false);
×
192
            return false;
193
    }
194
    return true;
5✔
195
}
196

197
// FIXME: this function can collapse with the one above.
198
bool ParamValue::set_from_mavlink_param_ext_value(
61✔
199
    const mavlink_param_ext_value_t& mavlink_ext_value)
200
{
201
    switch (mavlink_ext_value.param_type) {
61✔
202
        case MAV_PARAM_EXT_TYPE_UINT8: {
×
203
            uint8_t temp;
204
            memcpy(&temp, &mavlink_ext_value.param_value[0], sizeof(temp));
×
205
            _value = temp;
×
206
        } break;
×
207
        case MAV_PARAM_EXT_TYPE_INT8: {
×
208
            int8_t temp;
209
            memcpy(&temp, &mavlink_ext_value.param_value[0], sizeof(temp));
×
210
            _value = temp;
×
211
        } break;
×
212
        case MAV_PARAM_EXT_TYPE_UINT16: {
×
213
            uint16_t temp;
214
            memcpy(&temp, &mavlink_ext_value.param_value[0], sizeof(temp));
×
215
            _value = temp;
×
216
        } break;
×
217
        case MAV_PARAM_EXT_TYPE_INT16: {
×
218
            int16_t temp;
219
            memcpy(&temp, &mavlink_ext_value.param_value[0], sizeof(temp));
×
220
            _value = temp;
×
221
        } break;
×
222
        case MAV_PARAM_EXT_TYPE_UINT32: {
×
223
            uint32_t temp;
224
            memcpy(&temp, &mavlink_ext_value.param_value[0], sizeof(temp));
×
225
            _value = temp;
×
226
        } break;
×
227
        case MAV_PARAM_EXT_TYPE_INT32: {
45✔
228
            int32_t temp;
229
            memcpy(&temp, &mavlink_ext_value.param_value[0], sizeof(temp));
45✔
230
            _value = temp;
45✔
231
        } break;
45✔
232
        case MAV_PARAM_EXT_TYPE_UINT64: {
×
233
            uint64_t temp;
234
            memcpy(&temp, &mavlink_ext_value.param_value[0], sizeof(temp));
×
235
            _value = temp;
×
236
        } break;
×
237
        case MAV_PARAM_EXT_TYPE_INT64: {
×
238
            int64_t temp;
239
            memcpy(&temp, &mavlink_ext_value.param_value[0], sizeof(temp));
×
240
            _value = temp;
×
241
        } break;
×
242
        case MAV_PARAM_EXT_TYPE_REAL32: {
6✔
243
            float temp;
244
            memcpy(&temp, &mavlink_ext_value.param_value[0], sizeof(temp));
6✔
245
            _value = temp;
6✔
246
        } break;
6✔
247
        case MAV_PARAM_EXT_TYPE_REAL64: {
×
248
            double temp;
249
            memcpy(&temp, &mavlink_ext_value.param_value[0], sizeof(temp));
×
250
            _value = temp;
×
251
        } break;
×
252
        case MAV_PARAM_EXT_TYPE_CUSTOM: {
10✔
253
            std::size_t len = strnlen(mavlink_ext_value.param_value, 128);
10✔
254
            _value =
255
                std::string(mavlink_ext_value.param_value, mavlink_ext_value.param_value + len);
10✔
256
        } break;
10✔
257
        default:
×
258
            // This would be worrying
259
            LogErr() << "Error: unknown mavlink ext param type";
×
260
            assert(false);
×
261
            return false;
262
    }
263
    return true;
61✔
264
}
265

266
bool ParamValue::set_from_xml(const std::string& type_str, const std::string& value_str)
6,276✔
267
{
268
    if (type_str == "bool") {
6,276✔
269
        // bool is internally handled as uint8_t
270
        _value = static_cast<uint8_t>(std::stoi(value_str));
×
271
    } else if (type_str == "uint8") {
6,276✔
272
        _value = static_cast<uint8_t>(std::stoi(value_str));
×
273
    } else if (type_str == "int8") {
6,276✔
274
        _value = static_cast<int8_t>(std::stoi(value_str));
50✔
275
    } else if (type_str == "uint16") {
6,226✔
276
        _value = static_cast<uint16_t>(std::stoi(value_str));
×
277
    } else if (type_str == "int16") {
6,226✔
278
        _value = static_cast<int16_t>(std::stoi(value_str));
40✔
279
    } else if (type_str == "uint32") {
6,186✔
280
        _value = static_cast<uint32_t>(std::stoi(value_str));
35✔
281
    } else if (type_str == "int32") {
6,151✔
282
        _value = static_cast<int32_t>(std::stoi(value_str));
1,469✔
283
    } else if (type_str == "uint64") {
4,682✔
284
        _value = static_cast<uint64_t>(std::stoll(value_str));
×
285
    } else if (type_str == "int64") {
4,682✔
286
        _value = static_cast<int64_t>(std::stoll(value_str));
×
287
    } else if (type_str == "float") {
4,682✔
288
        _value = static_cast<float>(std::stof(value_str));
4,682✔
289
    } else if (type_str == "double") {
×
290
        _value = static_cast<double>(std::stod(value_str));
×
291
    } else {
292
        LogErr() << "Unknown type: " << type_str;
×
293
        return false;
×
294
    }
295
    return true;
6,276✔
296
}
297

298
bool ParamValue::set_empty_type_from_xml(const std::string& type_str)
301✔
299
{
300
    if (type_str == "bool") {
301✔
301
        _value = uint8_t(0);
×
302
    } else if (type_str == "uint8") {
301✔
303
        _value = uint8_t(0);
×
304
    } else if (type_str == "int8") {
301✔
305
        _value = int8_t(0);
20✔
306
    } else if (type_str == "uint16") {
281✔
307
        _value = uint16_t(0);
×
308
    } else if (type_str == "int16") {
281✔
309
        _value = int16_t(0);
10✔
310
    } else if (type_str == "uint32") {
271✔
311
        _value = uint32_t(0);
3✔
312
    } else if (type_str == "int32") {
268✔
313
        _value = int32_t(0);
237✔
314
    } else if (type_str == "uint64") {
31✔
315
        _value = uint64_t(0);
×
316
    } else if (type_str == "int64") {
31✔
317
        _value = int64_t(0);
×
318
    } else if (type_str == "float") {
31✔
319
        _value = 0.0f;
31✔
320
    } else if (type_str == "double") {
×
321
        _value = 0.0;
×
322
    } else {
323
        LogErr() << "Unknown type: " << type_str;
×
324
        return false;
×
325
    }
326
    return true;
301✔
327
}
328

329
[[nodiscard]] MAV_PARAM_TYPE ParamValue::get_mav_param_type() const
39✔
330
{
331
    if (std::get_if<uint8_t>(&_value)) {
39✔
332
        return MAV_PARAM_TYPE_UINT8;
×
333
    } else if (std::get_if<int8_t>(&_value)) {
39✔
334
        return MAV_PARAM_TYPE_INT8;
×
335
    } else if (std::get_if<uint16_t>(&_value)) {
39✔
336
        return MAV_PARAM_TYPE_UINT16;
×
337
    } else if (std::get_if<int16_t>(&_value)) {
39✔
338
        return MAV_PARAM_TYPE_INT16;
×
339
    } else if (std::get_if<uint32_t>(&_value)) {
39✔
340
        return MAV_PARAM_TYPE_UINT32;
×
341
    } else if (std::get_if<int32_t>(&_value)) {
39✔
342
        return MAV_PARAM_TYPE_INT32;
20✔
343
    } else if (std::get_if<uint64_t>(&_value)) {
19✔
344
        return MAV_PARAM_TYPE_UINT64;
×
345
    } else if (std::get_if<int64_t>(&_value)) {
19✔
346
        return MAV_PARAM_TYPE_INT64;
×
347
    } else if (std::get_if<float>(&_value)) {
19✔
348
        return MAV_PARAM_TYPE_REAL32;
19✔
349
    } else if (std::get_if<double>(&_value)) {
×
350
        return MAV_PARAM_TYPE_REAL64;
×
351
    } else {
352
        LogErr() << "Unknown data type for param.";
×
353
        assert(false);
×
354
        return MAV_PARAM_TYPE_INT32;
355
    }
356
}
357

358
[[nodiscard]] MAV_PARAM_EXT_TYPE ParamValue::get_mav_param_ext_type() const
79✔
359
{
360
    if (std::get_if<uint8_t>(&_value)) {
79✔
361
        return MAV_PARAM_EXT_TYPE_UINT8;
×
362
    } else if (std::get_if<int8_t>(&_value)) {
79✔
363
        return MAV_PARAM_EXT_TYPE_INT8;
×
364
    } else if (std::get_if<uint16_t>(&_value)) {
79✔
365
        return MAV_PARAM_EXT_TYPE_UINT16;
×
366
    } else if (std::get_if<int16_t>(&_value)) {
79✔
367
        return MAV_PARAM_EXT_TYPE_INT16;
×
368
    } else if (std::get_if<uint32_t>(&_value)) {
79✔
369
        return MAV_PARAM_EXT_TYPE_UINT32;
×
370
    } else if (std::get_if<int32_t>(&_value)) {
79✔
371
        return MAV_PARAM_EXT_TYPE_INT32;
53✔
372
    } else if (std::get_if<uint64_t>(&_value)) {
26✔
373
        return MAV_PARAM_EXT_TYPE_UINT64;
×
374
    } else if (std::get_if<int64_t>(&_value)) {
26✔
375
        return MAV_PARAM_EXT_TYPE_INT64;
×
376
    } else if (std::get_if<float>(&_value)) {
26✔
377
        return MAV_PARAM_EXT_TYPE_REAL32;
8✔
378
    } else if (std::get_if<double>(&_value)) {
18✔
379
        return MAV_PARAM_EXT_TYPE_REAL64;
×
380
    } else if (std::get_if<std::string>(&_value)) {
18✔
381
        return MAV_PARAM_EXT_TYPE_CUSTOM;
18✔
382
    } else {
383
        LogErr() << "Unknown data type for param.";
×
384
        assert(false);
×
385
        return MAV_PARAM_EXT_TYPE_INT32;
386
    }
387
}
388

389
bool ParamValue::set_as_same_type(const std::string& value_str)
×
390
{
391
    if (std::get_if<uint8_t>(&_value)) {
×
392
        _value = uint8_t(std::stoi(value_str));
×
393
    } else if (std::get_if<int8_t>(&_value)) {
×
394
        _value = int8_t(std::stoi(value_str));
×
395
    } else if (std::get_if<uint16_t>(&_value)) {
×
396
        _value = uint16_t(std::stoi(value_str));
×
397
    } else if (std::get_if<int16_t>(&_value)) {
×
398
        _value = int16_t(std::stoi(value_str));
×
399
    } else if (std::get_if<uint32_t>(&_value)) {
×
400
        _value = uint32_t(std::stoi(value_str));
×
401
    } else if (std::get_if<int32_t>(&_value)) {
×
402
        _value = int32_t(std::stoi(value_str));
×
403
    } else if (std::get_if<uint64_t>(&_value)) {
×
404
        _value = uint64_t(std::stoll(value_str));
×
405
    } else if (std::get_if<int64_t>(&_value)) {
×
406
        _value = int64_t(std::stoll(value_str));
×
407
    } else if (std::get_if<float>(&_value)) {
×
408
        _value = float(std::stof(value_str));
×
409
    } else if (std::get_if<double>(&_value)) {
×
410
        _value = double(std::stod(value_str));
×
411
    } else {
412
        LogErr() << "Unknown type";
×
413
        return false;
×
414
    }
415
    return true;
×
416
}
417

418
[[nodiscard]] float ParamValue::get_4_float_bytes_bytewise() const
39✔
419
{
420
    if (std::get_if<float>(&_value)) {
39✔
421
        return std::get<float>(_value);
19✔
422
    } else if (std::get_if<int32_t>(&_value)) {
20✔
423
        return *(reinterpret_cast<const float*>(&std::get<int32_t>(_value)));
20✔
424
    } else {
425
        LogErr() << "Unknown type";
×
426
        assert(false);
×
427
        return NAN;
428
    }
429
}
430

431
[[nodiscard]] float ParamValue::get_4_float_bytes_cast() const
×
432
{
433
    if (std::get_if<float>(&_value)) {
×
434
        return std::get<float>(_value);
×
435
    } else if (std::get_if<uint32_t>(&_value)) {
×
436
        return static_cast<float>(std::get<uint32_t>(_value));
×
437
    } else if (std::get_if<int32_t>(&_value)) {
×
438
        return static_cast<float>(std::get<int32_t>(_value));
×
439
    } else if (std::get_if<uint16_t>(&_value)) {
×
440
        return static_cast<float>(std::get<uint16_t>(_value));
×
441
    } else if (std::get_if<int16_t>(&_value)) {
×
442
        return static_cast<float>(std::get<int16_t>(_value));
×
443
    } else if (std::get_if<uint8_t>(&_value)) {
×
444
        return static_cast<float>(std::get<uint8_t>(_value));
×
445
    } else if (std::get_if<int8_t>(&_value)) {
×
446
        return static_cast<float>(std::get<int8_t>(_value));
×
447
    } else {
448
        LogErr() << "Unknown type";
×
449
        assert(false);
×
450
        return NAN;
451
    }
452
}
453

454
[[nodiscard]] std::optional<int> ParamValue::get_int() const
66✔
455
{
456
    if (std::get_if<uint32_t>(&_value)) {
66✔
457
        return static_cast<int>(std::get<uint32_t>(_value));
×
458
    } else if (std::get_if<int32_t>(&_value)) {
66✔
459
        return static_cast<int>(std::get<int32_t>(_value));
66✔
460
    } else if (std::get_if<uint16_t>(&_value)) {
×
461
        return static_cast<int>(std::get<uint16_t>(_value));
×
462
    } else if (std::get_if<int16_t>(&_value)) {
×
463
        return static_cast<int>(std::get<int16_t>(_value));
×
464
    } else if (std::get_if<uint8_t>(&_value)) {
×
465
        return static_cast<int>(std::get<uint8_t>(_value));
×
466
    } else if (std::get_if<int8_t>(&_value)) {
×
467
        return static_cast<int>(std::get<int8_t>(_value));
×
468
    } else {
469
        LogErr() << "Not int type";
×
470
        return {};
×
471
    }
472
}
473

474
bool ParamValue::set_int(int new_value)
5✔
475
{
476
    if (std::get_if<uint8_t>(&_value)) {
5✔
477
        _value = static_cast<uint8_t>(new_value);
3✔
478
        return true;
3✔
479
    } else if (std::get_if<int8_t>(&_value)) {
2✔
480
        _value = static_cast<int8_t>(new_value);
×
481
        return true;
×
482
    } else if (std::get_if<uint16_t>(&_value)) {
2✔
483
        _value = static_cast<uint16_t>(new_value);
×
484
        return true;
×
485
    } else if (std::get_if<int16_t>(&_value)) {
2✔
486
        _value = static_cast<int16_t>(new_value);
×
487
        return true;
×
488
    } else if (std::get_if<uint32_t>(&_value)) {
2✔
489
        _value = static_cast<uint32_t>(new_value);
×
490
        return true;
×
491
    } else if (std::get_if<int32_t>(&_value)) {
2✔
492
        _value = new_value;
2✔
493
        return true;
2✔
494
    } else {
495
        return false;
×
496
    }
497
}
498

499
void ParamValue::set_float(float new_value)
2✔
500
{
501
    _value = new_value;
2✔
502
}
2✔
503

504
void ParamValue::set_custom(const std::string& new_value)
2✔
505
{
506
    _value = new_value;
2✔
507
}
2✔
508

509
[[nodiscard]] std::optional<float> ParamValue::get_float() const
4✔
510
{
511
    if (std::get_if<float>(&_value)) {
4✔
512
        return std::get<float>(_value);
4✔
513
    } else {
514
        LogErr() << "Not float type";
×
515
        return {};
×
516
    }
517
}
518

519
[[nodiscard]] std::optional<std::string> ParamValue::get_custom() const
4✔
520
{
521
    if (std::get_if<std::string>(&_value)) {
4✔
522
        return std::get<std::string>(_value);
4✔
523
    } else {
524
        LogErr() << "Not custom type";
×
525
        return {};
×
526
    }
527
}
528

529
std::array<char, 128> ParamValue::get_128_bytes() const
79✔
530
{
531
    std::array<char, 128> bytes{};
79✔
532

533
    if (std::get_if<uint8_t>(&_value)) {
79✔
534
        memcpy(bytes.data(), &std::get<uint8_t>(_value), sizeof(uint8_t));
×
535
    } else if (std::get_if<int8_t>(&_value)) {
79✔
536
        memcpy(bytes.data(), &std::get<int8_t>(_value), sizeof(int8_t));
×
537
    } else if (std::get_if<uint16_t>(&_value)) {
79✔
538
        memcpy(bytes.data(), &std::get<uint16_t>(_value), sizeof(uint16_t));
×
539
    } else if (std::get_if<int16_t>(&_value)) {
79✔
540
        memcpy(bytes.data(), &std::get<int16_t>(_value), sizeof(int16_t));
×
541
    } else if (std::get_if<uint32_t>(&_value)) {
79✔
542
        memcpy(bytes.data(), &std::get<uint32_t>(_value), sizeof(uint32_t));
×
543
    } else if (std::get_if<int32_t>(&_value)) {
79✔
544
        memcpy(bytes.data(), &std::get<int32_t>(_value), sizeof(int32_t));
53✔
545
    } else if (std::get_if<uint64_t>(&_value)) {
26✔
546
        memcpy(bytes.data(), &std::get<uint64_t>(_value), sizeof(uint64_t));
×
547
    } else if (std::get_if<int64_t>(&_value)) {
26✔
548
        memcpy(bytes.data(), &std::get<int64_t>(_value), sizeof(int64_t));
×
549
    } else if (std::get_if<float>(&_value)) {
26✔
550
        memcpy(bytes.data(), &std::get<float>(_value), sizeof(float));
8✔
551
    } else if (std::get_if<double>(&_value)) {
18✔
552
        memcpy(bytes.data(), &std::get<double>(_value), sizeof(double));
×
553
    } else if (std::get_if<std::string>(&_value)) {
18✔
554
        auto str_ptr = &std::get<std::string>(_value);
18✔
555
        // Copy all data in string, max 128 bytes
556
        memcpy(bytes.data(), str_ptr->data(), std::min(bytes.size(), str_ptr->size()));
18✔
557
    } else {
558
        LogErr() << "Unknown type";
×
559
        assert(false);
×
560
    }
561

562
    return bytes;
79✔
563
}
564

565
[[nodiscard]] std::string ParamValue::get_string() const
320✔
566
{
567
    return std::visit([](auto value) { return to_string(value); }, _value);
640✔
568
}
569

570
[[nodiscard]] bool ParamValue::is_same_type(const ParamValue& rhs) const
11,174✔
571
{
572
    if ((std::get_if<uint8_t>(&_value) && std::get_if<uint8_t>(&rhs._value)) ||
22,348✔
573
        (std::get_if<int8_t>(&_value) && std::get_if<int8_t>(&rhs._value)) ||
22,348✔
574
        (std::get_if<uint16_t>(&_value) && std::get_if<uint16_t>(&rhs._value)) ||
22,222✔
575
        (std::get_if<int16_t>(&_value) && std::get_if<int16_t>(&rhs._value)) ||
22,222✔
576
        (std::get_if<uint32_t>(&_value) && std::get_if<uint32_t>(&rhs._value)) ||
22,156✔
577
        (std::get_if<int32_t>(&_value) && std::get_if<int32_t>(&rhs._value)) ||
22,159✔
578
        (std::get_if<uint64_t>(&_value) && std::get_if<uint64_t>(&rhs._value)) ||
1,122✔
579
        (std::get_if<int64_t>(&_value) && std::get_if<int64_t>(&rhs._value)) ||
1,122✔
580
        (std::get_if<float>(&_value) && std::get_if<float>(&rhs._value)) ||
1,122✔
581
        (std::get_if<double>(&_value) && std::get_if<double>(&rhs._value)) ||
22,371✔
582
        (std::get_if<std::string>(&_value) && std::get_if<std::string>(&rhs._value))) {
23✔
583
        return true;
11,170✔
584
    }
585

586
    if ((std::get_if<uint8_t>(&_value) || std::get_if<int8_t>(&_value) ||
12✔
587
         std::get_if<uint16_t>(&_value) || std::get_if<int16_t>(&_value) ||
12✔
588
         std::get_if<uint32_t>(&_value) || std::get_if<int32_t>(&_value) ||
9✔
589
         std::get_if<uint64_t>(&_value) || std::get_if<int64_t>(&_value)) &&
12✔
590
        (std::get_if<uint8_t>(&rhs._value) || std::get_if<int8_t>(&rhs._value) ||
9✔
591
         std::get_if<uint16_t>(&rhs._value) || std::get_if<int16_t>(&rhs._value) ||
9✔
592
         std::get_if<uint32_t>(&rhs._value) || std::get_if<int32_t>(&rhs._value) ||
9✔
593
         std::get_if<uint64_t>(&rhs._value) || std::get_if<int64_t>(&rhs._value))) {
6✔
594
        LogDebug() << "Ignoring int mismatch between " << typestr() << " and " << rhs.typestr();
×
595
        return true;
×
596
    }
597

598
    if ((std::get_if<float>(&_value) || std::get_if<double>(&_value)) &&
4✔
599
        (std::get_if<float>(&rhs._value) || std::get_if<double>(&rhs._value))) {
×
600
        LogDebug() << "Ignoring float/double mismatch between " << typestr() << " and "
×
601
                   << rhs.typestr();
×
602
        return true;
×
603
    }
604

605
    LogWarn() << "Comparison type mismatch between " << typestr() << " and " << rhs.typestr();
4✔
606
    return false;
4✔
607
}
608

609
bool ParamValue::operator==(const std::string& value_str) const
1,617✔
610
{
611
    if (std::get_if<uint8_t>(&_value)) {
1,617✔
612
        return std::get<uint8_t>(_value) == std::stoi(value_str);
×
613
    } else if (std::get_if<int8_t>(&_value)) {
1,617✔
614
        return std::get<int8_t>(_value) == std::stoi(value_str);
50✔
615
    } else if (std::get_if<uint16_t>(&_value)) {
1,567✔
616
        return std::get<uint16_t>(_value) == std::stoi(value_str);
×
617
    } else if (std::get_if<int16_t>(&_value)) {
1,567✔
618
        return std::get<int16_t>(_value) == std::stoi(value_str);
×
619
    } else if (std::get_if<uint32_t>(&_value)) {
1,567✔
620
        return std::get<uint32_t>(_value) == std::stoul(value_str);
35✔
621
    } else if (std::get_if<int32_t>(&_value)) {
1,532✔
622
        return std::get<int32_t>(_value) == std::stol(value_str);
1,071✔
623
    } else if (std::get_if<uint64_t>(&_value)) {
461✔
624
        return std::get<uint64_t>(_value) == std::stoull(value_str);
×
625
    } else if (std::get_if<int64_t>(&_value)) {
461✔
626
        return std::get<int64_t>(_value) == std::stoll(value_str);
×
627
    } else if (std::get_if<float>(&_value)) {
461✔
628
        return std::get<float>(_value) == std::stof(value_str);
461✔
629
    } else if (std::get_if<double>(&_value)) {
×
630
        return std::get<double>(_value) == std::stod(value_str);
×
631
    } else {
632
        // This also covers custom_type_t
633
        return false;
×
634
    }
635
}
636

637
std::ostream& operator<<(std::ostream& str, const ParamValue& obj)
53✔
638
{
639
    str << obj.get_string();
53✔
640
    return str;
53✔
641
}
642

643
[[nodiscard]] std::string ParamValue::typestr() const
8✔
644
{
645
    if (std::get_if<uint8_t>(&_value)) {
8✔
646
        return "uint8_t";
×
647
    } else if (std::get_if<int8_t>(&_value)) {
8✔
648
        return "int8_t";
×
649
    } else if (std::get_if<uint16_t>(&_value)) {
8✔
650
        return "uint16_t";
×
651
    } else if (std::get_if<int16_t>(&_value)) {
8✔
652
        return "int16_t";
×
653
    } else if (std::get_if<uint32_t>(&_value)) {
8✔
654
        return "uint32_t";
×
655
    } else if (std::get_if<int32_t>(&_value)) {
8✔
656
        return "int32_t";
4✔
657
    } else if (std::get_if<uint64_t>(&_value)) {
4✔
658
        return "uint64_t";
×
659
    } else if (std::get_if<int64_t>(&_value)) {
4✔
660
        return "int64_t";
×
661
    } else if (std::get_if<float>(&_value)) {
4✔
662
        return "float";
2✔
663
    } else if (std::get_if<double>(&_value)) {
2✔
664
        return "double";
×
665
    } else if (std::get_if<std::string>(&_value)) {
2✔
666
        return "custom";
2✔
667
    }
668
    // FIXME: Added to fix CI error (control reading end of non-void function)
669
    return "unknown";
×
670
}
671

672
void ParamValue::update_value_typesafe(const ParamValue& new_value)
28✔
673
{
674
    assert(this->is_same_type(new_value));
28✔
675
    _value = new_value._value;
28✔
676
}
28✔
677

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