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

mavlink / MAVSDK / 18329400312

07 Oct 2025 11:57PM UTC coverage: 47.68% (+0.07%) from 47.615%
18329400312

push

github

web-flow
Merge pull request #2680 from mavlink/pr-int64-json

mavlink_direct: handle (u)int > 2^32

62 of 67 new or added lines in 3 files covered. (92.54%)

27 existing lines in 10 files now uncovered.

17088 of 35839 relevant lines covered (47.68%)

446.34 hits per line

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

46.81
/src/mavsdk/plugins/mavlink_direct/mavlink_direct_impl.cpp
1
#include "mavlink_direct_impl.h"
2
#include <mav/Message.h>
3
#include <mav/MessageSet.h>
4
#include <variant>
5
#include <json/json.h>
6
#include <cmath>
7
#include <limits>
8
#include "log.h"
9
#include "connection.h"
10
#include "callback_list.tpp"
11

12
namespace mavsdk {
13

14
template class CallbackList<MavlinkDirect::MavlinkMessage>;
15

16
MavlinkDirectImpl::MavlinkDirectImpl(System& system) : PluginImplBase(system)
×
17
{
18
    if (const char* env_p = std::getenv("MAVSDK_MAVLINK_DIRECT_DEBUGGING")) {
×
19
        if (std::string(env_p) == "1") {
×
20
            _debugging = true;
×
21
        }
22
    }
23
    _system_impl->register_plugin(this);
×
24
}
×
25

26
MavlinkDirectImpl::MavlinkDirectImpl(std::shared_ptr<System> system) :
26✔
27
    PluginImplBase(std::move(system))
26✔
28
{
29
    if (const char* env_p = std::getenv("MAVSDK_MAVLINK_DIRECT_DEBUGGING")) {
26✔
30
        if (std::string(env_p) == "1") {
×
31
            _debugging = true;
×
32
        }
33
    }
34
    _system_impl->register_plugin(this);
26✔
35
}
26✔
36

37
MavlinkDirectImpl::~MavlinkDirectImpl()
52✔
38
{
39
    _system_impl->unregister_plugin(this);
26✔
40
}
52✔
41

42
void MavlinkDirectImpl::init()
26✔
43
{
44
    // Subscribe to all messages from SystemImpl and distribute to internal CallbackList
45
    _system_subscription = _system_impl->register_libmav_message_handler(
26✔
46
        "", // Empty string means all messages
47
        [this](const Mavsdk::MavlinkMessage& message) {
118✔
48
            // Convert Mavsdk::MavlinkMessage to MavlinkDirect::MavlinkMessage
49
            MavlinkDirect::MavlinkMessage mavlink_direct_message;
59✔
50
            mavlink_direct_message.message_name = message.message_name;
59✔
51
            mavlink_direct_message.system_id = message.system_id;
59✔
52
            mavlink_direct_message.component_id = message.component_id;
59✔
53
            mavlink_direct_message.target_system_id = message.target_system_id;
59✔
54
            mavlink_direct_message.target_component_id = message.target_component_id;
59✔
55
            mavlink_direct_message.fields_json = message.fields_json;
59✔
56

57
            // Distribute to all internal subscribers
58
            _callbacks.queue(mavlink_direct_message, [this](const std::function<void()>& func) {
59✔
59
                _system_impl->call_user_callback(func);
51✔
60
            });
51✔
61
        });
59✔
62
}
26✔
63

64
void MavlinkDirectImpl::deinit()
26✔
65
{
66
    // Unsubscribe from SystemImpl - this automatically prevents dangling callbacks
67
    if (_system_subscription.valid()) {
26✔
68
        _system_impl->unregister_libmav_message_handler(_system_subscription);
26✔
69
        _system_subscription = {}; // Reset handle
26✔
70
    }
71
    // Internal CallbackList will be automatically cleaned up when destroyed
72
}
26✔
73

74
void MavlinkDirectImpl::enable() {}
26✔
75

76
void MavlinkDirectImpl::disable() {}
26✔
77

78
MavlinkDirect::Result MavlinkDirectImpl::send_message(MavlinkDirect::MavlinkMessage message)
23✔
79
{
80
    // Get access to the MessageSet through the system
81
    auto& message_set = _system_impl->get_message_set();
23✔
82

83
    // Create libmav message from the message name
84
    auto libmav_message_opt = message_set.create(message.message_name);
23✔
85
    if (!libmav_message_opt) {
23✔
86
        LogErr() << "Failed to create message: " << message.message_name;
×
87
        return MavlinkDirect::Result::InvalidMessage; // Message type not found
×
88
    }
89

90
    if (_debugging) {
23✔
91
        LogDebug() << "Created message " << message.message_name
×
92
                   << " with ID: " << libmav_message_opt.value().id();
×
93
    }
94

95
    auto libmav_message = libmav_message_opt.value();
23✔
96

97
    // Convert JSON fields to libmav message fields
98
    if (!json_to_libmav_message(message.fields_json, libmav_message)) {
23✔
99
        LogErr() << "Failed to convert JSON fields to libmav message for " << message.message_name;
×
100
        return MavlinkDirect::Result::InvalidField; // JSON conversion failed
×
101
    }
102

103
    if (_debugging) {
23✔
104
        LogDebug() << "Successfully populated fields for " << message.message_name;
×
105
    }
106

107
    // Set target system/component if specified
108
    if (message.target_system_id != 0) {
23✔
109
        // For messages that have target_system field, set it
110
        libmav_message.set("target_system", static_cast<uint8_t>(message.target_system_id));
×
111
    }
112
    if (message.target_component_id != 0) {
23✔
113
        // For messages that have target_component field, set it
114
        libmav_message.set(
×
115
            "target_component_id", static_cast<uint8_t>(message.target_component_id));
×
116
    }
117

118
    if (_debugging) {
23✔
119
        LogDebug() << "Sending " << message.message_name << " via unified libmav API";
×
120
    }
121

122
    _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
23✔
123
        mavlink_message_t mavlink_message;
124

125
        // Use clean libmav helper methods to get payload data
126
        auto payload_view = libmav_message.getPayloadView();
23✔
127
        const uint8_t payload_length = libmav_message.getPayloadLength();
23✔
128

129
        // Set up the mavlink_message_t structure
130
        mavlink_message.msgid = libmav_message.id();
23✔
131
        mavlink_message.len = payload_length;
23✔
132
        memcpy(mavlink_message.payload64, payload_view.first, payload_length);
23✔
133

134
        mavlink_finalize_message_chan(
46✔
135
            &mavlink_message,
136
            mavlink_address.system_id,
23✔
137
            mavlink_address.component_id,
23✔
138
            channel,
139
            payload_length,
140
            libmav_message.type().maxPayloadSize(),
23✔
141
            libmav_message.type().crcExtra());
23✔
142

143
        return mavlink_message;
23✔
144
    });
145

146
    if (_debugging) {
23✔
147
        LogDebug() << "Successfully sent " << message.message_name << " as raw data";
×
148
    }
149

150
    return MavlinkDirect::Result::Success;
23✔
151
}
152

153
MavlinkDirect::MessageHandle MavlinkDirectImpl::subscribe_message(
14✔
154
    std::string message_name, const MavlinkDirect::MessageCallback& callback)
155
{
156
    // Add filtering callback to internal CallbackList
157
    auto filtering_callback = [message_name,
51✔
158
                               callback](const MavlinkDirect::MavlinkMessage& message) {
159
        // Apply message filtering (empty string means all messages)
160
        if (!message_name.empty() && message_name != message.message_name) {
51✔
161
            return;
22✔
162
        }
163

164
        // Call user callback for matching messages
165
        callback(message);
29✔
166
    };
14✔
167

168
    // Subscribe to internal CallbackList and return handle directly
169
    return _callbacks.subscribe(filtering_callback);
14✔
170
}
14✔
171

172
void MavlinkDirectImpl::unsubscribe_message(MavlinkDirect::MessageHandle handle)
14✔
173
{
174
    // Unregister from internal CallbackList directly
175
    _callbacks.unsubscribe(handle);
14✔
176
}
14✔
177

178
std::optional<uint32_t> MavlinkDirectImpl::message_name_to_id(const std::string& name) const
×
179
{
180
    // Get MessageSet to access message definitions
181
    auto& message_set = _system_impl->get_message_set();
×
182

183
    // Use MessageSet's message name to ID conversion
184
    auto id_opt = message_set.idForMessage(name);
×
185
    if (id_opt.has_value()) {
×
186
        return static_cast<uint32_t>(id_opt.value());
×
187
    }
188

189
    return std::nullopt;
×
190
}
191

192
std::optional<std::string> MavlinkDirectImpl::message_id_to_name(uint32_t id) const
×
193
{
194
    // Get MessageSet to access message definitions
195
    auto& message_set = _system_impl->get_message_set();
×
196

197
    // Use MessageSet's message ID to name conversion
198
    auto message_def = message_set.getMessageDefinition(static_cast<int>(id));
×
199
    if (message_def) {
×
200
        return message_def.get().name();
×
201
    }
202
    return std::nullopt;
×
203
}
204

205
Json::Value MavlinkDirectImpl::libmav_to_json(const mav::Message& msg) const
×
206
{
207
    (void)msg;
208
    // TODO: Implement field iteration once libmav noexcept API is stable
209
    return Json::Value();
×
210
}
211

212
bool MavlinkDirectImpl::json_to_libmav(const Json::Value& json, mav::Message& msg) const
×
213
{
214
    (void)json;
215
    (void)msg;
216
    // TODO: Implement once libmav noexcept API set methods are stable
217
    return false;
×
218
}
219

220
bool MavlinkDirectImpl::json_to_libmav_message(
23✔
221
    const std::string& json_string, mav::Message& msg) const
222
{
223
    Json::Value json;
23✔
224
    Json::Reader reader;
23✔
225

226
    if (!reader.parse(json_string, json)) {
23✔
227
        LogErr() << "Failed to parse JSON: " << json_string;
×
228
        return false;
×
229
    }
230

231
    // Iterate through all JSON fields and set them in the libmav message
232
    for (const auto& field_name : json.getMemberNames()) {
211✔
233
        const Json::Value& field_value = json[field_name];
188✔
234

235
        // Convert JSON values to appropriate types and set in message
236
        // libmav handles type casting based on field definition, so we just need to pass
237
        // int64/uint64
238
        if (field_value.isInt() || field_value.isInt64()) {
188✔
239
            int64_t value = field_value.asInt64();
170✔
240
            auto result = msg.set(field_name, value);
170✔
241
            if (result != ::mav::MessageResult::Success) {
170✔
NEW
242
                LogWarn() << "Failed to set integer field " << field_name << " = " << value;
×
243
            }
244
        } else if (field_value.isUInt() || field_value.isUInt64()) {
18✔
NEW
245
            uint64_t value = field_value.asUInt64();
×
NEW
246
            auto result = msg.set(field_name, value);
×
UNCOV
247
            if (result != ::mav::MessageResult::Success) {
×
NEW
248
                LogWarn() << "Failed to set unsigned integer field " << field_name << " = "
×
NEW
249
                          << value;
×
250
            }
251
        } else if (field_value.isNull() || field_value.isDouble()) {
18✔
252
            // Handle float/double values (including null -> NaN)
253
            auto field_opt = msg.type().getField(field_name);
6✔
254
            if (!field_opt) {
6✔
255
                LogWarn() << "Field " << field_name << " not found in message definition";
×
256
                continue;
×
257
            }
258

259
            auto field = field_opt.value();
6✔
260
            ::mav::MessageResult result = ::mav::MessageResult::FieldNotFound;
6✔
261

262
            if (field.type.base_type == ::mav::FieldType::BaseType::FLOAT) {
6✔
263
                if (field_value.isNull()) {
4✔
264
                    result = msg.set(field_name, std::numeric_limits<float>::quiet_NaN());
3✔
265
                } else {
266
                    result = msg.set(field_name, static_cast<float>(field_value.asFloat()));
1✔
267
                }
268
            } else if (field.type.base_type == ::mav::FieldType::BaseType::DOUBLE) {
2✔
269
                if (field_value.isNull()) {
2✔
270
                    result = msg.set(field_name, std::numeric_limits<double>::quiet_NaN());
1✔
271
                } else {
272
                    result = msg.set(field_name, field_value.asDouble());
1✔
273
                }
274
            } else {
275
                LogWarn() << "Field " << field_name << " is not a float or double field";
×
276
                continue;
×
277
            }
278

279
            if (result != ::mav::MessageResult::Success) {
6✔
280
                LogWarn() << "Failed to set float/double field " << field_name << " = "
×
281
                          << (field_value.isNull() ? "null" :
×
282
                                                     std::to_string(field_value.asDouble()));
×
283
            }
284
        } else if (field_value.isString()) {
12✔
285
            auto result = msg.setString(field_name, field_value.asString());
1✔
286
            if (result != ::mav::MessageResult::Success) {
1✔
287
                LogWarn() << "Failed to set string field " << field_name << " = "
×
288
                          << field_value.asString();
×
289
            }
290
        } else if (field_value.isArray()) {
11✔
291
            // Handle array fields with proper type detection
292
            auto array_size = field_value.size();
11✔
293

294
            // Get field definition to determine correct type
295
            auto field_opt = msg.type().getField(field_name);
11✔
296
            if (!field_opt) {
11✔
297
                LogWarn() << "Field " << field_name << " not found in message definition";
×
298
                continue;
×
299
            }
300

301
            auto field = field_opt.value();
11✔
302
            if (field.type.size <= 1) {
11✔
303
                LogWarn() << "Field " << field_name << " is not an array field";
×
304
                continue;
×
305
            }
306

307
            // Create and populate only the correct vector type
308
            ::mav::MessageResult result = ::mav::MessageResult::FieldNotFound;
11✔
309
            switch (field.type.base_type) {
11✔
310
                case ::mav::FieldType::BaseType::UINT8: {
10✔
311
                    std::vector<uint8_t> vec;
10✔
312
                    vec.reserve(array_size);
10✔
313
                    for (Json::ArrayIndex i = 0; i < array_size; ++i) {
210✔
314
                        const auto& elem = field_value[i];
200✔
315
                        vec.push_back(elem.isNumeric() ? static_cast<uint8_t>(elem.asUInt()) : 0);
200✔
316
                    }
317
                    result = msg.set(field_name, vec);
10✔
318
                    break;
10✔
319
                }
10✔
320
                case ::mav::FieldType::BaseType::UINT16: {
×
321
                    std::vector<uint16_t> vec;
×
322
                    vec.reserve(array_size);
×
323
                    for (Json::ArrayIndex i = 0; i < array_size; ++i) {
×
324
                        const auto& elem = field_value[i];
×
325
                        vec.push_back(elem.isNumeric() ? static_cast<uint16_t>(elem.asUInt()) : 0);
×
326
                    }
327
                    result = msg.set(field_name, vec);
×
328
                    break;
×
329
                }
×
330
                case ::mav::FieldType::BaseType::UINT32: {
×
331
                    std::vector<uint32_t> vec;
×
332
                    vec.reserve(array_size);
×
333
                    for (Json::ArrayIndex i = 0; i < array_size; ++i) {
×
334
                        const auto& elem = field_value[i];
×
335
                        vec.push_back(elem.isNumeric() ? static_cast<uint32_t>(elem.asUInt()) : 0);
×
336
                    }
337
                    result = msg.set(field_name, vec);
×
338
                    break;
×
339
                }
×
340
                case ::mav::FieldType::BaseType::UINT64: {
×
341
                    std::vector<uint64_t> vec;
×
342
                    vec.reserve(array_size);
×
343
                    for (Json::ArrayIndex i = 0; i < array_size; ++i) {
×
344
                        const auto& elem = field_value[i];
×
345
                        vec.push_back(
×
346
                            elem.isNumeric() ? static_cast<uint64_t>(elem.asUInt64()) : 0);
×
347
                    }
348
                    result = msg.set(field_name, vec);
×
349
                    break;
×
350
                }
×
351
                case ::mav::FieldType::BaseType::INT8: {
×
352
                    std::vector<int8_t> vec;
×
353
                    vec.reserve(array_size);
×
354
                    for (Json::ArrayIndex i = 0; i < array_size; ++i) {
×
355
                        const auto& elem = field_value[i];
×
356
                        vec.push_back(elem.isNumeric() ? static_cast<int8_t>(elem.asInt()) : 0);
×
357
                    }
358
                    result = msg.set(field_name, vec);
×
359
                    break;
×
360
                }
×
361
                case ::mav::FieldType::BaseType::INT16: {
×
362
                    std::vector<int16_t> vec;
×
363
                    vec.reserve(array_size);
×
364
                    for (Json::ArrayIndex i = 0; i < array_size; ++i) {
×
365
                        const auto& elem = field_value[i];
×
366
                        vec.push_back(elem.isNumeric() ? static_cast<int16_t>(elem.asInt()) : 0);
×
367
                    }
368
                    result = msg.set(field_name, vec);
×
369
                    break;
×
370
                }
×
371
                case ::mav::FieldType::BaseType::INT32: {
×
372
                    std::vector<int32_t> vec;
×
373
                    vec.reserve(array_size);
×
374
                    for (Json::ArrayIndex i = 0; i < array_size; ++i) {
×
375
                        const auto& elem = field_value[i];
×
376
                        vec.push_back(elem.isNumeric() ? static_cast<int32_t>(elem.asInt()) : 0);
×
377
                    }
378
                    result = msg.set(field_name, vec);
×
379
                    break;
×
380
                }
×
381
                case ::mav::FieldType::BaseType::INT64: {
×
382
                    std::vector<int64_t> vec;
×
383
                    vec.reserve(array_size);
×
384
                    for (Json::ArrayIndex i = 0; i < array_size; ++i) {
×
385
                        const auto& elem = field_value[i];
×
386
                        vec.push_back(elem.isNumeric() ? static_cast<int64_t>(elem.asInt64()) : 0);
×
387
                    }
388
                    result = msg.set(field_name, vec);
×
389
                    break;
×
390
                }
×
391
                case ::mav::FieldType::BaseType::FLOAT: {
1✔
392
                    std::vector<float> vec;
1✔
393
                    vec.reserve(array_size);
1✔
394
                    for (Json::ArrayIndex i = 0; i < array_size; ++i) {
5✔
395
                        const auto& elem = field_value[i];
4✔
396
                        if (elem.isNumeric()) {
4✔
397
                            vec.push_back(static_cast<float>(elem.asFloat()));
2✔
398
                        } else {
399
                            // For non-numeric values (including null), use NaN
400
                            vec.push_back(std::numeric_limits<float>::quiet_NaN());
2✔
401
                        }
402
                    }
403
                    result = msg.set(field_name, vec);
1✔
404
                    break;
1✔
405
                }
1✔
406
                case ::mav::FieldType::BaseType::DOUBLE: {
×
407
                    std::vector<double> vec;
×
408
                    vec.reserve(array_size);
×
409
                    for (Json::ArrayIndex i = 0; i < array_size; ++i) {
×
410
                        const auto& elem = field_value[i];
×
411
                        if (elem.isNumeric()) {
×
412
                            vec.push_back(elem.asDouble());
×
413
                        } else {
414
                            // For non-numeric values (including null), use NaN
415
                            vec.push_back(std::numeric_limits<double>::quiet_NaN());
×
416
                        }
417
                    }
418
                    result = msg.set(field_name, vec);
×
419
                    break;
×
420
                }
×
421
                case ::mav::FieldType::BaseType::CHAR: {
×
422
                    std::vector<char> vec;
×
423
                    vec.reserve(array_size);
×
424
                    for (Json::ArrayIndex i = 0; i < array_size; ++i) {
×
425
                        const auto& elem = field_value[i];
×
426
                        vec.push_back(elem.isNumeric() ? static_cast<char>(elem.asInt()) : 0);
×
427
                    }
428
                    result = msg.set(field_name, vec);
×
429
                    break;
×
430
                }
×
431
                default:
×
432
                    LogWarn() << "Unsupported array field type for " << field_name;
×
433
                    break;
×
434
            }
435

436
            if (result != ::mav::MessageResult::Success) {
11✔
437
                LogWarn() << "Failed to set array field " << field_name;
×
438
            }
439
        } else {
440
            LogWarn() << "Unsupported JSON field type for " << field_name;
×
441
        }
442
    }
23✔
443

444
    return true;
23✔
445
}
23✔
446

447
MavlinkDirect::Result MavlinkDirectImpl::load_custom_xml(const std::string& xml_content)
6✔
448
{
449
    if (_debugging) {
6✔
450
        LogDebug() << "Loading custom XML definitions...";
×
451
    }
452

453
    // Load the custom XML into the MessageSet with thread safety
454
    // This uses the thread-safe method that protects against concurrent read operations
455
    bool success = _system_impl->load_custom_xml_to_message_set(xml_content);
6✔
456

457
    if (success) {
6✔
458
        if (_debugging) {
6✔
459
            LogDebug() << "Successfully loaded custom XML definitions";
×
460
        }
461
        return MavlinkDirect::Result::Success;
6✔
462
    } else {
463
        LogErr() << "Failed to load custom XML definitions";
×
464
        return MavlinkDirect::Result::Error;
×
465
    }
466
}
467

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