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

mavlink / MAVSDK / 11041590519

25 Sep 2024 09:43PM UTC coverage: 38.062% (-0.02%) from 38.077%
11041590519

Pull #2405

github

web-flow
Merge 6965341a9 into ae4379225
Pull Request #2405: third_party: update libevents

11454 of 30093 relevant lines covered (38.06%)

260.86 hits per line

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

60.82
/src/mavsdk/core/mavsdk_impl.cpp
1
#include "mavsdk_impl.h"
2

3
#include <algorithm>
4
#include <mutex>
5
#include <tcp_server_connection.h>
6

7
#include "connection.h"
8
#include "tcp_client_connection.h"
9
#include "tcp_server_connection.h"
10
#include "udp_connection.h"
11
#include "system.h"
12
#include "system_impl.h"
13
#include "serial_connection.h"
14
#include "version.h"
15
#include "server_component_impl.h"
16
#include "plugin_base.h"
17
#include "mavlink_channels.h"
18
#include "callback_list.tpp"
19

20
namespace mavsdk {
21

22
template class CallbackList<>;
23

24
MavsdkImpl::MavsdkImpl(const Mavsdk::Configuration& configuration) :
71✔
25
    timeout_handler(time),
71✔
26
    call_every_handler(time)
71✔
27
{
28
    LogInfo() << "MAVSDK version: " << mavsdk_version;
71✔
29

30
    if (const char* env_p = std::getenv("MAVSDK_CALLBACK_DEBUGGING")) {
71✔
31
        if (std::string(env_p) == "1") {
×
32
            LogDebug() << "Callback debugging is on.";
×
33
            _callback_debugging = true;
×
34
        }
35
    }
36

37
    if (const char* env_p = std::getenv("MAVSDK_MESSAGE_DEBUGGING")) {
71✔
38
        if (std::string(env_p) == "1") {
×
39
            LogDebug() << "Message debugging is on.";
×
40
            _message_logging_on = true;
×
41
        }
42
    }
43

44
    set_configuration(configuration);
71✔
45

46
    _work_thread = new std::thread(&MavsdkImpl::work_thread, this);
71✔
47

48
    _process_user_callbacks_thread =
142✔
49
        new std::thread(&MavsdkImpl::process_user_callbacks_thread, this);
71✔
50
}
71✔
51

52
MavsdkImpl::~MavsdkImpl()
71✔
53
{
54
    call_every_handler.remove(_heartbeat_send_cookie);
71✔
55

56
    _should_exit = true;
71✔
57

58
    if (_process_user_callbacks_thread != nullptr) {
71✔
59
        _user_callback_queue.stop();
71✔
60
        _process_user_callbacks_thread->join();
71✔
61
        delete _process_user_callbacks_thread;
71✔
62
        _process_user_callbacks_thread = nullptr;
71✔
63
    }
64

65
    if (_work_thread != nullptr) {
71✔
66
        _work_thread->join();
71✔
67
        delete _work_thread;
71✔
68
        _work_thread = nullptr;
71✔
69
    }
70

71
    {
72
        std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
142✔
73
        _systems.clear();
71✔
74
    }
75

76
    {
77
        std::lock_guard<std::mutex> lock(_connections_mutex);
142✔
78
        _connections.clear();
71✔
79
    }
80
}
71✔
81

82
std::string MavsdkImpl::version()
1✔
83
{
84
    static unsigned version_counter = 0;
85

86
    ++version_counter;
1✔
87

88
    switch (version_counter) {
1✔
89
        case 10:
×
90
            return "You were wondering about the name of this library?";
×
91
        case 11:
×
92
            return "Let's look at the history:";
×
93
        case 12:
×
94
            return "DroneLink";
×
95
        case 13:
×
96
            return "DroneCore";
×
97
        case 14:
×
98
            return "DronecodeSDK";
×
99
        case 15:
×
100
            return "MAVSDK";
×
101
        case 16:
×
102
            return "And that's it...";
×
103
        case 17:
×
104
            return "At least for now ¯\\_(ツ)_/¯.";
×
105
        default:
1✔
106
            return mavsdk_version;
1✔
107
    }
108
}
109

110
std::vector<std::shared_ptr<System>> MavsdkImpl::systems() const
70✔
111
{
112
    std::vector<std::shared_ptr<System>> systems_result{};
70✔
113

114
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
140✔
115
    for (auto& system : _systems) {
106✔
116
        // We ignore the 0 entry because it's just a null system.
117
        // It's only created because the older, deprecated API needs a
118
        // reference.
119
        if (system.first == 0) {
36✔
120
            continue;
×
121
        }
122
        systems_result.push_back(system.second);
36✔
123
    }
124

125
    return systems_result;
70✔
126
}
127

128
std::optional<std::shared_ptr<System>> MavsdkImpl::first_autopilot(double timeout_s)
33✔
129
{
130
    {
131
        std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
33✔
132
        for (auto system : _systems) {
33✔
133
            if (system.second->is_connected() && system.second->has_autopilot()) {
×
134
                return system.second;
×
135
            }
136
        }
137
    }
138

139
    if (timeout_s == 0.0) {
33✔
140
        // Don't wait at all.
141
        return {};
×
142
    }
143

144
    auto prom = std::promise<std::shared_ptr<System>>();
66✔
145

146
    std::once_flag flag;
33✔
147
    auto handle = subscribe_on_new_system([this, &prom, &flag]() {
33✔
148
        const auto system = systems().at(0);
99✔
149
        if (system->is_connected() && system->has_autopilot()) {
33✔
150
            std::call_once(flag, [&prom, &system]() { prom.set_value(system); });
66✔
151
        }
152
    });
33✔
153

154
    auto fut = prom.get_future();
66✔
155

156
    if (timeout_s > 0.0) {
33✔
157
        if (fut.wait_for(std::chrono::milliseconds(int64_t(timeout_s * 1e3))) ==
33✔
158
            std::future_status::ready) {
159
            unsubscribe_on_new_system(handle);
33✔
160
            return fut.get();
33✔
161

162
        } else {
163
            unsubscribe_on_new_system(handle);
×
164
            return std::nullopt;
×
165
        }
166
    } else {
167
        fut.wait();
×
168
        unsubscribe_on_new_system(handle);
×
169
        return std::optional(fut.get());
×
170
    }
171
}
172

173
std::shared_ptr<ServerComponent> MavsdkImpl::server_component(unsigned instance)
35✔
174
{
175
    auto component_type = _configuration.get_component_type();
35✔
176
    switch (component_type) {
35✔
177
        case Mavsdk::ComponentType::Autopilot:
35✔
178
        case Mavsdk::ComponentType::GroundStation:
179
        case Mavsdk::ComponentType::CompanionComputer:
180
        case Mavsdk::ComponentType::Camera:
181
        case Mavsdk::ComponentType::Custom:
182
            return server_component_by_type(component_type, instance);
35✔
183
        default:
×
184
            LogErr() << "Unknown component type";
×
185
            return {};
×
186
    }
187
}
188

189
std::shared_ptr<ServerComponent>
190
MavsdkImpl::server_component_by_type(Mavsdk::ComponentType server_component_type, unsigned instance)
35✔
191
{
192
    switch (server_component_type) {
35✔
193
        case Mavsdk::ComponentType::Autopilot:
33✔
194
            if (instance == 0) {
33✔
195
                return server_component_by_id(MAV_COMP_ID_AUTOPILOT1);
33✔
196
            } else {
197
                LogErr() << "Only autopilot instance 0 is valid";
×
198
                return {};
×
199
            }
200

201
        case Mavsdk::ComponentType::GroundStation:
×
202
            if (instance == 0) {
×
203
                return server_component_by_id(MAV_COMP_ID_MISSIONPLANNER);
×
204
            } else {
205
                LogErr() << "Only one ground station supported at this time";
×
206
                return {};
×
207
            }
208

209
        case Mavsdk::ComponentType::CompanionComputer:
1✔
210
            if (instance == 0) {
1✔
211
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER);
1✔
212
            } else if (instance == 1) {
×
213
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER2);
×
214
            } else if (instance == 2) {
×
215
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER3);
×
216
            } else if (instance == 3) {
×
217
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER4);
×
218
            } else {
219
                LogErr() << "Only companion computer 0..3 are supported";
×
220
                return {};
×
221
            }
222

223
        case Mavsdk::ComponentType::Camera:
1✔
224
            if (instance == 0) {
1✔
225
                return server_component_by_id(MAV_COMP_ID_CAMERA);
1✔
226
            } else if (instance == 1) {
×
227
                return server_component_by_id(MAV_COMP_ID_CAMERA2);
×
228
            } else if (instance == 2) {
×
229
                return server_component_by_id(MAV_COMP_ID_CAMERA3);
×
230
            } else if (instance == 3) {
×
231
                return server_component_by_id(MAV_COMP_ID_CAMERA4);
×
232
            } else if (instance == 4) {
×
233
                return server_component_by_id(MAV_COMP_ID_CAMERA5);
×
234
            } else if (instance == 5) {
×
235
                return server_component_by_id(MAV_COMP_ID_CAMERA6);
×
236
            } else {
237
                LogErr() << "Only camera 0..5 are supported";
×
238
                return {};
×
239
            }
240

241
        default:
×
242
            LogErr() << "Unknown server component type";
×
243
            return {};
×
244
    }
245
}
246

247
std::shared_ptr<ServerComponent> MavsdkImpl::server_component_by_id(uint8_t component_id)
140✔
248
{
249
    if (component_id == 0) {
140✔
250
        LogErr() << "Server component with component ID 0 not allowed";
×
251
        return nullptr;
×
252
    }
253

254
    std::lock_guard<std::mutex> lock(_server_components_mutex);
280✔
255

256
    for (auto& it : _server_components) {
141✔
257
        if (it.first == component_id) {
69✔
258
            if (it.second != nullptr) {
68✔
259
                return it.second;
68✔
260
            } else {
261
                it.second = std::make_shared<ServerComponent>(*this, component_id);
×
262
            }
263
        }
264
    }
265

266
    _server_components.emplace_back(std::pair<uint8_t, std::shared_ptr<ServerComponent>>(
216✔
267
        component_id, std::make_shared<ServerComponent>(*this, component_id)));
288✔
268

269
    return _server_components.back().second;
72✔
270
}
271

272
void MavsdkImpl::forward_message(mavlink_message_t& message, Connection* connection)
×
273
{
274
    // Forward_message Function implementing Mavlink routing rules.
275
    // See https://mavlink.io/en/guide/routing.html
276

277
    bool forward_heartbeats_enabled = true;
×
278
    const uint8_t target_system_id = get_target_system_id(message);
×
279
    const uint8_t target_component_id = get_target_component_id(message);
×
280

281
    // If it's a message only for us, we keep it, otherwise, we forward it.
282
    const bool targeted_only_at_us =
283
        (target_system_id == get_own_system_id() && target_component_id == get_own_component_id());
×
284

285
    // We don't forward heartbeats unless it's specifically enabled.
286
    const bool heartbeat_check_ok =
×
287
        (message.msgid != MAVLINK_MSG_ID_HEARTBEAT || forward_heartbeats_enabled);
×
288

289
    if (!targeted_only_at_us && heartbeat_check_ok) {
×
290
        std::lock_guard<std::mutex> lock(_connections_mutex);
×
291

292
        unsigned successful_emissions = 0;
×
293
        for (auto& entry : _connections) {
×
294
            // Check whether the connection is not the one from which we received the message.
295
            // And also check if the connection was set to forward messages.
296
            if (entry.connection.get() == connection ||
×
297
                !entry.connection->should_forward_messages()) {
×
298
                continue;
×
299
            }
300
            if ((*entry.connection).send_message(message)) {
×
301
                successful_emissions++;
×
302
            }
303
        }
304
        if (successful_emissions == 0) {
×
305
            LogErr() << "Message forwarding failed";
×
306
        }
307
    }
308
}
×
309

310
void MavsdkImpl::receive_message(mavlink_message_t& message, Connection* connection)
1,559✔
311
{
312
    if (_message_logging_on) {
1,559✔
313
        LogDebug() << "Processing message " << message.msgid << " from "
×
314
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid);
×
315
    }
316

317
    // This is a low level interface where incoming messages can be tampered
318
    // with or even dropped.
319
    {
320
        std::lock_guard<std::mutex> lock(_intercept_callback_mutex);
1,559✔
321
        if (_intercept_incoming_messages_callback != nullptr) {
1,559✔
322
            bool keep = _intercept_incoming_messages_callback(message);
248✔
323
            if (!keep) {
248✔
324
                LogDebug() << "Dropped incoming message: " << int(message.msgid);
44✔
325
                return;
44✔
326
            }
327
        }
328
    }
329

330
    /** @note: Forward message if option is enabled and multiple interfaces are connected.
331
     *  Performs message forwarding checks for every messages if message forwarding
332
     *  is enabled on at least one connection, and in case of a single forwarding connection,
333
     *  we check that it is not the one which received the current message.
334
     *
335
     * Conditions:
336
     * 1. At least 2 connections.
337
     * 2. At least 1 forwarding connection.
338
     * 3. At least 2 forwarding connections or current connection is not forwarding.
339
     */
340
    if (_connections.size() > 1 && mavsdk::Connection::forwarding_connections_count() > 0 &&
1,514✔
341
        (mavsdk::Connection::forwarding_connections_count() > 1 ||
×
342
         !connection->should_forward_messages())) {
×
343
        if (_message_logging_on) {
×
344
            LogDebug() << "Forwarding message " << message.msgid << " from "
×
345
                       << static_cast<int>(message.sysid) << "/"
×
346
                       << static_cast<int>(message.compid);
×
347
        }
348
        forward_message(message, connection);
×
349
    }
350

351
    // Don't ever create a system with sysid 0.
352
    if (message.sysid == 0) {
1,515✔
353
        if (_message_logging_on) {
×
354
            LogDebug() << "Ignoring message with sysid == 0";
×
355
        }
356
        return;
×
357
    }
358

359
    // Filter out messages by QGroundControl, however, only do that if MAVSDK
360
    // is also implementing a ground station and not if it is used in another
361
    // configuration, e.g. on a companion.
362
    //
363
    // This is a workaround because PX4 started forwarding messages between
364
    // mavlink instances which leads to existing implementations (including
365
    // examples and integration tests) to connect to QGroundControl by accident
366
    // instead of PX4 because the check `has_autopilot()` is not used.
367
    if (_configuration.get_component_type() == Mavsdk::ComponentType::GroundStation &&
1,515✔
368
        message.sysid == 255 && message.compid == MAV_COMP_ID_MISSIONPLANNER) {
1,514✔
369
        if (_message_logging_on) {
×
370
            LogDebug() << "Ignoring messages from QGC as we are also a ground station";
×
371
        }
372
        return;
×
373
    }
374

375
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
1,514✔
376

377
    bool found_system = false;
1,515✔
378
    for (auto& system : _systems) {
1,515✔
379
        if (system.first == message.sysid) {
1,445✔
380
            system.second->system_impl()->add_new_component(message.compid);
1,445✔
381
            found_system = true;
1,444✔
382
            break;
1,444✔
383
        }
384
    }
385

386
    if (!found_system) {
1,514✔
387
        make_system_with_component(message.sysid, message.compid);
70✔
388
    }
389

390
    if (_should_exit) {
1,514✔
391
        // Don't try to call at() if systems have already been destroyed
392
        // in destructor.
393
        return;
1✔
394
    }
395

396
    mavlink_message_handler.process_message(message);
1,513✔
397

398
    for (auto& system : _systems) {
1,514✔
399
        if (system.first == message.sysid) {
1,514✔
400
            system.second->system_impl()->process_mavlink_message(message);
1,514✔
401
            break;
1,514✔
402
        }
403
    }
404
}
405

406
bool MavsdkImpl::send_message(mavlink_message_t& message)
1,671✔
407
{
408
    if (_message_logging_on) {
1,671✔
409
        LogDebug() << "Sending message " << message.msgid << " from "
×
410
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid)
×
411
                   << " to " << static_cast<int>(get_target_system_id(message)) << "/"
×
412
                   << static_cast<int>(get_target_component_id(message));
×
413
    }
414

415
    // This is a low level interface where outgoing messages can be tampered
416
    // with or even dropped.
417
    if (_intercept_outgoing_messages_callback != nullptr) {
1,671✔
418
        const bool keep = _intercept_outgoing_messages_callback(message);
220✔
419
        if (!keep) {
220✔
420
            // We fake that everything was sent as instructed because
421
            // a potential loss would happen later, and we would not be informed
422
            // about it.
423
            LogDebug() << "Dropped outgoing message: " << int(message.msgid);
77✔
424
            return true;
77✔
425
        }
426
    }
427

428
    std::lock_guard<std::mutex> lock(_connections_mutex);
3,187✔
429

430
    if (_connections.empty()) {
1,594✔
431
        // We obviously can't send any messages without a connection added, so
432
        // we silently ignore this.
433
        return true;
35✔
434
    }
435

436
    uint8_t successful_emissions = 0;
1,559✔
437
    for (auto& _connection : _connections) {
3,118✔
438
        const uint8_t target_system_id = get_target_system_id(message);
1,559✔
439

440
        if (target_system_id != 0 && !(*_connection.connection).has_system_id(target_system_id)) {
1,559✔
441
            continue;
×
442
        }
443

444
        if ((*_connection.connection).send_message(message)) {
1,559✔
445
            successful_emissions++;
1,559✔
446
        }
447
    }
448

449
    if (successful_emissions == 0) {
1,559✔
450
        LogErr() << "Sending message failed";
×
451
        return false;
×
452
    }
453

454
    return true;
1,559✔
455
}
456

457
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_any_connection(
70✔
458
    const std::string& connection_url, ForwardingOption forwarding_option)
459
{
460
    CliArg cli_arg;
140✔
461
    if (!cli_arg.parse(connection_url)) {
70✔
462
        return {ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle{}};
×
463
    }
464

465
    return std::visit(
466
        overloaded{
70✔
467
            [](std::monostate) {
×
468
                // Should not happen anyway.
469
                return std::pair<ConnectionResult, Mavsdk::ConnectionHandle>{
×
470
                    ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle()};
×
471
            },
472
            [this, forwarding_option](const CliArg::Udp& udp) {
68✔
473
                return add_udp_connection(udp, forwarding_option);
68✔
474
            },
475
            [this, forwarding_option](const CliArg::Tcp& tcp) {
2✔
476
                return add_tcp_connection(tcp, forwarding_option);
2✔
477
            },
478
            [this, forwarding_option](const CliArg::Serial& serial) {
×
479
                return add_serial_connection(
480
                    serial.path, serial.baudrate, serial.flow_control_enabled, forwarding_option);
×
481
            }},
482
        cli_arg.protocol);
70✔
483
}
484

485
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
486
MavsdkImpl::add_udp_connection(const CliArg::Udp& udp, ForwardingOption forwarding_option)
68✔
487
{
488
    auto new_conn = std::make_shared<UdpConnection>(
68✔
489
        [this](mavlink_message_t& message, Connection* connection) {
1,548✔
490
            receive_message(message, connection);
1,548✔
491
        },
1,549✔
492
        udp.mode == CliArg::Udp::Mode::In ? udp.host : "0.0.0.0",
170✔
493
        udp.mode == CliArg::Udp::Mode::In ? udp.port : 0,
136✔
494
        forwarding_option);
272✔
495

496
    if (!new_conn) {
68✔
497
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
498
    }
499

500
    ConnectionResult ret = new_conn->start();
68✔
501

502
    if (ret != ConnectionResult::Success) {
68✔
503
        return {ret, Mavsdk::ConnectionHandle{}};
×
504
    }
505

506
    auto handle = add_connection(new_conn);
68✔
507

508
    if (udp.mode == CliArg::Udp::Mode::Out) {
68✔
509
        new_conn->add_remote(udp.host, udp.port);
34✔
510
        std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
68✔
511

512
        // With a UDP remote, we need to initiate the connection by sending heartbeats.
513
        auto new_configuration = get_configuration();
34✔
514
        new_configuration.set_always_send_heartbeats(true);
34✔
515
        set_configuration(new_configuration);
34✔
516
    }
517
    return {ConnectionResult::Success, handle};
68✔
518
}
519

520
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
521
MavsdkImpl::add_tcp_connection(const CliArg::Tcp& tcp, ForwardingOption forwarding_option)
2✔
522
{
523
    if (tcp.mode == CliArg::Tcp::Mode::Out) {
2✔
524
        auto new_conn = std::make_shared<TcpClientConnection>(
1✔
525
            [this](mavlink_message_t& message, Connection* connection) {
2✔
526
                receive_message(message, connection);
2✔
527
            },
2✔
528
            tcp.host,
1✔
529
            tcp.port,
1✔
530
            forwarding_option);
2✔
531
        if (!new_conn) {
1✔
532
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
533
        }
534
        ConnectionResult ret = new_conn->start();
1✔
535
        if (ret == ConnectionResult::Success) {
1✔
536
            return {ret, add_connection(new_conn)};
1✔
537
        } else {
538
            return {ret, Mavsdk::ConnectionHandle{}};
×
539
        }
540
    } else {
541
        auto new_conn = std::make_shared<TcpServerConnection>(
1✔
542
            [this](mavlink_message_t& message, Connection* connection) {
8✔
543
                receive_message(message, connection);
8✔
544
            },
8✔
545
            tcp.host,
1✔
546
            tcp.port,
1✔
547
            forwarding_option);
2✔
548
        if (!new_conn) {
1✔
549
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
550
        }
551
        ConnectionResult ret = new_conn->start();
1✔
552
        if (ret == ConnectionResult::Success) {
1✔
553
            return {ret, add_connection(new_conn)};
1✔
554
        } else {
555
            return {ret, Mavsdk::ConnectionHandle{}};
×
556
        }
557
    }
558
}
559

560
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_serial_connection(
×
561
    const std::string& dev_path,
562
    int baudrate,
563
    bool flow_control,
564
    ForwardingOption forwarding_option)
565
{
566
    auto new_conn = std::make_shared<SerialConnection>(
×
567
        [this](mavlink_message_t& message, Connection* connection) {
×
568
            receive_message(message, connection);
×
569
        },
×
570
        dev_path,
571
        baudrate,
572
        flow_control,
573
        forwarding_option);
×
574
    if (!new_conn) {
×
575
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
576
    }
577
    ConnectionResult ret = new_conn->start();
×
578
    if (ret == ConnectionResult::Success) {
×
579
        auto handle = add_connection(new_conn);
×
580

581
        auto new_configuration = get_configuration();
×
582

583
        // PX4 starting with v1.13 does not send heartbeats by default, so we need
584
        // to initiate the MAVLink connection by sending heartbeats.
585
        // Therefore, we override the default here and enable sending heartbeats.
586
        new_configuration.set_always_send_heartbeats(true);
×
587
        set_configuration(new_configuration);
×
588

589
        return {ret, handle};
×
590

591
    } else {
592
        return {ret, Mavsdk::ConnectionHandle{}};
×
593
    }
594
}
595

596
Mavsdk::ConnectionHandle
597
MavsdkImpl::add_connection(const std::shared_ptr<Connection>& new_connection)
70✔
598
{
599
    std::lock_guard<std::mutex> lock(_connections_mutex);
70✔
600
    auto handle = _connections_handle_factory.create();
70✔
601
    _connections.emplace_back(ConnectionEntry{new_connection, handle});
70✔
602

603
    return handle;
70✔
604
}
605

606
void MavsdkImpl::remove_connection(Mavsdk::ConnectionHandle handle)
×
607
{
608
    std::lock_guard<std::mutex> lock(_connections_mutex);
×
609

610
    _connections.erase(std::remove_if(_connections.begin(), _connections.end(), [&](auto&& entry) {
×
611
        return (entry.handle == handle);
×
612
    }));
×
613
}
×
614

615
Mavsdk::Configuration MavsdkImpl::get_configuration() const
34✔
616
{
617
    return _configuration;
34✔
618
}
619

620
void MavsdkImpl::set_configuration(Mavsdk::Configuration new_configuration)
105✔
621
{
622
    // We just point the default to the newly created component. This means
623
    // that the previous default component will be deleted if it is not
624
    // used/referenced anywhere.
625
    _default_server_component = server_component_by_id(new_configuration.get_component_id());
105✔
626

627
    if (new_configuration.get_always_send_heartbeats() &&
174✔
628
        !_configuration.get_always_send_heartbeats()) {
69✔
629
        start_sending_heartbeats();
35✔
630
    } else if (
70✔
631
        !new_configuration.get_always_send_heartbeats() &&
106✔
632
        _configuration.get_always_send_heartbeats() && !is_any_system_connected()) {
106✔
633
        stop_sending_heartbeats();
×
634
    }
635

636
    _configuration = new_configuration;
105✔
637
}
105✔
638

639
uint8_t MavsdkImpl::get_own_system_id() const
4,263✔
640
{
641
    return _configuration.get_system_id();
4,263✔
642
}
643

644
uint8_t MavsdkImpl::get_own_component_id() const
1,209✔
645
{
646
    return _configuration.get_component_id();
1,209✔
647
}
648

649
uint8_t MavsdkImpl::channel() const
×
650
{
651
    // TODO
652
    return 0;
×
653
}
654

655
Autopilot MavsdkImpl::autopilot() const
×
656
{
657
    // TODO
658
    return Autopilot::Px4;
×
659
}
660

661
// FIXME: this should be per component
662
uint8_t MavsdkImpl::get_mav_type() const
162✔
663
{
664
    switch (_configuration.get_component_type()) {
162✔
665
        case Mavsdk::ComponentType::Autopilot:
113✔
666
            return MAV_TYPE_GENERIC;
113✔
667

668
        case Mavsdk::ComponentType::GroundStation:
43✔
669
            return MAV_TYPE_GCS;
43✔
670

671
        case Mavsdk::ComponentType::CompanionComputer:
4✔
672
            return MAV_TYPE_ONBOARD_CONTROLLER;
4✔
673

674
        case Mavsdk::ComponentType::Camera:
2✔
675
            return MAV_TYPE_CAMERA;
2✔
676

677
        case Mavsdk::ComponentType::Custom:
×
678
            return MAV_TYPE_GENERIC;
×
679

680
        default:
×
681
            LogErr() << "Unknown configuration";
×
682
            return 0;
×
683
    }
684
}
685

686
void MavsdkImpl::make_system_with_component(uint8_t system_id, uint8_t comp_id)
70✔
687
{
688
    // Needs _systems_lock
689

690
    if (_should_exit) {
70✔
691
        // When the system got destroyed in the destructor, we have to give up.
692
        return;
1✔
693
    }
694

695
    if (static_cast<int>(system_id) == 0 && static_cast<int>(comp_id) == 0) {
69✔
696
        LogDebug() << "Initializing connection to remote system...";
×
697
    } else {
698
        LogDebug() << "New system ID: " << static_cast<int>(system_id)
207✔
699
                   << " Comp ID: " << static_cast<int>(comp_id);
207✔
700
    }
701

702
    // Make a system with its first component
703
    auto new_system = std::make_shared<System>(*this);
138✔
704
    new_system->init(system_id, comp_id);
69✔
705

706
    _systems.emplace_back(system_id, new_system);
69✔
707
}
708

709
void MavsdkImpl::notify_on_discover()
69✔
710
{
711
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
138✔
712
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
104✔
713
}
69✔
714

715
void MavsdkImpl::notify_on_timeout()
×
716
{
717
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
×
718
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
719
}
×
720

721
Mavsdk::NewSystemHandle
722
MavsdkImpl::subscribe_on_new_system(const Mavsdk::NewSystemCallback& callback)
35✔
723
{
724
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
35✔
725

726
    const auto handle = _new_system_callbacks.subscribe(callback);
35✔
727

728
    if (is_any_system_connected()) {
35✔
729
        _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
730
    }
731

732
    return handle;
35✔
733
}
734

735
void MavsdkImpl::unsubscribe_on_new_system(Mavsdk::NewSystemHandle handle)
34✔
736
{
737
    _new_system_callbacks.unsubscribe(handle);
34✔
738
}
34✔
739

740
bool MavsdkImpl::is_any_system_connected() const
35✔
741
{
742
    std::vector<std::shared_ptr<System>> connected_systems = systems();
70✔
743
    return std::any_of(connected_systems.cbegin(), connected_systems.cend(), [](auto& system) {
35✔
744
        return system->is_connected();
1✔
745
    });
35✔
746
}
747

748
void MavsdkImpl::work_thread()
11,849✔
749
{
750
    while (!_should_exit) {
11,849✔
751
        timeout_handler.run_once();
11,668✔
752
        call_every_handler.run_once();
11,747✔
753

754
        {
755
            std::lock_guard<std::mutex> lock(_server_components_mutex);
23,450✔
756
            for (auto& it : _server_components) {
23,533✔
757
                if (it.second != nullptr) {
11,771✔
758
                    it.second->_impl->do_work();
11,746✔
759
                }
760
            }
761
        }
762

763
        std::this_thread::sleep_for(std::chrono::milliseconds(10));
11,739✔
764
    }
765
}
70✔
766

767
void MavsdkImpl::call_user_callback_located(
809✔
768
    const std::string& filename, const int linenumber, const std::function<void()>& func)
769
{
770
    auto callback_size = _user_callback_queue.size();
809✔
771
    if (callback_size == 10) {
809✔
772
        LogWarn()
×
773
            << "User callback queue too slow.\n"
×
774
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
775

776
    } else if (callback_size == 99) {
809✔
777
        LogErr()
×
778
            << "User callback queue overflown\n"
×
779
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
780

781
    } else if (callback_size == 100) {
809✔
782
        return;
×
783
    }
784

785
    // We only need to keep track of filename and linenumber if we're actually debugging this.
786
    UserCallback user_callback =
809✔
787
        _callback_debugging ? UserCallback{func, filename, linenumber} : UserCallback{func};
2,427✔
788

789
    _user_callback_queue.enqueue(user_callback);
809✔
790
}
791

792
void MavsdkImpl::process_user_callbacks_thread()
951✔
793
{
794
    while (!_should_exit) {
951✔
795
        auto callback = _user_callback_queue.dequeue();
880✔
796
        if (!callback) {
880✔
797
            continue;
71✔
798
        }
799

800
        const double timeout_s = 1.0;
809✔
801
        auto cookie = timeout_handler.add(
809✔
802
            [&]() {
×
803
                if (_callback_debugging) {
×
804
                    LogWarn() << "Callback called from " << callback.value().filename << ":"
×
805
                              << callback.value().linenumber << " took more than " << timeout_s
×
806
                              << " second to run.";
×
807
                    fflush(stdout);
×
808
                    fflush(stderr);
×
809
                    abort();
×
810
                } else {
811
                    LogWarn()
×
812
                        << "Callback took more than " << timeout_s << " second to run.\n"
×
813
                        << "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
814
                }
815
            },
×
816
            timeout_s);
809✔
817
        callback.value().func();
809✔
818
        timeout_handler.remove(cookie);
809✔
819
    }
820
}
71✔
821

822
void MavsdkImpl::start_sending_heartbeats()
104✔
823
{
824
    // Before sending out first heartbeats we need to make sure we have a
825
    // default server component.
826
    default_server_component_impl();
104✔
827

828
    call_every_handler.remove(_heartbeat_send_cookie);
104✔
829
    _heartbeat_send_cookie =
208✔
830
        call_every_handler.add([this]() { send_heartbeat(); }, HEARTBEAT_SEND_INTERVAL_S);
265✔
831
}
104✔
832

833
void MavsdkImpl::stop_sending_heartbeats()
×
834
{
835
    if (!_configuration.get_always_send_heartbeats()) {
×
836
        call_every_handler.remove(_heartbeat_send_cookie);
×
837
    }
838
}
×
839

840
ServerComponentImpl& MavsdkImpl::default_server_component_impl()
756✔
841
{
842
    if (_default_server_component == nullptr) {
756✔
843
        _default_server_component = server_component_by_id(_configuration.get_component_id());
×
844
    }
845
    return *_default_server_component->_impl;
756✔
846
}
847

848
void MavsdkImpl::send_heartbeat()
161✔
849
{
850
    std::lock_guard<std::mutex> lock(_server_components_mutex);
322✔
851

852
    for (auto& it : _server_components) {
322✔
853
        if (it.second != nullptr) {
162✔
854
            it.second->_impl->send_heartbeat();
162✔
855
        }
856
    }
857
}
161✔
858

859
void MavsdkImpl::intercept_incoming_messages_async(std::function<bool(mavlink_message_t&)> callback)
22✔
860
{
861
    std::lock_guard<std::mutex> lock(_intercept_callback_mutex);
44✔
862
    _intercept_incoming_messages_callback = callback;
22✔
863
}
22✔
864

865
void MavsdkImpl::intercept_outgoing_messages_async(std::function<bool(mavlink_message_t&)> callback)
14✔
866
{
867
    std::lock_guard<std::mutex> lock(_intercept_callback_mutex);
28✔
868
    _intercept_outgoing_messages_callback = callback;
14✔
869
}
14✔
870

871
uint8_t MavsdkImpl::get_target_system_id(const mavlink_message_t& message)
1,559✔
872
{
873
    // Checks whether connection knows target system ID by extracting target system if set.
874
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
1,559✔
875

876
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM)) {
1,559✔
877
        return 0;
224✔
878
    }
879

880
    // Don't look at the target system offset if it is outside the payload length.
881
    // This can happen if the fields are trimmed.
882
    if (meta->target_system_ofs >= message.len) {
1,335✔
883
        return 0;
×
884
    }
885

886
    return (_MAV_PAYLOAD(&message))[meta->target_system_ofs];
1,335✔
887
}
888

889
uint8_t MavsdkImpl::get_target_component_id(const mavlink_message_t& message)
×
890
{
891
    // Checks whether connection knows target system ID by extracting target system if set.
892
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
×
893

894
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT)) {
×
895
        return 0;
×
896
    }
897

898
    // Don't look at the target component offset if it is outside the payload length.
899
    // This can happen if the fields are trimmed.
900
    if (meta->target_component_ofs >= message.len) {
×
901
        return 0;
×
902
    }
903

904
    return (_MAV_PAYLOAD(&message))[meta->target_component_ofs];
×
905
}
906

907
Sender& MavsdkImpl::sender()
×
908
{
909
    return default_server_component_impl().sender();
×
910
}
911

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