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

mavlink / MAVSDK / 16665088909

01 Aug 2025 02:55AM UTC coverage: 46.166% (-0.1%) from 46.31%
16665088909

push

github

web-flow
Merge pull request #2630 from mavlink/pr-segfault-fixes

Stack-use-after-free and thread-safety fixes, CI additions, clang-format-19

241 of 320 new or added lines in 32 files covered. (75.31%)

39 existing lines in 10 files now uncovered.

16101 of 34876 relevant lines covered (46.17%)

361.1 hits per line

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

56.93
/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 "log.h"
7
#include "connection.h"
8
#include "callback_list.tpp"
9

10
namespace mavsdk {
11

12
template class CallbackList<MavlinkDirect::MavlinkMessage>;
13

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

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

35
MavlinkDirectImpl::~MavlinkDirectImpl()
24✔
36
{
37
    _system_impl->unregister_plugin(this);
12✔
38
}
24✔
39

40
void MavlinkDirectImpl::init()
12✔
41
{
42
    // No need to initialize MessageSet here - LibmavReceiver handles that
43
    // No need to register for mavlink messages anymore - we'll use libmav subscription system
44
}
12✔
45

46
void MavlinkDirectImpl::deinit() {}
12✔
47

48
void MavlinkDirectImpl::enable() {}
12✔
49

50
void MavlinkDirectImpl::disable() {}
12✔
51

52
MavlinkDirect::Result MavlinkDirectImpl::send_message(MavlinkDirect::MavlinkMessage message)
8✔
53
{
54
    // Get access to the MessageSet through the system
55
    auto& message_set = _system_impl->get_message_set();
8✔
56

57
    // Create libmav message from the message name
58
    auto libmav_message_opt = message_set.create(message.message_name);
8✔
59
    if (!libmav_message_opt) {
8✔
60
        LogErr() << "Failed to create message: " << message.message_name;
×
61
        return MavlinkDirect::Result::InvalidMessage; // Message type not found
×
62
    }
63

64
    if (_debugging) {
8✔
65
        LogDebug() << "Created message " << message.message_name
×
66
                   << " with ID: " << libmav_message_opt.value().id();
×
67
    }
68

69
    auto libmav_message = libmav_message_opt.value();
8✔
70

71
    // Convert JSON fields to libmav message fields
72
    if (!json_to_libmav_message(message.fields_json, libmav_message)) {
8✔
73
        LogErr() << "Failed to convert JSON fields to libmav message for " << message.message_name;
×
74
        return MavlinkDirect::Result::InvalidField; // JSON conversion failed
×
75
    }
76

77
    if (_debugging) {
8✔
78
        LogDebug() << "Successfully populated fields for " << message.message_name;
×
79
    }
80

81
    // Set target system/component if specified
82
    if (message.target_system != 0) {
8✔
83
        // For messages that have target_system field, set it
84
        libmav_message.set("target_system", static_cast<uint8_t>(message.target_system));
×
85
    }
86
    if (message.target_component != 0) {
8✔
87
        // For messages that have target_component field, set it
88
        libmav_message.set("target_component", static_cast<uint8_t>(message.target_component));
×
89
    }
90

91
    if (_debugging) {
8✔
92
        LogDebug() << "Sending " << message.message_name << " via unified libmav API";
×
93
    }
94

95
    _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
8✔
96
        mavlink_message_t mavlink_message;
97

98
        // Use clean libmav helper methods to get payload data
99
        auto payload_view = libmav_message.getPayloadView();
8✔
100
        const uint8_t payload_length = libmav_message.getPayloadLength();
8✔
101

102
        // Set up the mavlink_message_t structure
103
        mavlink_message.msgid = libmav_message.id();
8✔
104
        mavlink_message.len = payload_length;
8✔
105
        memcpy(mavlink_message.payload64, payload_view.first, payload_length);
8✔
106

107
        mavlink_finalize_message_chan(
16✔
108
            &mavlink_message,
109
            mavlink_address.system_id,
8✔
110
            mavlink_address.component_id,
8✔
111
            channel,
112
            payload_length,
113
            libmav_message.type().maxPayloadSize(),
8✔
114
            libmav_message.type().crcExtra());
8✔
115

116
        return mavlink_message;
8✔
117
    });
118

119
    if (_debugging) {
8✔
120
        LogDebug() << "Successfully sent " << message.message_name << " as raw data";
×
121
    }
122

123
    return MavlinkDirect::Result::Success;
8✔
124
}
125

126
MavlinkDirect::MessageHandle MavlinkDirectImpl::subscribe_message(
6✔
127
    std::string message_name, const MavlinkDirect::MessageCallback& callback)
128
{
129
    // Subscribe using CallbackList pattern - this handles thread safety internally
130
    auto handle = _message_subscriptions.subscribe(callback);
6✔
131

132
    // Store message name for this handle (CallbackList protects this too)
133
    _handle_to_message_name[handle] = message_name;
6✔
134

135
    // Register with SystemImpl - no lock-order-inversion because CallbackList handles
136
    // synchronization
137
    _system_impl->register_libmav_message_handler(
6✔
138
        message_name,
139
        [this](const LibmavMessage& libmav_msg) {
16✔
140
            // Convert LibmavMessage to MavlinkDirect::MavlinkMessage
141
            MavlinkDirect::MavlinkMessage message;
8✔
142
            message.message_name = libmav_msg.message_name;
8✔
143
            message.system_id = libmav_msg.system_id;
8✔
144
            message.component_id = libmav_msg.component_id;
8✔
145
            message.target_system = libmav_msg.target_system;
8✔
146
            message.target_component = libmav_msg.target_component;
8✔
147
            message.fields_json = libmav_msg.fields_json;
8✔
148

149
            // Use CallbackList::queue to safely call all subscribed callbacks
150
            _message_subscriptions.queue(
8✔
151
                message, [this](const auto& func) { _system_impl->call_user_callback(func); });
8✔
152
        },
8✔
153
        &handle // Use handle address as cookie for specific unregistration
154
    );
155

156
    return handle;
6✔
157
}
158

159
void MavlinkDirectImpl::unsubscribe_message(MavlinkDirect::MessageHandle handle)
6✔
160
{
161
    // Get the message name for unregistration
162
    auto name_it = _handle_to_message_name.find(handle);
6✔
163
    if (name_it == _handle_to_message_name.end()) {
6✔
NEW
164
        return; // Handle not found, nothing to unsubscribe
×
165
    }
166
    std::string message_name = name_it->second;
6✔
167

168
    // Unregister from SystemImpl - no lock-order-inversion with CallbackList pattern
169
    _system_impl->unregister_libmav_message_handler(message_name, &handle);
6✔
170

171
    // Remove from CallbackList and message name map - CallbackList handles thread safety
172
    _message_subscriptions.unsubscribe(handle);
6✔
173
    _handle_to_message_name.erase(handle);
6✔
174
}
6✔
175

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

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

187
    return std::nullopt;
×
188
}
189

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

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

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

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

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

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

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

233
        // Convert JSON values to appropriate types and set in message
234
        if (field_value.isInt()) {
64✔
235
            auto result = msg.set(field_name, static_cast<int32_t>(field_value.asInt()));
54✔
236
            if (result != ::mav::MessageResult::Success) {
54✔
237
                // Try as other integer types
238
                if (msg.set(field_name, static_cast<uint32_t>(field_value.asUInt())) !=
×
239
                        ::mav::MessageResult::Success &&
×
240
                    msg.set(field_name, static_cast<int16_t>(field_value.asInt())) !=
×
241
                        ::mav::MessageResult::Success &&
×
242
                    msg.set(field_name, static_cast<uint16_t>(field_value.asUInt())) !=
×
243
                        ::mav::MessageResult::Success &&
×
244
                    msg.set(field_name, static_cast<int8_t>(field_value.asInt())) !=
×
245
                        ::mav::MessageResult::Success &&
×
246
                    msg.set(field_name, static_cast<uint8_t>(field_value.asUInt())) !=
×
247
                        ::mav::MessageResult::Success) {
248
                    LogWarn() << "Failed to set integer field " << field_name << " = "
×
249
                              << field_value.asInt();
×
250
                }
251
            }
252
        } else if (field_value.isUInt()) {
10✔
253
            auto result = msg.set(field_name, static_cast<uint32_t>(field_value.asUInt()));
×
254
            if (result != ::mav::MessageResult::Success) {
×
255
                // Try as other unsigned integer types
256
                if (msg.set(field_name, static_cast<uint64_t>(field_value.asUInt64())) !=
×
257
                        ::mav::MessageResult::Success &&
×
258
                    msg.set(field_name, static_cast<uint16_t>(field_value.asUInt())) !=
×
259
                        ::mav::MessageResult::Success &&
×
260
                    msg.set(field_name, static_cast<uint8_t>(field_value.asUInt())) !=
×
261
                        ::mav::MessageResult::Success) {
262
                    LogWarn() << "Failed to set unsigned integer field " << field_name << " = "
×
263
                              << field_value.asUInt();
×
264
                }
265
            }
266
        } else if (field_value.isDouble()) {
10✔
267
            auto result = msg.set(field_name, static_cast<float>(field_value.asFloat()));
×
268
            if (result != ::mav::MessageResult::Success) {
×
269
                // Try as double
270
                if (msg.set(field_name, field_value.asDouble()) != ::mav::MessageResult::Success) {
×
271
                    LogWarn() << "Failed to set float/double field " << field_name << " = "
×
272
                              << field_value.asDouble();
×
273
                }
274
            }
275
        } else if (field_value.isString()) {
10✔
276
            auto result = msg.setString(field_name, field_value.asString());
×
277
            if (result != ::mav::MessageResult::Success) {
×
278
                LogWarn() << "Failed to set string field " << field_name << " = "
×
279
                          << field_value.asString();
×
280
            }
281
        } else if (field_value.isArray()) {
10✔
282
            // Handle array fields
283
            auto array_size = field_value.size();
10✔
284

285
            // Try different vector types based on typical MAVLink array field types
286
            std::vector<uint8_t> uint8_vec;
10✔
287
            std::vector<uint16_t> uint16_vec;
10✔
288
            std::vector<uint32_t> uint32_vec;
10✔
289
            std::vector<int8_t> int8_vec;
10✔
290
            std::vector<int16_t> int16_vec;
10✔
291
            std::vector<int32_t> int32_vec;
10✔
292
            std::vector<float> float_vec;
10✔
293
            std::vector<double> double_vec;
10✔
294

295
            // Convert JSON array to vectors of different types
296
            uint8_vec.reserve(array_size);
10✔
297
            uint16_vec.reserve(array_size);
10✔
298
            uint32_vec.reserve(array_size);
10✔
299
            int8_vec.reserve(array_size);
10✔
300
            int16_vec.reserve(array_size);
10✔
301
            int32_vec.reserve(array_size);
10✔
302
            float_vec.reserve(array_size);
10✔
303
            double_vec.reserve(array_size);
10✔
304

305
            for (Json::ArrayIndex i = 0; i < array_size; ++i) {
210✔
306
                const auto& elem = field_value[i];
200✔
307
                if (elem.isNumeric()) {
200✔
308
                    uint8_vec.push_back(static_cast<uint8_t>(elem.asUInt()));
200✔
309
                    uint16_vec.push_back(static_cast<uint16_t>(elem.asUInt()));
200✔
310
                    uint32_vec.push_back(static_cast<uint32_t>(elem.asUInt()));
200✔
311
                    int8_vec.push_back(static_cast<int8_t>(elem.asInt()));
200✔
312
                    int16_vec.push_back(static_cast<int16_t>(elem.asInt()));
200✔
313
                    int32_vec.push_back(static_cast<int32_t>(elem.asInt()));
200✔
314
                    float_vec.push_back(static_cast<float>(elem.asFloat()));
200✔
315
                    double_vec.push_back(elem.asDouble());
200✔
316
                } else {
317
                    // Default to 0 for non-numeric values
318
                    uint8_vec.push_back(0);
×
319
                    uint16_vec.push_back(0);
×
320
                    uint32_vec.push_back(0);
×
321
                    int8_vec.push_back(0);
×
322
                    int16_vec.push_back(0);
×
323
                    int32_vec.push_back(0);
×
324
                    float_vec.push_back(0.0f);
×
325
                    double_vec.push_back(0.0);
×
326
                }
327
            }
328

329
            // Try to set the array field with different vector types
330
            if (msg.set(field_name, uint8_vec) == ::mav::MessageResult::Success ||
10✔
331
                msg.set(field_name, uint16_vec) == ::mav::MessageResult::Success ||
×
332
                msg.set(field_name, uint32_vec) == ::mav::MessageResult::Success ||
×
333
                msg.set(field_name, int8_vec) == ::mav::MessageResult::Success ||
×
334
                msg.set(field_name, int16_vec) == ::mav::MessageResult::Success ||
×
335
                msg.set(field_name, int32_vec) == ::mav::MessageResult::Success ||
×
336
                msg.set(field_name, float_vec) == ::mav::MessageResult::Success ||
10✔
337
                msg.set(field_name, double_vec) == ::mav::MessageResult::Success) {
×
338
                // Successfully set the array field
339
            } else {
340
                LogWarn() << "Failed to set array field " << field_name;
×
341
            }
342
        } else {
10✔
343
            LogWarn() << "Unsupported JSON field type for " << field_name;
×
344
        }
345
    }
8✔
346

347
    return true;
8✔
348
}
8✔
349

350
MavlinkDirect::Result MavlinkDirectImpl::load_custom_xml(const std::string& xml_content)
2✔
351
{
352
    if (_debugging) {
2✔
UNCOV
353
        LogDebug() << "Loading custom XML definitions...";
×
354
    }
355

356
    // Load the custom XML into the MessageSet with thread safety
357
    // This uses the thread-safe method that protects against concurrent read operations
358
    bool success = _system_impl->load_custom_xml_to_message_set(xml_content);
2✔
359

360
    if (success) {
2✔
361
        if (_debugging) {
2✔
362
            LogDebug() << "Successfully loaded custom XML definitions";
×
363
        }
364
        return MavlinkDirect::Result::Success;
2✔
365
    } else {
366
        LogErr() << "Failed to load custom XML definitions";
×
367
        return MavlinkDirect::Result::Error;
×
368
    }
369
}
370

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