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

mavlink / MAVSDK / 11588874603

30 Oct 2024 07:37AM UTC coverage: 38.621% (+0.7%) from 37.918%
11588874603

Pull #2394

github

web-flow
Merge 991248b3a into cebb708a4
Pull Request #2394: Consolidate CI

12034 of 31159 relevant lines covered (38.62%)

243.25 hits per line

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

60.79
/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)
142✔
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
    if (const char* env_p = std::getenv("MAVSDK_SYSTEM_DEBUGGING")) {
71✔
45
        if (std::string(env_p) == "1") {
×
46
            LogDebug() << "System debugging is on.";
×
47
            _system_debugging = true;
×
48
        }
49
    }
50

51
    set_configuration(configuration);
71✔
52

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

55
    _process_user_callbacks_thread =
142✔
56
        new std::thread(&MavsdkImpl::process_user_callbacks_thread, this);
71✔
57
}
71✔
58

59
MavsdkImpl::~MavsdkImpl()
71✔
60
{
61
    call_every_handler.remove(_heartbeat_send_cookie);
71✔
62

63
    _should_exit = true;
71✔
64

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

72
    if (_work_thread != nullptr) {
71✔
73
        _work_thread->join();
71✔
74
        delete _work_thread;
71✔
75
        _work_thread = nullptr;
71✔
76
    }
77

78
    {
79
        std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
71✔
80
        _systems.clear();
71✔
81
    }
71✔
82

83
    {
84
        std::lock_guard<std::mutex> lock(_connections_mutex);
71✔
85
        _connections.clear();
71✔
86
    }
71✔
87
}
71✔
88

89
std::string MavsdkImpl::version()
1✔
90
{
91
    static unsigned version_counter = 0;
92

93
    ++version_counter;
1✔
94

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

117
std::vector<std::shared_ptr<System>> MavsdkImpl::systems() const
70✔
118
{
119
    std::vector<std::shared_ptr<System>> systems_result{};
70✔
120

121
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
70✔
122
    for (auto& system : _systems) {
105✔
123
        // We ignore the 0 entry because it's just a null system.
124
        // It's only created because the older, deprecated API needs a
125
        // reference.
126
        if (system.first == 0) {
35✔
127
            continue;
×
128
        }
129
        systems_result.push_back(system.second);
35✔
130
    }
131

132
    return systems_result;
70✔
133
}
70✔
134

135
std::optional<std::shared_ptr<System>> MavsdkImpl::first_autopilot(double timeout_s)
33✔
136
{
137
    {
138
        std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
33✔
139
        for (auto system : _systems) {
33✔
140
            if (system.second->is_connected() && system.second->has_autopilot()) {
×
141
                return system.second;
×
142
            }
143
        }
×
144
    }
33✔
145

146
    if (timeout_s == 0.0) {
33✔
147
        // Don't wait at all.
148
        return {};
×
149
    }
150

151
    auto prom = std::promise<std::shared_ptr<System>>();
33✔
152

153
    std::once_flag flag;
33✔
154
    auto handle = subscribe_on_new_system([this, &prom, &flag]() {
66✔
155
        const auto system = systems().at(0);
66✔
156
        if (system->is_connected() && system->has_autopilot()) {
33✔
157
            std::call_once(flag, [&prom, &system]() { prom.set_value(system); });
66✔
158
        }
159
    });
66✔
160

161
    auto fut = prom.get_future();
33✔
162

163
    if (timeout_s > 0.0) {
33✔
164
        if (fut.wait_for(std::chrono::milliseconds(int64_t(timeout_s * 1e3))) ==
33✔
165
            std::future_status::ready) {
166
            unsubscribe_on_new_system(handle);
33✔
167
            return fut.get();
33✔
168

169
        } else {
170
            unsubscribe_on_new_system(handle);
×
171
            return std::nullopt;
×
172
        }
173
    } else {
174
        fut.wait();
×
175
        unsubscribe_on_new_system(handle);
×
176
        return std::optional(fut.get());
×
177
    }
178
}
33✔
179

180
std::shared_ptr<ServerComponent> MavsdkImpl::server_component(unsigned instance)
35✔
181
{
182
    auto component_type = _configuration.get_component_type();
35✔
183
    switch (component_type) {
35✔
184
        case ComponentType::Autopilot:
35✔
185
        case ComponentType::GroundStation:
186
        case ComponentType::CompanionComputer:
187
        case ComponentType::Camera:
188
        case ComponentType::Gimbal:
189
        case ComponentType::RemoteId:
190
        case ComponentType::Custom:
191
            return server_component_by_type(component_type, instance);
35✔
192
        default:
×
193
            LogErr() << "Unknown component type";
×
194
            return {};
×
195
    }
196
}
197

198
std::shared_ptr<ServerComponent>
199
MavsdkImpl::server_component_by_type(ComponentType server_component_type, unsigned instance)
35✔
200
{
201
    switch (server_component_type) {
35✔
202
        case ComponentType::Autopilot:
33✔
203
            if (instance == 0) {
33✔
204
                return server_component_by_id(MAV_COMP_ID_AUTOPILOT1);
33✔
205
            } else {
206
                LogErr() << "Only autopilot instance 0 is valid";
×
207
                return {};
×
208
            }
209

210
        case ComponentType::GroundStation:
×
211
            if (instance == 0) {
×
212
                return server_component_by_id(MAV_COMP_ID_MISSIONPLANNER);
×
213
            } else {
214
                LogErr() << "Only one ground station supported at this time";
×
215
                return {};
×
216
            }
217

218
        case ComponentType::CompanionComputer:
1✔
219
            if (instance == 0) {
1✔
220
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER);
1✔
221
            } else if (instance == 1) {
×
222
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER2);
×
223
            } else if (instance == 2) {
×
224
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER3);
×
225
            } else if (instance == 3) {
×
226
                return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER4);
×
227
            } else {
228
                LogErr() << "Only companion computer 0..3 are supported";
×
229
                return {};
×
230
            }
231

232
        case ComponentType::Camera:
1✔
233
            if (instance == 0) {
1✔
234
                return server_component_by_id(MAV_COMP_ID_CAMERA);
1✔
235
            } else if (instance == 1) {
×
236
                return server_component_by_id(MAV_COMP_ID_CAMERA2);
×
237
            } else if (instance == 2) {
×
238
                return server_component_by_id(MAV_COMP_ID_CAMERA3);
×
239
            } else if (instance == 3) {
×
240
                return server_component_by_id(MAV_COMP_ID_CAMERA4);
×
241
            } else if (instance == 4) {
×
242
                return server_component_by_id(MAV_COMP_ID_CAMERA5);
×
243
            } else if (instance == 5) {
×
244
                return server_component_by_id(MAV_COMP_ID_CAMERA6);
×
245
            } else {
246
                LogErr() << "Only camera 0..5 are supported";
×
247
                return {};
×
248
            }
249

250
        default:
×
251
            LogErr() << "Unknown server component type";
×
252
            return {};
×
253
    }
254
}
255

256
std::shared_ptr<ServerComponent> MavsdkImpl::server_component_by_id(uint8_t component_id)
140✔
257
{
258
    if (component_id == 0) {
140✔
259
        LogErr() << "Server component with component ID 0 not allowed";
×
260
        return nullptr;
×
261
    }
262

263
    std::lock_guard<std::mutex> lock(_server_components_mutex);
140✔
264

265
    for (auto& it : _server_components) {
141✔
266
        if (it.first == component_id) {
69✔
267
            if (it.second != nullptr) {
68✔
268
                return it.second;
68✔
269
            } else {
270
                it.second = std::make_shared<ServerComponent>(*this, component_id);
×
271
            }
272
        }
273
    }
274

275
    _server_components.emplace_back(std::pair<uint8_t, std::shared_ptr<ServerComponent>>(
144✔
276
        component_id, std::make_shared<ServerComponent>(*this, component_id)));
144✔
277

278
    return _server_components.back().second;
72✔
279
}
140✔
280

281
void MavsdkImpl::forward_message(mavlink_message_t& message, Connection* connection)
×
282
{
283
    // Forward_message Function implementing Mavlink routing rules.
284
    // See https://mavlink.io/en/guide/routing.html
285

286
    bool forward_heartbeats_enabled = true;
×
287
    const uint8_t target_system_id = get_target_system_id(message);
×
288
    const uint8_t target_component_id = get_target_component_id(message);
×
289

290
    // If it's a message only for us, we keep it, otherwise, we forward it.
291
    const bool targeted_only_at_us =
292
        (target_system_id == get_own_system_id() && target_component_id == get_own_component_id());
×
293

294
    // We don't forward heartbeats unless it's specifically enabled.
295
    const bool heartbeat_check_ok =
×
296
        (message.msgid != MAVLINK_MSG_ID_HEARTBEAT || forward_heartbeats_enabled);
×
297

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

317
void MavsdkImpl::receive_message(mavlink_message_t& message, Connection* connection)
1,547✔
318
{
319
    if (_message_logging_on) {
1,547✔
320
        LogDebug() << "Processing message " << message.msgid << " from "
×
321
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid);
×
322
    }
323

324
    if (_should_exit) {
1,547✔
325
        // If we're meant to clean up, let's not try to acquire any more locks but bail.
326
        return;
2✔
327
    }
328

329
    // This is a low level interface where incoming messages can be tampered
330
    // with or even dropped.
331
    {
332
        std::lock_guard<std::mutex> lock(_intercept_callback_mutex);
1,545✔
333
        if (_intercept_incoming_messages_callback != nullptr) {
1,545✔
334
            bool keep = _intercept_incoming_messages_callback(message);
244✔
335
            if (!keep) {
244✔
336
                LogDebug() << "Dropped incoming message: " << int(message.msgid);
40✔
337
                return;
40✔
338
            }
339
        }
340
    }
1,545✔
341

342
    if (_should_exit) {
1,505✔
343
        // If we're meant to clean up, let's not try to acquire any more locks but bail.
344
        return;
×
345
    }
346

347
    /** @note: Forward message if option is enabled and multiple interfaces are connected.
348
     *  Performs message forwarding checks for every messages if message forwarding
349
     *  is enabled on at least one connection, and in case of a single forwarding connection,
350
     *  we check that it is not the one which received the current message.
351
     *
352
     * Conditions:
353
     * 1. At least 2 connections.
354
     * 2. At least 1 forwarding connection.
355
     * 3. At least 2 forwarding connections or current connection is not forwarding.
356
     */
357

358
    {
359
        std::lock_guard<std::mutex> lock(_connections_mutex);
1,505✔
360

361
        if (_connections.size() > 1 && mavsdk::Connection::forwarding_connections_count() > 0 &&
1,505✔
362
            (mavsdk::Connection::forwarding_connections_count() > 1 ||
×
363
             !connection->should_forward_messages())) {
×
364
            if (_message_logging_on) {
×
365
                LogDebug() << "Forwarding message " << message.msgid << " from "
×
366
                           << static_cast<int>(message.sysid) << "/"
×
367
                           << static_cast<int>(message.compid);
×
368
            }
369
            forward_message(message, connection);
×
370
        }
371
    }
1,505✔
372

373
    // Don't ever create a system with sysid 0.
374
    if (message.sysid == 0) {
1,505✔
375
        if (_message_logging_on) {
×
376
            LogDebug() << "Ignoring message with sysid == 0";
×
377
        }
378
        return;
×
379
    }
380

381
    // Filter out messages by QGroundControl, however, only do that if MAVSDK
382
    // is also implementing a ground station and not if it is used in another
383
    // configuration, e.g. on a companion.
384
    //
385
    // This is a workaround because PX4 started forwarding messages between
386
    // mavlink instances which leads to existing implementations (including
387
    // examples and integration tests) to connect to QGroundControl by accident
388
    // instead of PX4 because the check `has_autopilot()` is not used.
389
    if (_configuration.get_component_type() == ComponentType::GroundStation &&
1,505✔
390
        message.sysid == 255 && message.compid == MAV_COMP_ID_MISSIONPLANNER) {
1,505✔
391
        if (_message_logging_on) {
×
392
            LogDebug() << "Ignoring messages from QGC as we are also a ground station";
×
393
        }
394
        return;
×
395
    }
396

397
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
1,505✔
398

399
    bool found_system = false;
1,505✔
400
    for (auto& system : _systems) {
1,505✔
401
        if (system.first == message.sysid) {
1,436✔
402
            system.second->system_impl()->add_new_component(message.compid);
1,436✔
403
            found_system = true;
1,436✔
404
            break;
1,436✔
405
        }
406
    }
407

408
    if (!found_system) {
1,505✔
409
        if (_system_debugging) {
69✔
410
            LogWarn() << "Create new system/component " << (int)message.sysid << "/"
×
411
                      << (int)message.compid;
×
412
            LogWarn() << "From message " << (int)message.msgid << " with len " << (int)message.len;
×
413
            std::string bytes = "";
×
414
            for (unsigned i = 0; i < 12 + message.len; ++i) {
×
415
                bytes += std::to_string(reinterpret_cast<uint8_t*>(&message)[i]) + ' ';
×
416
            }
417
            LogWarn() << "Bytes: " << bytes;
×
418
        }
×
419
        make_system_with_component(message.sysid, message.compid);
69✔
420
    }
421

422
    if (_should_exit) {
1,505✔
423
        // Don't try to call at() if systems have already been destroyed
424
        // in destructor.
425
        return;
×
426
    }
427

428
    mavlink_message_handler.process_message(message);
1,505✔
429

430
    for (auto& system : _systems) {
1,505✔
431
        if (system.first == message.sysid) {
1,505✔
432
            system.second->system_impl()->process_mavlink_message(message);
1,505✔
433
            break;
1,505✔
434
        }
435
    }
436
}
1,505✔
437

438
bool MavsdkImpl::send_message(mavlink_message_t& message)
1,663✔
439
{
440
    if (_message_logging_on) {
1,663✔
441
        LogDebug() << "Sending message " << message.msgid << " from "
×
442
                   << static_cast<int>(message.sysid) << "/" << static_cast<int>(message.compid)
×
443
                   << " to " << static_cast<int>(get_target_system_id(message)) << "/"
×
444
                   << static_cast<int>(get_target_component_id(message));
×
445
    }
446

447
    // This is a low level interface where outgoing messages can be tampered
448
    // with or even dropped.
449
    if (_intercept_outgoing_messages_callback != nullptr) {
1,663✔
450
        const bool keep = _intercept_outgoing_messages_callback(message);
220✔
451
        if (!keep) {
220✔
452
            // We fake that everything was sent as instructed because
453
            // a potential loss would happen later, and we would not be informed
454
            // about it.
455
            LogDebug() << "Dropped outgoing message: " << int(message.msgid);
81✔
456
            return true;
81✔
457
        }
458
    }
459

460
    std::lock_guard<std::mutex> lock(_connections_mutex);
1,582✔
461

462
    if (_connections.empty()) {
1,582✔
463
        // We obviously can't send any messages without a connection added, so
464
        // we silently ignore this.
465
        return true;
35✔
466
    }
467

468
    uint8_t successful_emissions = 0;
1,547✔
469
    for (auto& _connection : _connections) {
3,094✔
470
        const uint8_t target_system_id = get_target_system_id(message);
1,547✔
471

472
        if (target_system_id != 0 && !(*_connection.connection).has_system_id(target_system_id)) {
1,547✔
473
            continue;
×
474
        }
475

476
        if ((*_connection.connection).send_message(message)) {
1,547✔
477
            successful_emissions++;
1,547✔
478
        }
479
    }
480

481
    if (successful_emissions == 0) {
1,547✔
482
        LogErr() << "Sending message failed";
×
483
        return false;
×
484
    }
485

486
    return true;
1,547✔
487
}
1,582✔
488

489
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_any_connection(
70✔
490
    const std::string& connection_url, ForwardingOption forwarding_option)
491
{
492
    CliArg cli_arg;
70✔
493
    if (!cli_arg.parse(connection_url)) {
70✔
494
        return {ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle{}};
×
495
    }
496

497
    return std::visit(
70✔
498
        overloaded{
140✔
499
            [](std::monostate) {
×
500
                // Should not happen anyway.
501
                return std::pair<ConnectionResult, Mavsdk::ConnectionHandle>{
×
502
                    ConnectionResult::ConnectionUrlInvalid, Mavsdk::ConnectionHandle()};
×
503
            },
504
            [this, forwarding_option](const CliArg::Udp& udp) {
68✔
505
                return add_udp_connection(udp, forwarding_option);
68✔
506
            },
507
            [this, forwarding_option](const CliArg::Tcp& tcp) {
2✔
508
                return add_tcp_connection(tcp, forwarding_option);
2✔
509
            },
510
            [this, forwarding_option](const CliArg::Serial& serial) {
×
511
                return add_serial_connection(
×
512
                    serial.path, serial.baudrate, serial.flow_control_enabled, forwarding_option);
×
513
            }},
514
        cli_arg.protocol);
70✔
515
}
70✔
516

517
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
518
MavsdkImpl::add_udp_connection(const CliArg::Udp& udp, ForwardingOption forwarding_option)
68✔
519
{
520
    auto new_conn = std::make_shared<UdpConnection>(
68✔
521
        [this](mavlink_message_t& message, Connection* connection) {
1,537✔
522
            receive_message(message, connection);
1,537✔
523
        },
1,537✔
524
        udp.mode == CliArg::Udp::Mode::In ? udp.host : "0.0.0.0",
170✔
525
        udp.mode == CliArg::Udp::Mode::In ? udp.port : 0,
136✔
526
        forwarding_option);
204✔
527

528
    if (!new_conn) {
68✔
529
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
530
    }
531

532
    ConnectionResult ret = new_conn->start();
68✔
533

534
    if (ret != ConnectionResult::Success) {
68✔
535
        return {ret, Mavsdk::ConnectionHandle{}};
×
536
    }
537

538
    auto handle = add_connection(new_conn);
68✔
539

540
    if (udp.mode == CliArg::Udp::Mode::Out) {
68✔
541
        new_conn->add_remote(udp.host, udp.port);
34✔
542
        std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
34✔
543

544
        // With a UDP remote, we need to initiate the connection by sending heartbeats.
545
        auto new_configuration = get_configuration();
34✔
546
        new_configuration.set_always_send_heartbeats(true);
34✔
547
        set_configuration(new_configuration);
34✔
548
    }
34✔
549
    return {ConnectionResult::Success, handle};
68✔
550
}
68✔
551

552
std::pair<ConnectionResult, Mavsdk::ConnectionHandle>
553
MavsdkImpl::add_tcp_connection(const CliArg::Tcp& tcp, ForwardingOption forwarding_option)
2✔
554
{
555
    if (tcp.mode == CliArg::Tcp::Mode::Out) {
2✔
556
        auto new_conn = std::make_shared<TcpClientConnection>(
1✔
557
            [this](mavlink_message_t& message, Connection* connection) {
3✔
558
                receive_message(message, connection);
3✔
559
            },
3✔
560
            tcp.host,
1✔
561
            tcp.port,
1✔
562
            forwarding_option);
1✔
563
        if (!new_conn) {
1✔
564
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
565
        }
566
        ConnectionResult ret = new_conn->start();
1✔
567
        if (ret == ConnectionResult::Success) {
1✔
568
            return {ret, add_connection(new_conn)};
1✔
569
        } else {
570
            return {ret, Mavsdk::ConnectionHandle{}};
×
571
        }
572
    } else {
1✔
573
        auto new_conn = std::make_shared<TcpServerConnection>(
1✔
574
            [this](mavlink_message_t& message, Connection* connection) {
7✔
575
                receive_message(message, connection);
7✔
576
            },
7✔
577
            tcp.host,
1✔
578
            tcp.port,
1✔
579
            forwarding_option);
1✔
580
        if (!new_conn) {
1✔
581
            return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
582
        }
583
        ConnectionResult ret = new_conn->start();
1✔
584
        if (ret == ConnectionResult::Success) {
1✔
585
            return {ret, add_connection(new_conn)};
1✔
586
        } else {
587
            return {ret, Mavsdk::ConnectionHandle{}};
×
588
        }
589
    }
1✔
590
}
591

592
std::pair<ConnectionResult, Mavsdk::ConnectionHandle> MavsdkImpl::add_serial_connection(
×
593
    const std::string& dev_path,
594
    int baudrate,
595
    bool flow_control,
596
    ForwardingOption forwarding_option)
597
{
598
    auto new_conn = std::make_shared<SerialConnection>(
×
599
        [this](mavlink_message_t& message, Connection* connection) {
×
600
            receive_message(message, connection);
×
601
        },
×
602
        dev_path,
603
        baudrate,
604
        flow_control,
605
        forwarding_option);
×
606
    if (!new_conn) {
×
607
        return {ConnectionResult::ConnectionError, Mavsdk::ConnectionHandle{}};
×
608
    }
609
    ConnectionResult ret = new_conn->start();
×
610
    if (ret == ConnectionResult::Success) {
×
611
        auto handle = add_connection(new_conn);
×
612

613
        auto new_configuration = get_configuration();
×
614

615
        // PX4 starting with v1.13 does not send heartbeats by default, so we need
616
        // to initiate the MAVLink connection by sending heartbeats.
617
        // Therefore, we override the default here and enable sending heartbeats.
618
        new_configuration.set_always_send_heartbeats(true);
×
619
        set_configuration(new_configuration);
×
620

621
        return {ret, handle};
×
622

623
    } else {
624
        return {ret, Mavsdk::ConnectionHandle{}};
×
625
    }
626
}
×
627

628
Mavsdk::ConnectionHandle
629
MavsdkImpl::add_connection(const std::shared_ptr<Connection>& new_connection)
70✔
630
{
631
    std::lock_guard<std::mutex> lock(_connections_mutex);
70✔
632
    auto handle = _connections_handle_factory.create();
70✔
633
    _connections.emplace_back(ConnectionEntry{new_connection, handle});
70✔
634

635
    return handle;
140✔
636
}
70✔
637

638
void MavsdkImpl::remove_connection(Mavsdk::ConnectionHandle handle)
×
639
{
640
    std::lock_guard<std::mutex> lock(_connections_mutex);
×
641

642
    _connections.erase(std::remove_if(_connections.begin(), _connections.end(), [&](auto&& entry) {
×
643
        return (entry.handle == handle);
×
644
    }));
645
}
×
646

647
Mavsdk::Configuration MavsdkImpl::get_configuration() const
34✔
648
{
649
    return _configuration;
34✔
650
}
651

652
void MavsdkImpl::set_configuration(Mavsdk::Configuration new_configuration)
105✔
653
{
654
    // We just point the default to the newly created component. This means
655
    // that the previous default component will be deleted if it is not
656
    // used/referenced anywhere.
657
    _default_server_component = server_component_by_id(new_configuration.get_component_id());
105✔
658

659
    if (new_configuration.get_always_send_heartbeats() &&
174✔
660
        !_configuration.get_always_send_heartbeats()) {
69✔
661
        start_sending_heartbeats();
35✔
662
    } else if (
70✔
663
        !new_configuration.get_always_send_heartbeats() &&
106✔
664
        _configuration.get_always_send_heartbeats() && !is_any_system_connected()) {
106✔
665
        stop_sending_heartbeats();
×
666
    }
667

668
    _configuration = new_configuration;
105✔
669
}
105✔
670

671
uint8_t MavsdkImpl::get_own_system_id() const
4,247✔
672
{
673
    return _configuration.get_system_id();
4,247✔
674
}
675

676
uint8_t MavsdkImpl::get_own_component_id() const
1,205✔
677
{
678
    return _configuration.get_component_id();
1,205✔
679
}
680

681
uint8_t MavsdkImpl::channel() const
×
682
{
683
    // TODO
684
    return 0;
×
685
}
686

687
Autopilot MavsdkImpl::autopilot() const
×
688
{
689
    // TODO
690
    return Autopilot::Px4;
×
691
}
692

693
// FIXME: this should be per component
694
uint8_t MavsdkImpl::get_mav_type() const
162✔
695
{
696
    switch (_configuration.get_component_type()) {
162✔
697
        case ComponentType::Autopilot:
113✔
698
            return MAV_TYPE_GENERIC;
113✔
699

700
        case ComponentType::GroundStation:
43✔
701
            return MAV_TYPE_GCS;
43✔
702

703
        case ComponentType::CompanionComputer:
4✔
704
            return MAV_TYPE_ONBOARD_CONTROLLER;
4✔
705

706
        case ComponentType::Camera:
2✔
707
            return MAV_TYPE_CAMERA;
2✔
708

709
        case ComponentType::Gimbal:
×
710
            return MAV_TYPE_GIMBAL;
×
711

712
        case ComponentType::RemoteId:
×
713
            return MAV_TYPE_ODID;
×
714

715
        case ComponentType::Custom:
×
716
            return MAV_TYPE_GENERIC;
×
717

718
        default:
×
719
            LogErr() << "Unknown configuration";
×
720
            return 0;
×
721
    }
722
}
723

724
void MavsdkImpl::make_system_with_component(uint8_t system_id, uint8_t comp_id)
69✔
725
{
726
    // Needs _systems_lock
727

728
    if (_should_exit) {
69✔
729
        // When the system got destroyed in the destructor, we have to give up.
730
        return;
×
731
    }
732

733
    if (static_cast<int>(system_id) == 0 && static_cast<int>(comp_id) == 0) {
69✔
734
        LogDebug() << "Initializing connection to remote system...";
×
735
    } else {
736
        LogDebug() << "New system ID: " << static_cast<int>(system_id)
207✔
737
                   << " Comp ID: " << static_cast<int>(comp_id);
207✔
738
    }
739

740
    // Make a system with its first component
741
    auto new_system = std::make_shared<System>(*this);
69✔
742
    new_system->init(system_id, comp_id);
69✔
743

744
    _systems.emplace_back(system_id, new_system);
69✔
745
}
69✔
746

747
void MavsdkImpl::notify_on_discover()
69✔
748
{
749
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
69✔
750
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
104✔
751
}
69✔
752

753
void MavsdkImpl::notify_on_timeout()
×
754
{
755
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
×
756
    _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
757
}
×
758

759
Mavsdk::NewSystemHandle
760
MavsdkImpl::subscribe_on_new_system(const Mavsdk::NewSystemCallback& callback)
35✔
761
{
762
    std::lock_guard<std::recursive_mutex> lock(_systems_mutex);
35✔
763

764
    const auto handle = _new_system_callbacks.subscribe(callback);
35✔
765

766
    if (is_any_system_connected()) {
35✔
767
        _new_system_callbacks.queue([this](const auto& func) { call_user_callback(func); });
×
768
    }
769

770
    return handle;
70✔
771
}
35✔
772

773
void MavsdkImpl::unsubscribe_on_new_system(Mavsdk::NewSystemHandle handle)
34✔
774
{
775
    _new_system_callbacks.unsubscribe(handle);
34✔
776
}
34✔
777

778
bool MavsdkImpl::is_any_system_connected() const
35✔
779
{
780
    std::vector<std::shared_ptr<System>> connected_systems = systems();
35✔
781
    return std::any_of(connected_systems.cbegin(), connected_systems.cend(), [](auto& system) {
35✔
782
        return system->is_connected();
×
783
    });
35✔
784
}
35✔
785

786
void MavsdkImpl::work_thread()
71✔
787
{
788
    while (!_should_exit) {
11,541✔
789
        timeout_handler.run_once();
11,325✔
790
        call_every_handler.run_once();
11,732✔
791

792
        {
793
            std::lock_guard<std::mutex> lock(_server_components_mutex);
11,755✔
794
            for (auto& it : _server_components) {
23,190✔
795
                if (it.second != nullptr) {
11,764✔
796
                    it.second->_impl->do_work();
11,722✔
797
                }
798
            }
799
        }
11,170✔
800

801
        std::this_thread::sleep_for(std::chrono::milliseconds(10));
11,308✔
802
    }
803
}
45✔
804

805
void MavsdkImpl::call_user_callback_located(
808✔
806
    const std::string& filename, const int linenumber, const std::function<void()>& func)
807
{
808
    auto callback_size = _user_callback_queue.size();
808✔
809
    if (callback_size == 10) {
808✔
810
        LogWarn()
6✔
811
            << "User callback queue too slow.\n"
3✔
812
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
3✔
813

814
    } else if (callback_size == 99) {
805✔
815
        LogErr()
×
816
            << "User callback queue overflown\n"
×
817
               "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
818

819
    } else if (callback_size == 100) {
805✔
820
        return;
×
821
    }
822

823
    // We only need to keep track of filename and linenumber if we're actually debugging this.
824
    UserCallback user_callback =
808✔
825
        _callback_debugging ? UserCallback{func, filename, linenumber} : UserCallback{func};
1,616✔
826

827
    _user_callback_queue.enqueue(user_callback);
808✔
828
}
808✔
829

830
void MavsdkImpl::process_user_callbacks_thread()
71✔
831
{
832
    while (!_should_exit) {
950✔
833
        auto callback = _user_callback_queue.dequeue();
879✔
834
        if (!callback) {
879✔
835
            continue;
71✔
836
        }
837

838
        const double timeout_s = 1.0;
808✔
839
        auto cookie = timeout_handler.add(
808✔
840
            [&]() {
×
841
                if (_callback_debugging) {
×
842
                    LogWarn() << "Callback called from " << callback.value().filename << ":"
×
843
                              << callback.value().linenumber << " took more than " << timeout_s
×
844
                              << " second to run.";
×
845
                    fflush(stdout);
×
846
                    fflush(stderr);
×
847
                    abort();
×
848
                } else {
849
                    LogWarn()
×
850
                        << "Callback took more than " << timeout_s << " second to run.\n"
×
851
                        << "See: https://mavsdk.mavlink.io/main/en/cpp/troubleshooting.html#user_callbacks";
×
852
                }
853
            },
×
854
            timeout_s);
808✔
855
        callback.value().func();
808✔
856
        timeout_handler.remove(cookie);
808✔
857
    }
879✔
858
}
71✔
859

860
void MavsdkImpl::start_sending_heartbeats()
104✔
861
{
862
    // Before sending out first heartbeats we need to make sure we have a
863
    // default server component.
864
    default_server_component_impl();
104✔
865

866
    call_every_handler.remove(_heartbeat_send_cookie);
104✔
867
    _heartbeat_send_cookie =
208✔
868
        call_every_handler.add([this]() { send_heartbeat(); }, HEARTBEAT_SEND_INTERVAL_S);
265✔
869
}
104✔
870

871
void MavsdkImpl::stop_sending_heartbeats()
×
872
{
873
    if (!_configuration.get_always_send_heartbeats()) {
×
874
        call_every_handler.remove(_heartbeat_send_cookie);
×
875
    }
876
}
×
877

878
ServerComponentImpl& MavsdkImpl::default_server_component_impl()
754✔
879
{
880
    if (_default_server_component == nullptr) {
754✔
881
        _default_server_component = server_component_by_id(_configuration.get_component_id());
×
882
    }
883
    return *_default_server_component->_impl;
754✔
884
}
885

886
void MavsdkImpl::send_heartbeat()
161✔
887
{
888
    std::lock_guard<std::mutex> lock(_server_components_mutex);
161✔
889

890
    for (auto& it : _server_components) {
323✔
891
        if (it.second != nullptr) {
162✔
892
            it.second->_impl->send_heartbeat();
162✔
893
        }
894
    }
895
}
161✔
896

897
void MavsdkImpl::intercept_incoming_messages_async(std::function<bool(mavlink_message_t&)> callback)
22✔
898
{
899
    std::lock_guard<std::mutex> lock(_intercept_callback_mutex);
22✔
900
    _intercept_incoming_messages_callback = callback;
22✔
901
}
22✔
902

903
void MavsdkImpl::intercept_outgoing_messages_async(std::function<bool(mavlink_message_t&)> callback)
14✔
904
{
905
    std::lock_guard<std::mutex> lock(_intercept_callback_mutex);
14✔
906
    _intercept_outgoing_messages_callback = callback;
14✔
907
}
14✔
908

909
uint8_t MavsdkImpl::get_target_system_id(const mavlink_message_t& message)
1,547✔
910
{
911
    // Checks whether connection knows target system ID by extracting target system if set.
912
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
1,547✔
913

914
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM)) {
1,547✔
915
        return 0;
224✔
916
    }
917

918
    // Don't look at the target system offset if it is outside the payload length.
919
    // This can happen if the fields are trimmed.
920
    if (meta->target_system_ofs >= message.len) {
1,323✔
921
        return 0;
×
922
    }
923

924
    return (_MAV_PAYLOAD(&message))[meta->target_system_ofs];
1,323✔
925
}
926

927
uint8_t MavsdkImpl::get_target_component_id(const mavlink_message_t& message)
×
928
{
929
    // Checks whether connection knows target system ID by extracting target system if set.
930
    const mavlink_msg_entry_t* meta = mavlink_get_msg_entry(message.msgid);
×
931

932
    if (meta == nullptr || !(meta->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT)) {
×
933
        return 0;
×
934
    }
935

936
    // Don't look at the target component offset if it is outside the payload length.
937
    // This can happen if the fields are trimmed.
938
    if (meta->target_component_ofs >= message.len) {
×
939
        return 0;
×
940
    }
941

942
    return (_MAV_PAYLOAD(&message))[meta->target_component_ofs];
×
943
}
944

945
Sender& MavsdkImpl::sender()
×
946
{
947
    return default_server_component_impl().sender();
×
948
}
949

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