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

mavlink / MAVSDK / 14846374211

05 May 2025 09:13PM UTC coverage: 44.218% (+0.1%) from 44.075%
14846374211

push

github

web-flow
Merge pull request #2542 from mavlink/pr-tsan

Fixing thread sanitizer issues

229 of 320 new or added lines in 20 files covered. (71.56%)

73 existing lines in 8 files now uncovered.

14784 of 33434 relevant lines covered (44.22%)

276.78 hits per line

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

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

3
#include <cassert>
4

5
namespace mavsdk {
6

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

127
    return set_from_mavlink_param_value_bytewise(mavlink_value);
4✔
128
}
129

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

561
    return bytes;
77✔
562
}
563

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

569
[[nodiscard]] bool ParamValue::is_same_type(const ParamValue& rhs) const
10,709✔
570
{
571
    if ((std::get_if<uint8_t>(&_value) && std::get_if<uint8_t>(&rhs._value)) ||
21,418✔
572
        (std::get_if<int8_t>(&_value) && std::get_if<int8_t>(&rhs._value)) ||
21,418✔
573
        (std::get_if<uint16_t>(&_value) && std::get_if<uint16_t>(&rhs._value)) ||
21,292✔
574
        (std::get_if<int16_t>(&_value) && std::get_if<int16_t>(&rhs._value)) ||
21,292✔
575
        (std::get_if<uint32_t>(&_value) && std::get_if<uint32_t>(&rhs._value)) ||
21,226✔
576
        (std::get_if<int32_t>(&_value) && std::get_if<int32_t>(&rhs._value)) ||
21,229✔
577
        (std::get_if<uint64_t>(&_value) && std::get_if<uint64_t>(&rhs._value)) ||
1,122✔
578
        (std::get_if<int64_t>(&_value) && std::get_if<int64_t>(&rhs._value)) ||
1,122✔
579
        (std::get_if<float>(&_value) && std::get_if<float>(&rhs._value)) ||
1,122✔
580
        (std::get_if<double>(&_value) && std::get_if<double>(&rhs._value)) ||
21,447✔
581
        (std::get_if<std::string>(&_value) && std::get_if<std::string>(&rhs._value))) {
29✔
582
        return true;
10,705✔
583
    }
584

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

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

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

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

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

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

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

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