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

mavlink / MAVSDK / 20738098150

06 Jan 2026 01:54AM UTC coverage: 48.071% (+0.02%) from 48.056%
20738098150

push

github

web-flow
Merge pull request #2748 from mavlink/pr-log-annoyance

Clean up debug messages on discovery a bit

8 of 11 new or added lines in 2 files covered. (72.73%)

4 existing lines in 3 files now uncovered.

17743 of 36910 relevant lines covered (48.07%)

464.68 hits per line

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

45.61
/src/mavsdk/core/system_impl.cpp
1
#include "system.h"
2
#include "mavsdk_impl.h"
3
#include "mavlink_include.h"
4
#include "system_impl.h"
5
#include <mav/MessageSet.h>
6
#include "server_component_impl.h"
7
#include "plugin_impl_base.h"
8
#include "px4_custom_mode.h"
9
#include "ardupilot_custom_mode.h"
10
#include "callback_list.tpp"
11
#include "unused.h"
12
#include <cassert>
13
#include <cstdlib>
14
#include <functional>
15
#include <future>
16
#include <utility>
17

18
namespace mavsdk {
19

20
template class CallbackList<bool>;
21
template class CallbackList<ComponentType>;
22
template class CallbackList<ComponentType, uint8_t>;
23

24
SystemImpl::SystemImpl(MavsdkImpl& mavsdk_impl) :
142✔
25
    _mavsdk_impl(mavsdk_impl),
142✔
26
    _command_sender(*this),
142✔
27
    _timesync(*this),
142✔
28
    _ping(*this),
142✔
29
    _mission_transfer_client(
284✔
30
        _mavsdk_impl.default_server_component_impl().sender(),
142✔
31
        _mavlink_message_handler,
142✔
32
        _mavsdk_impl.timeout_handler,
142✔
33
        [this]() { return timeout_s(); },
1✔
34
        [this]() { return autopilot(); }),
1✔
35
    _mavlink_request_message(
142✔
36
        *this, _command_sender, _mavlink_message_handler, _mavsdk_impl.timeout_handler),
142✔
37
    _mavlink_ftp_client(*this),
142✔
38
    _mavlink_component_metadata(*this)
284✔
39
{
40
    if (const char* env_p = std::getenv("MAVSDK_MESSAGE_DEBUGGING")) {
142✔
41
        if (std::string(env_p) == "1") {
×
42
            _message_debugging = true;
×
43
        }
44
    }
45

46
    _system_thread = new std::thread(&SystemImpl::system_thread, this);
142✔
47
}
142✔
48

49
SystemImpl::~SystemImpl()
142✔
50
{
51
    _should_exit = true;
142✔
52
    // Use blocking version to ensure any in-flight callbacks complete before destruction.
53
    _mavlink_message_handler.unregister_all_blocking(this);
142✔
54
    // Clear all libmav message callbacks
55
    _libmav_message_callbacks.clear();
142✔
56

57
    unregister_timeout_handler(_heartbeat_timeout_cookie);
142✔
58

59
    if (_system_thread != nullptr) {
142✔
60
        _system_thread->join();
142✔
61
        delete _system_thread;
142✔
62
        _system_thread = nullptr;
142✔
63
    }
64
}
142✔
65

66
void SystemImpl::init(uint8_t system_id, uint8_t comp_id)
141✔
67
{
68
    _target_address.system_id = system_id;
141✔
69
    // We use this as a default.
70
    _target_address.component_id = MAV_COMP_ID_AUTOPILOT1;
141✔
71

72
    _mavlink_message_handler.register_one(
141✔
73
        MAVLINK_MSG_ID_HEARTBEAT,
74
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
353✔
75
        this);
76

77
    _mavlink_message_handler.register_one(
142✔
78
        MAVLINK_MSG_ID_STATUSTEXT,
79
        [this](const mavlink_message_t& message) { process_statustext(message); },
3✔
80
        this);
81

82
    _mavlink_message_handler.register_one(
142✔
83
        MAVLINK_MSG_ID_AUTOPILOT_VERSION,
84
        [this](const mavlink_message_t& message) { process_autopilot_version(message); },
74✔
85
        this);
86

87
    add_new_component(comp_id);
142✔
88
}
142✔
89

90
bool SystemImpl::is_connected() const
69✔
91
{
92
    return _connected;
69✔
93
}
94

95
void SystemImpl::register_mavlink_message_handler(
646✔
96
    uint16_t msg_id, const MavlinkMessageHandler::Callback& callback, const void* cookie)
97
{
98
    _mavlink_message_handler.register_one(msg_id, callback, cookie);
646✔
99
}
646✔
100

101
void SystemImpl::register_mavlink_message_handler_with_compid(
×
102
    uint16_t msg_id,
103
    uint8_t component_id,
104
    const MavlinkMessageHandler::Callback& callback,
105
    const void* cookie)
106
{
107
    _mavlink_message_handler.register_one_with_component_id(msg_id, component_id, callback, cookie);
×
108
}
×
109

110
void SystemImpl::unregister_mavlink_message_handler(uint16_t msg_id, const void* cookie)
×
111
{
112
    _mavlink_message_handler.unregister_one(msg_id, cookie);
×
113
}
×
114

115
void SystemImpl::unregister_all_mavlink_message_handlers(const void* cookie)
568✔
116
{
117
    _mavlink_message_handler.unregister_all(cookie);
568✔
118
}
568✔
119

120
void SystemImpl::unregister_all_mavlink_message_handlers_blocking(const void* cookie)
17✔
121
{
122
    _mavlink_message_handler.unregister_all_blocking(cookie);
17✔
123
}
17✔
124

125
void SystemImpl::update_component_id_messages_handler(
×
126
    uint16_t msg_id, uint8_t component_id, const void* cookie)
127
{
128
    _mavlink_message_handler.update_component_id(msg_id, component_id, cookie);
×
129
}
×
130

131
void SystemImpl::process_libmav_message(const Mavsdk::MavlinkMessage& message)
2,439✔
132
{
133
    if (_message_debugging) {
2,439✔
134
        LogDebug() << "SystemImpl::process_libmav_message: " << message.message_name;
×
135
    }
136

137
    // CallbackList handles thread safety - just call all callbacks and let them filter internally
138
    _libmav_message_callbacks.queue(
2,439✔
139
        message, [this](const std::function<void()>& callback_wrapper) { callback_wrapper(); });
110✔
140
}
2,442✔
141

142
Handle<Mavsdk::MavlinkMessage> SystemImpl::register_libmav_message_handler(
30✔
143
    const std::string& message_name, const LibmavMessageCallback& callback)
144
{
145
    // Create a filtering callback that only calls the user callback for matching messages
146
    auto filtering_callback =
147
        [this, message_name, callback](const Mavsdk::MavlinkMessage& message) {
221✔
148
            if (_message_debugging) {
111✔
149
                LogDebug() << "Checking handler for message: '" << message_name << "' against '"
×
150
                           << message.message_name << "'";
×
151
            }
152

153
            // Check if message name matches (empty string means match all messages)
154
            if (!message_name.empty() && message_name != message.message_name) {
111✔
155
                if (_message_debugging) {
×
156
                    LogDebug() << "Handler message name mismatch, skipping";
×
157
                }
158
                return;
×
159
            }
160

161
            // Call the user callback
162
            if (_message_debugging) {
110✔
163
                LogDebug() << "Calling libmav handler for: " << message.message_name;
×
164
            }
165
            callback(message);
110✔
166
        };
30✔
167

168
    auto handle = _libmav_message_callbacks.subscribe(filtering_callback);
30✔
169

170
    if (_message_debugging) {
30✔
171
        LogDebug() << "Registering libmav handler for message: '" << message_name << "'";
×
172
    }
173

174
    return handle;
60✔
175
}
30✔
176

177
Handle<Mavsdk::MavlinkMessage> SystemImpl::register_libmav_message_handler_with_compid(
×
178
    const std::string& message_name, uint8_t cmp_id, const LibmavMessageCallback& callback)
179
{
180
    // Create a filtering callback that only calls the user callback for matching messages
181
    auto filtering_callback =
182
        [this, message_name, cmp_id, callback](const Mavsdk::MavlinkMessage& message) {
×
183
            if (_message_debugging) {
×
184
                LogDebug() << "Checking handler for message: '" << message_name << "' against '"
×
185
                           << message.message_name
×
186
                           << "' with component ID: " << static_cast<int>(cmp_id);
×
187
            }
188

189
            // Check if message name matches (empty string means match all messages)
190
            if (!message_name.empty() && message_name != message.message_name) {
×
191
                if (_message_debugging) {
×
192
                    LogDebug() << "Handler message name mismatch, skipping";
×
193
                }
194
                return;
×
195
            }
196

197
            // Check if component ID matches
198
            if (cmp_id != message.component_id) {
×
199
                if (_message_debugging) {
×
200
                    LogDebug() << "Handler component ID mismatch, skipping";
×
201
                }
202
                return;
×
203
            }
204

205
            // Call the user callback
206
            if (_message_debugging) {
×
207
                LogDebug() << "Calling libmav handler for: " << message.message_name;
×
208
            }
209
            callback(message);
×
210
        };
×
211

212
    auto handle = _libmav_message_callbacks.subscribe(filtering_callback);
×
213

214
    if (_message_debugging) {
×
215
        LogDebug() << "Registering libmav handler for message: '" << message_name
×
216
                   << "' with component ID: " << static_cast<int>(cmp_id);
×
217
    }
218

219
    return handle;
×
220
}
×
221

222
void SystemImpl::unregister_libmav_message_handler(Handle<Mavsdk::MavlinkMessage> handle)
30✔
223
{
224
    _libmav_message_callbacks.unsubscribe(handle);
30✔
225

226
    if (_message_debugging) {
30✔
227
        LogDebug() << "Unregistered libmav handler";
×
228
    }
229
}
30✔
230

231
TimeoutHandler::Cookie
232
SystemImpl::register_timeout_handler(const std::function<void()>& callback, double duration_s)
1,198✔
233
{
234
    return _mavsdk_impl.timeout_handler.add(callback, duration_s);
1,198✔
235
}
236

237
void SystemImpl::refresh_timeout_handler(TimeoutHandler::Cookie cookie)
206✔
238
{
239
    _mavsdk_impl.timeout_handler.refresh(cookie);
206✔
240
}
212✔
241

242
void SystemImpl::unregister_timeout_handler(TimeoutHandler::Cookie cookie)
1,394✔
243
{
244
    _mavsdk_impl.timeout_handler.remove(cookie);
1,394✔
245
}
1,394✔
246

247
double SystemImpl::timeout_s() const
1,123✔
248
{
249
    return _mavsdk_impl.timeout_s();
1,123✔
250
}
251

252
void SystemImpl::enable_timesync()
×
253
{
254
    _timesync.enable();
×
255
}
×
256

257
System::IsConnectedHandle
258
SystemImpl::subscribe_is_connected(const System::IsConnectedCallback& callback)
×
259
{
260
    return _is_connected_callbacks.subscribe(callback);
×
261
}
262

263
void SystemImpl::unsubscribe_is_connected(System::IsConnectedHandle handle)
×
264
{
265
    _is_connected_callbacks.unsubscribe(handle);
×
266
}
×
267

268
void SystemImpl::process_mavlink_message(mavlink_message_t& message)
2,409✔
269
{
270
    _mavlink_message_handler.process_message(message);
2,409✔
271
}
2,415✔
272

273
CallEveryHandler::Cookie
274
SystemImpl::add_call_every(std::function<void()> callback, float interval_s)
33✔
275
{
276
    return _mavsdk_impl.call_every_handler.add(
66✔
277
        std::move(callback), static_cast<double>(interval_s));
66✔
278
}
279

280
void SystemImpl::change_call_every(float interval_s, CallEveryHandler::Cookie cookie)
×
281
{
282
    _mavsdk_impl.call_every_handler.change(static_cast<double>(interval_s), cookie);
×
283
}
×
284

285
void SystemImpl::reset_call_every(CallEveryHandler::Cookie cookie)
×
286
{
287
    _mavsdk_impl.call_every_handler.reset(cookie);
×
288
}
×
289

290
void SystemImpl::remove_call_every(CallEveryHandler::Cookie cookie)
33✔
291
{
292
    _mavsdk_impl.call_every_handler.remove(cookie);
33✔
293
}
33✔
294

295
void SystemImpl::register_statustext_handler(
6✔
296
    std::function<void(const MavlinkStatustextHandler::Statustext&)> callback, void* cookie)
297
{
298
    _statustext_handler_callbacks.push_back(StatustextCallback{std::move(callback), cookie});
6✔
299
}
6✔
300

301
void SystemImpl::unregister_statustext_handler(void* cookie)
6✔
302
{
303
    _statustext_handler_callbacks.erase(std::remove_if(
6✔
304
        _statustext_handler_callbacks.begin(),
305
        _statustext_handler_callbacks.end(),
306
        [&](const auto& entry) { return entry.cookie == cookie; }));
6✔
307
}
6✔
308

309
void SystemImpl::process_heartbeat(const mavlink_message_t& message)
352✔
310
{
311
    mavlink_heartbeat_t heartbeat;
312
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
352✔
313

314
    if (heartbeat.autopilot == MAV_AUTOPILOT_PX4) {
356✔
315
        _autopilot = Autopilot::Px4;
×
316
    } else if (heartbeat.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
356✔
317
        _autopilot = Autopilot::ArduPilot;
5✔
318
    }
319

320
    // Only set the vehicle type if the heartbeat is from an autopilot component
321
    // This check only works if the MAV_TYPE::MAV_TYPE_ENUM_END is actually the
322
    // last enumerator.
323
    if (MAV_TYPE::MAV_TYPE_ENUM_END < heartbeat.type) {
354✔
324
        LogErr() << "type received in HEARTBEAT was not recognized";
×
325
    } else {
326
        const auto new_vehicle_type = static_cast<MAV_TYPE>(heartbeat.type);
354✔
327
        if (heartbeat.autopilot != MAV_AUTOPILOT_INVALID && new_vehicle_type != MAV_TYPE_GENERIC) {
354✔
328
            if (_vehicle_type_set && _vehicle_type != new_vehicle_type) {
5✔
NEW
329
                LogWarn() << "Vehicle type changed (new type: "
×
NEW
330
                          << static_cast<unsigned>(heartbeat.type)
×
NEW
331
                          << ", old type: " << static_cast<unsigned>(_vehicle_type) << ")";
×
332
            }
333
            _vehicle_type = new_vehicle_type;
5✔
334
            _vehicle_type_set = true;
5✔
335
        }
336
    }
337

338
    if (message.compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
354✔
339
        _armed = (heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) != 0;
168✔
340
        _hitl_enabled = (heartbeat.base_mode & MAV_MODE_FLAG_HIL_ENABLED) != 0;
168✔
341
    }
342
    if (heartbeat.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
357✔
343
        _flight_mode =
5✔
344
            to_flight_mode_from_custom_mode(_autopilot, _vehicle_type, heartbeat.custom_mode);
345
    }
346

347
    set_connected();
357✔
348
}
353✔
349

350
void SystemImpl::process_statustext(const mavlink_message_t& message)
3✔
351
{
352
    mavlink_statustext_t statustext;
353
    mavlink_msg_statustext_decode(&message, &statustext);
3✔
354

355
    const auto maybe_result = _statustext_handler.process(statustext);
3✔
356

357
    if (maybe_result.has_value()) {
3✔
358
        LogDebug() << "MAVLink: "
3✔
359
                   << MavlinkStatustextHandler::severity_str(maybe_result.value().severity) << ": "
6✔
360
                   << maybe_result.value().text;
3✔
361

362
        for (const auto& entry : _statustext_handler_callbacks) {
6✔
363
            entry.callback(maybe_result.value());
3✔
364
        }
365
    }
366
}
3✔
367

368
void SystemImpl::process_autopilot_version(const mavlink_message_t& message)
74✔
369
{
370
    mavlink_autopilot_version_t autopilot_version;
371
    mavlink_msg_autopilot_version_decode(&message, &autopilot_version);
74✔
372

373
    _mission_transfer_client.set_int_messages_supported(
74✔
374
        autopilot_version.capabilities & MAV_PROTOCOL_CAPABILITY_MISSION_INT);
74✔
375
}
74✔
376

377
void SystemImpl::heartbeats_timed_out()
7✔
378
{
379
    LogInfo() << "heartbeats timed out";
7✔
380
    set_disconnected();
7✔
381
}
7✔
382

383
void SystemImpl::system_thread()
142✔
384
{
385
    SteadyTimePoint last_ping_time{};
142✔
386

387
    while (!_should_exit) {
17,852✔
388
        {
389
            std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
17,963✔
390
            for (auto& entry : _mavlink_parameter_clients) {
18,879✔
391
                entry.parameter_client->do_work();
923✔
392
            }
393
        }
17,842✔
394
        _command_sender.do_work();
18,008✔
395
        _timesync.do_work();
17,972✔
396
        _mission_transfer_client.do_work();
17,841✔
397
        _mavlink_ftp_client.do_work();
17,980✔
398

399
        if (_mavsdk_impl.time.elapsed_since_s(last_ping_time) >= SystemImpl::_ping_interval_s) {
18,003✔
400
            if (_connected && _autopilot != Autopilot::ArduPilot) {
152✔
401
                _ping.run_once();
11✔
402
            }
403
            last_ping_time = _mavsdk_impl.time.steady_time();
152✔
404
        }
405

406
        if (_connected) {
17,869✔
407
            // Work fairly fast if we're connected.
408
            std::this_thread::sleep_for(std::chrono::milliseconds(10));
17,748✔
409
        } else {
410
            // Be less aggressive when unconnected.
411
            std::this_thread::sleep_for(std::chrono::milliseconds(100));
178✔
412
        }
413
    }
414
}
75✔
415

416
std::string SystemImpl::component_name(uint8_t component_id)
145✔
417
{
418
    switch (component_id) {
145✔
419
        case MAV_COMP_ID_AUTOPILOT1:
60✔
420
            return "Autopilot";
60✔
421
        case MAV_COMP_ID_CAMERA:
9✔
422
            return "Camera 1";
9✔
423
        case MAV_COMP_ID_CAMERA2:
×
424
            return "Camera 2";
×
425
        case MAV_COMP_ID_CAMERA3:
×
426
            return "Camera 3";
×
427
        case MAV_COMP_ID_CAMERA4:
×
428
            return "Camera 4";
×
429
        case MAV_COMP_ID_CAMERA5:
×
430
            return "Camera 5";
×
431
        case MAV_COMP_ID_CAMERA6:
×
432
            return "Camera 6";
×
433
        case MAV_COMP_ID_GIMBAL:
×
434
            return "Gimbal";
×
435
        case MAV_COMP_ID_MISSIONPLANNER:
70✔
436
            return "Ground station";
70✔
437
        case MAV_COMP_ID_ONBOARD_COMPUTER:
1✔
438
            return "Companion Computer";
1✔
439
        case MAV_COMP_ID_WINCH:
×
440
            return "Winch";
×
441
        default:
5✔
442
            return "Unsupported component";
5✔
443
    }
444
}
445

446
ComponentType SystemImpl::component_type(uint8_t component_id)
289✔
447
{
448
    switch (component_id) {
289✔
449
        case MAV_COMP_ID_AUTOPILOT1:
119✔
450
            return ComponentType::Autopilot;
119✔
451
        case MAV_COMP_ID_MISSIONPLANNER:
140✔
452
            return ComponentType::GroundStation;
140✔
453
        case MAV_COMP_ID_ONBOARD_COMPUTER:
2✔
454
        case MAV_COMP_ID_ONBOARD_COMPUTER2:
455
        case MAV_COMP_ID_ONBOARD_COMPUTER3:
456
        case MAV_COMP_ID_ONBOARD_COMPUTER4:
457
            return ComponentType::CompanionComputer;
2✔
458
        case MAV_COMP_ID_CAMERA:
18✔
459
        case MAV_COMP_ID_CAMERA2:
460
        case MAV_COMP_ID_CAMERA3:
461
        case MAV_COMP_ID_CAMERA4:
462
        case MAV_COMP_ID_CAMERA5:
463
        case MAV_COMP_ID_CAMERA6:
464
            return ComponentType::Camera;
18✔
465
        case MAV_COMP_ID_GIMBAL:
×
466
            return ComponentType::Gimbal;
×
467
        case MAV_COMP_ID_ODID_TXRX_1:
×
468
        case MAV_COMP_ID_ODID_TXRX_2:
469
        case MAV_COMP_ID_ODID_TXRX_3:
470
            return ComponentType::RemoteId;
×
471
        default:
10✔
472
            return ComponentType::Custom;
10✔
473
    }
474
}
475

476
void SystemImpl::add_new_component(uint8_t component_id)
4,848✔
477
{
478
    if (component_id == 0) {
4,848✔
479
        return;
×
480
    }
481

482
    bool is_new_component = false;
4,848✔
483
    {
484
        std::lock_guard<std::mutex> lock(_components_mutex);
4,848✔
485
        auto res_pair = _components.insert(component_id);
4,861✔
486
        is_new_component = res_pair.second;
4,852✔
487
    }
4,852✔
488

489
    if (is_new_component) {
4,859✔
490
        _component_discovered_callbacks.queue(
145✔
491
            component_type(component_id), [this](const auto& func) { call_user_callback(func); });
×
492
        _component_discovered_id_callbacks.queue(
145✔
493
            component_type(component_id), component_id, [this](const auto& func) {
×
494
                call_user_callback(func);
×
495
            });
×
496
        LogDebug() << "Component " << component_name(component_id)
290✔
497
                   << " (component ID: " << int(component_id) << ") added.";
145✔
498
    }
499
}
500

501
size_t SystemImpl::total_components() const
×
502
{
503
    std::lock_guard<std::mutex> lock(_components_mutex);
×
504
    return _components.size();
×
505
}
×
506

507
System::ComponentDiscoveredHandle
508
SystemImpl::subscribe_component_discovered(const System::ComponentDiscoveredCallback& callback)
×
509
{
510
    const auto handle = _component_discovered_callbacks.subscribe(callback);
×
511

512
    if (total_components() > 0) {
×
513
        std::lock_guard<std::mutex> components_lock(_components_mutex);
×
514
        for (const auto& elem : _components) {
×
515
            _component_discovered_callbacks.queue(
×
516
                component_type(elem), [this](const auto& func) { call_user_callback(func); });
×
517
        }
518
    }
×
519
    return handle;
×
520
}
521

522
void SystemImpl::unsubscribe_component_discovered(System::ComponentDiscoveredHandle handle)
×
523
{
524
    _component_discovered_callbacks.unsubscribe(handle);
×
525
}
×
526

527
System::ComponentDiscoveredIdHandle
528
SystemImpl::subscribe_component_discovered_id(const System::ComponentDiscoveredIdCallback& callback)
×
529
{
530
    const auto handle = _component_discovered_id_callbacks.subscribe(callback);
×
531

532
    if (total_components() > 0) {
×
533
        std::lock_guard<std::mutex> components_lock(_components_mutex);
×
534
        for (const auto& elem : _components) {
×
535
            _component_discovered_id_callbacks.queue(
×
536
                component_type(elem), elem, [this](const auto& func) { call_user_callback(func); });
×
537
        }
538
    }
×
539
    return handle;
×
540
}
541

542
void SystemImpl::unsubscribe_component_discovered_id(System::ComponentDiscoveredIdHandle handle)
×
543
{
544
    _component_discovered_id_callbacks.unsubscribe(handle);
×
545
}
×
546

547
bool SystemImpl::is_standalone() const
×
548
{
549
    return !has_autopilot();
×
550
}
551

552
bool SystemImpl::has_autopilot() const
261✔
553
{
554
    return get_autopilot_id() != uint8_t(0);
261✔
555
}
556

557
bool SystemImpl::is_autopilot(uint8_t comp_id)
×
558
{
559
    return comp_id == MAV_COMP_ID_AUTOPILOT1;
×
560
}
561

562
bool SystemImpl::is_camera(uint8_t comp_id)
9✔
563
{
564
    return (comp_id >= MAV_COMP_ID_CAMERA) && (comp_id <= MAV_COMP_ID_CAMERA6);
9✔
565
}
566

567
bool SystemImpl::has_camera(int camera_id) const
9✔
568
{
569
    std::lock_guard<std::mutex> lock(_components_mutex);
9✔
570
    int camera_comp_id = (camera_id == -1) ? camera_id : (MAV_COMP_ID_CAMERA + camera_id);
9✔
571

572
    if (camera_comp_id == -1) { // Check whether the system has any camera.
9✔
573
        if (std::any_of(_components.begin(), _components.end(), is_camera)) {
9✔
574
            return true;
9✔
575
        }
576
    } else { // Look for the camera whose id is `camera_id`.
577
        for (auto compid : _components) {
×
578
            if (compid == camera_comp_id) {
×
579
                return true;
×
580
            }
581
        }
582
    }
583
    return false;
×
584
}
9✔
585

586
bool SystemImpl::has_gimbal() const
×
587
{
588
    return get_gimbal_id() == MAV_COMP_ID_GIMBAL;
×
589
}
590

591
bool SystemImpl::send_message(mavlink_message_t& message)
×
592
{
593
    return _mavsdk_impl.send_message(message);
×
594
}
595

596
bool SystemImpl::queue_message(
848✔
597
    std::function<mavlink_message_t(MavlinkAddress mavlink_address, uint8_t channel)> fun)
598
{
599
    return _mavsdk_impl.default_server_component_impl().queue_message(fun);
848✔
600
}
601

602
void SystemImpl::send_autopilot_version_request()
63✔
603
{
604
    mavlink_request_message().request(
63✔
605
        MAVLINK_MSG_ID_AUTOPILOT_VERSION, MAV_COMP_ID_AUTOPILOT1, nullptr);
606
}
63✔
607

608
void SystemImpl::set_connected()
356✔
609
{
610
    bool enable_needed = false;
356✔
611
    {
612
        if (!_connected) {
356✔
613
            {
614
                std::lock_guard<std::mutex> lock(_components_mutex);
148✔
615
                if (!_components.empty()) {
148✔
616
                    LogDebug() << "Discovered " << _components.size()
296✔
617
                               << (_components.size() == 1 ? " component" : " components");
148✔
618
                }
619
            }
148✔
620

621
            _connected = true;
148✔
622

623
            // Only send heartbeats if we're not shutting down
624
            if (!_should_exit) {
148✔
625
                // We call this later to avoid deadlocks on creating the server components.
626
                _mavsdk_impl.call_user_callback([this]() {
296✔
627
                    // Send a heartbeat back immediately.
628
                    _mavsdk_impl.start_sending_heartbeats();
629
                });
630
            }
631

632
            _heartbeat_timeout_cookie = register_timeout_handler(
147✔
633
                [this] { heartbeats_timed_out(); }, _mavsdk_impl.heartbeat_timeout_s());
155✔
634

635
            enable_needed = true;
148✔
636

637
            // Queue callbacks without holding any locks to avoid deadlocks
638
            _is_connected_callbacks.queue(
148✔
639
                true, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
640

641
        } else if (_connected) {
210✔
642
            refresh_timeout_handler(_heartbeat_timeout_cookie);
207✔
643
        }
644
        // If not yet connected there is nothing to do
645
    }
646

647
    if (enable_needed) {
360✔
648
        // Notify about the new system without holding any locks
649
        _mavsdk_impl.notify_on_discover();
148✔
650

651
        if (has_autopilot()) {
148✔
652
            send_autopilot_version_request();
63✔
653
        }
654

655
        // Enable plugins
656
        std::vector<PluginImplBase*> plugin_impls_to_enable;
148✔
657
        {
658
            std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
147✔
659
            plugin_impls_to_enable = _plugin_impls;
148✔
660
        }
147✔
661

662
        for (auto plugin_impl : plugin_impls_to_enable) {
152✔
663
            plugin_impl->enable();
4✔
664
        }
665
    }
148✔
666
}
360✔
667

668
void SystemImpl::set_disconnected()
7✔
669
{
670
    {
671
        // This might not be needed because this is probably called from the triggered
672
        // timeout anyway, but it should also do no harm.
673
        // unregister_timeout_handler(_heartbeat_timeout_cookie);
674
        //_heartbeat_timeout_cookie = nullptr;
675

676
        _connected = false;
7✔
677
        _is_connected_callbacks.queue(
7✔
678
            false, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
679
    }
680
    _mavsdk_impl.notify_on_timeout();
7✔
681

682
    _mavsdk_impl.stop_sending_heartbeats();
7✔
683

684
    {
685
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
7✔
686
        for (auto plugin_impl : _plugin_impls) {
11✔
687
            plugin_impl->disable();
4✔
688
        }
689
    }
7✔
690
}
7✔
691

692
uint8_t SystemImpl::get_system_id() const
816✔
693
{
694
    return _target_address.system_id;
816✔
695
}
696

697
std::vector<uint8_t> SystemImpl::component_ids() const
12✔
698
{
699
    std::lock_guard<std::mutex> lock(_components_mutex);
12✔
700
    return std::vector<uint8_t>{_components.begin(), _components.end()};
12✔
701
}
12✔
702

703
void SystemImpl::set_system_id(uint8_t system_id)
×
704
{
705
    _target_address.system_id = system_id;
×
706
}
×
707

708
uint8_t SystemImpl::get_own_system_id() const
1,460✔
709
{
710
    return _mavsdk_impl.get_own_system_id();
1,460✔
711
}
712

713
uint8_t SystemImpl::get_own_component_id() const
1,440✔
714
{
715
    return _mavsdk_impl.get_own_component_id();
1,440✔
716
}
717

718
MAV_TYPE SystemImpl::get_vehicle_type() const
×
719
{
720
    return _vehicle_type;
×
721
}
722

723
Vehicle SystemImpl::vehicle() const
×
724
{
725
    return to_vehicle_from_mav_type(_vehicle_type);
×
726
}
727

728
uint8_t SystemImpl::get_own_mav_type() const
×
729
{
730
    return _mavsdk_impl.get_mav_type();
×
731
}
732

733
MavlinkParameterClient::Result SystemImpl::set_param(
×
734
    const std::string& name,
735
    ParamValue value,
736
    std::optional<uint8_t> maybe_component_id,
737
    bool extended)
738
{
739
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
740
        ->set_param(name, value);
×
741
}
742

743
MavlinkParameterClient::Result SystemImpl::set_param_float(
2✔
744
    const std::string& name, float value, std::optional<uint8_t> maybe_component_id, bool extended)
745
{
746
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
747
        ->set_param_float(name, value);
4✔
748
}
749

750
MavlinkParameterClient::Result SystemImpl::set_param_int(
2✔
751
    const std::string& name,
752
    int32_t value,
753
    std::optional<uint8_t> maybe_component_id,
754
    bool extended)
755
{
756
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
757
        ->set_param_int(name, value);
4✔
758
}
759

760
MavlinkParameterClient::Result SystemImpl::set_param_custom(
2✔
761
    const std::string& name, const std::string& value, std::optional<uint8_t> maybe_component_id)
762
{
763
    return param_sender(maybe_component_id.has_value() ? maybe_component_id.value() : 1, true)
4✔
764
        ->set_param_custom(name, value);
4✔
765
}
766

767
std::pair<MavlinkParameterClient::Result, std::map<std::string, ParamValue>>
768
SystemImpl::get_all_params(std::optional<uint8_t> maybe_component_id, bool extended)
5✔
769
{
770
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
771
        ->get_all_params();
10✔
772
}
773

774
void SystemImpl::set_param_async(
3✔
775
    const std::string& name,
776
    ParamValue value,
777
    const SetParamCallback& callback,
778
    const void* cookie,
779
    std::optional<uint8_t> maybe_component_id,
780
    bool extended)
781
{
782
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
3✔
783
        ->set_param_async(name, value, callback, cookie);
6✔
784
}
3✔
785

786
void SystemImpl::set_param_float_async(
×
787
    const std::string& name,
788
    float value,
789
    const SetParamCallback& callback,
790
    const void* cookie,
791
    std::optional<uint8_t> maybe_component_id,
792
    bool extended)
793
{
794
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
795
        ->set_param_float_async(name, value, callback, cookie);
×
796
}
×
797

798
void SystemImpl::set_param_int_async(
×
799
    const std::string& name,
800
    int32_t value,
801
    const SetParamCallback& callback,
802
    const void* cookie,
803
    std::optional<uint8_t> maybe_component_id,
804
    bool extended)
805
{
806
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
807
        ->set_param_int_async(name, value, callback, cookie);
×
808
}
×
809

810
std::pair<MavlinkParameterClient::Result, float> SystemImpl::get_param_float(
8✔
811
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
812
{
813
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
8✔
814
        ->get_param_float(name);
16✔
815
}
816

817
std::pair<MavlinkParameterClient::Result, int> SystemImpl::get_param_int(
8✔
818
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
819
{
820
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
8✔
821
        ->get_param_int(name);
16✔
822
}
823

824
std::pair<MavlinkParameterClient::Result, std::string>
825
SystemImpl::get_param_custom(const std::string& name, std::optional<uint8_t> maybe_component_id)
4✔
826
{
827
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, true)
8✔
828
        ->get_param_custom(name);
8✔
829
}
830

831
void SystemImpl::get_param_async(
×
832
    const std::string& name,
833
    ParamValue value,
834
    const GetParamAnyCallback& callback,
835
    const void* cookie,
836
    std::optional<uint8_t> maybe_component_id,
837
    bool extended)
838
{
839
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
840
        ->get_param_async(name, value, callback, cookie);
×
841
}
×
842

843
void SystemImpl::get_param_float_async(
×
844
    const std::string& name,
845
    const GetParamFloatCallback& callback,
846
    const void* cookie,
847
    std::optional<uint8_t> maybe_component_id,
848
    bool extended)
849
{
850
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
851
        ->get_param_float_async(name, callback, cookie);
×
852
}
×
853

854
void SystemImpl::get_param_int_async(
×
855
    const std::string& name,
856
    const GetParamIntCallback& callback,
857
    const void* cookie,
858
    std::optional<uint8_t> maybe_component_id,
859
    bool extended)
860
{
861
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
862
        ->get_param_int_async(name, callback, cookie);
×
863
}
×
864

865
void SystemImpl::get_param_custom_async(
×
866
    const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
867
{
868
    param_sender(1, false)->get_param_custom_async(name, callback, cookie);
×
869
}
×
870

871
void SystemImpl::cancel_all_param(const void* cookie)
9✔
872
{
873
    UNUSED(cookie);
9✔
874
    // FIXME: this currently crashes on destruction
875
    // param_sender(1, false)->cancel_all_param(cookie);
876
}
9✔
877

878
MavlinkCommandSender::Result
879
SystemImpl::set_flight_mode(FlightMode system_mode, uint8_t component_id)
×
880
{
881
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
882
        make_command_flight_mode(system_mode, component_id);
×
883

884
    if (result.first != MavlinkCommandSender::Result::Success) {
×
885
        return result.first;
×
886
    }
887

888
    return send_command(result.second);
×
889
}
890

891
void SystemImpl::set_flight_mode_async(
×
892
    FlightMode system_mode, const CommandResultCallback& callback, uint8_t component_id)
893
{
894
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
895
        make_command_flight_mode(system_mode, component_id);
×
896

897
    if (result.first != MavlinkCommandSender::Result::Success) {
×
898
        if (callback) {
×
899
            callback(result.first, NAN);
×
900
        }
901
        return;
×
902
    }
903

904
    send_command_async(result.second, callback);
×
905
}
906

907
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
908
SystemImpl::make_command_flight_mode(FlightMode flight_mode, uint8_t component_id)
×
909
{
910
    if (_autopilot == Autopilot::ArduPilot) {
×
911
        return make_command_ardupilot_mode(flight_mode, component_id);
×
912
    } else {
913
        return make_command_px4_mode(flight_mode, component_id);
×
914
    }
915
}
916

917
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
918
SystemImpl::make_command_ardupilot_mode(FlightMode flight_mode, uint8_t component_id)
×
919
{
920
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
921
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
922
    const uint8_t mode_type =
×
923
        MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
924

925
    MavlinkCommandSender::CommandLong command{};
×
926

927
    command.command = MAV_CMD_DO_SET_MODE;
×
928
    command.params.maybe_param1 = static_cast<float>(mode_type);
×
929

930
    switch (_vehicle_type) {
×
931
        case MAV_TYPE::MAV_TYPE_SURFACE_BOAT:
×
932
        case MAV_TYPE::MAV_TYPE_GROUND_ROVER: {
933
            const auto new_mode = flight_mode_to_ardupilot_rover_mode(flight_mode);
×
934
            if (new_mode == ardupilot::RoverMode::Unknown) {
×
935
                LogErr() << "Cannot translate flight mode to ArduPilot Rover mode.";
×
936
                MavlinkCommandSender::CommandLong empty_command{};
×
937
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
938
            } else {
939
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
940
            }
941
            break;
×
942
        }
943
        case MAV_TYPE::MAV_TYPE_FIXED_WING:
×
944
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
945
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
946
        case MAV_TYPE::MAV_TYPE_VTOL_TILTROTOR:
947
        case MAV_TYPE::MAV_TYPE_VTOL_FIXEDROTOR:
948
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER:
949
        case MAV_TYPE::MAV_TYPE_VTOL_TILTWING: {
950
            const auto new_mode = flight_mode_to_ardupilot_plane_mode(flight_mode);
×
951
            if (new_mode == ardupilot::PlaneMode::Unknown) {
×
952
                LogErr() << "Cannot translate flight mode to ArduPilot Plane mode.";
×
953
                MavlinkCommandSender::CommandLong empty_command{};
×
954
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
955
            } else {
956
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
957
            }
958
            break;
×
959
        }
960

961
        case MAV_TYPE::MAV_TYPE_QUADROTOR:
×
962
        case MAV_TYPE::MAV_TYPE_COAXIAL:
963
        case MAV_TYPE::MAV_TYPE_HELICOPTER:
964
        case MAV_TYPE::MAV_TYPE_HEXAROTOR:
965
        case MAV_TYPE::MAV_TYPE_OCTOROTOR:
966
        case MAV_TYPE::MAV_TYPE_TRICOPTER:
967
        case MAV_TYPE::MAV_TYPE_DODECAROTOR:
968
        case MAV_TYPE::MAV_TYPE_DECAROTOR: {
969
            const auto new_mode = flight_mode_to_ardupilot_copter_mode(flight_mode);
×
970
            if (new_mode == ardupilot::CopterMode::Unknown) {
×
971
                LogErr() << "Cannot translate flight mode to ArduPilot Copter mode.";
×
972
                MavlinkCommandSender::CommandLong empty_command{};
×
973
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
974
            } else {
975
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
976
            }
977
            break;
×
978
        }
979

980
        default:
×
981
            LogErr() << "Cannot translate flight mode to ArduPilot mode, for MAV_TYPE: "
×
982
                     << _vehicle_type;
×
983
            MavlinkCommandSender::CommandLong empty_command{};
×
984
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
985
    }
986
    command.target_component_id = component_id;
×
987

988
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
989
}
990
ardupilot::RoverMode SystemImpl::flight_mode_to_ardupilot_rover_mode(FlightMode flight_mode)
×
991
{
992
    switch (flight_mode) {
×
993
        case FlightMode::Mission:
×
994
            return ardupilot::RoverMode::Auto;
×
995
        case FlightMode::Acro:
×
996
            return ardupilot::RoverMode::Acro;
×
997
        case FlightMode::Hold:
×
998
            return ardupilot::RoverMode::Hold;
×
999
        case FlightMode::ReturnToLaunch:
×
1000
            return ardupilot::RoverMode::RTL;
×
1001
        case FlightMode::Manual:
×
1002
            return ardupilot::RoverMode::Manual;
×
1003
        case FlightMode::FollowMe:
×
1004
            return ardupilot::RoverMode::Follow;
×
1005
        case FlightMode::Offboard:
×
1006
            return ardupilot::RoverMode::Guided;
×
1007
        case FlightMode::Unknown:
×
1008
        case FlightMode::Ready:
1009
        case FlightMode::Takeoff:
1010
        case FlightMode::Land:
1011
        case FlightMode::Altctl:
1012
        case FlightMode::Posctl:
1013
        case FlightMode::Rattitude:
1014
        case FlightMode::Stabilized:
1015
        default:
1016
            return ardupilot::RoverMode::Unknown;
×
1017
    }
1018
}
1019
ardupilot::CopterMode SystemImpl::flight_mode_to_ardupilot_copter_mode(FlightMode flight_mode)
×
1020
{
1021
    switch (flight_mode) {
×
1022
        case FlightMode::Mission:
×
1023
            return ardupilot::CopterMode::Auto;
×
1024
        case FlightMode::Acro:
×
1025
            return ardupilot::CopterMode::Acro;
×
1026
        case FlightMode::Hold:
×
1027
            return ardupilot::CopterMode::Loiter;
×
1028
        case FlightMode::ReturnToLaunch:
×
1029
            return ardupilot::CopterMode::Rtl;
×
1030
        case FlightMode::Land:
×
1031
            return ardupilot::CopterMode::Land;
×
1032
        case FlightMode::Manual:
×
1033
            return ardupilot::CopterMode::Stabilize;
×
1034
        case FlightMode::FollowMe:
×
1035
            return ardupilot::CopterMode::Follow;
×
1036
        case FlightMode::Offboard:
×
1037
            return ardupilot::CopterMode::Guided;
×
1038
        case FlightMode::Altctl:
×
1039
            return ardupilot::CopterMode::AltHold;
×
1040
        case FlightMode::Posctl:
×
1041
            return ardupilot::CopterMode::PosHold;
×
1042
        case FlightMode::Stabilized:
×
1043
            return ardupilot::CopterMode::Stabilize;
×
1044
        case FlightMode::Unknown:
×
1045
        case FlightMode::Ready:
1046
        case FlightMode::Takeoff:
1047
        case FlightMode::Rattitude:
1048
        default:
1049
            return ardupilot::CopterMode::Unknown;
×
1050
    }
1051
}
1052
ardupilot::PlaneMode SystemImpl::flight_mode_to_ardupilot_plane_mode(FlightMode flight_mode)
×
1053
{
1054
    switch (flight_mode) {
×
1055
        case FlightMode::Mission:
×
1056
            return ardupilot::PlaneMode::Auto;
×
1057
        case FlightMode::Acro:
×
1058
            return ardupilot::PlaneMode::Acro;
×
1059
        case FlightMode::Hold:
×
1060
            return ardupilot::PlaneMode::Loiter;
×
1061
        case FlightMode::ReturnToLaunch:
×
1062
            return ardupilot::PlaneMode::Rtl;
×
1063
        case FlightMode::Manual:
×
1064
            return ardupilot::PlaneMode::Manual;
×
1065
        case FlightMode::FBWA:
×
1066
            return ardupilot::PlaneMode::Fbwa;
×
1067
        case FlightMode::FBWB:
×
1068
            return ardupilot::PlaneMode::Fbwb;
×
1069
        case FlightMode::Stabilized:
×
1070
            return ardupilot::PlaneMode::Stabilize;
×
1071
        case FlightMode::Takeoff:
×
1072
            return ardupilot::PlaneMode::Takeoff;
×
1073
        case FlightMode::Offboard:
×
1074
            return ardupilot::PlaneMode::Guided;
×
1075
        case FlightMode::Unknown:
×
1076
            return ardupilot::PlaneMode::Unknown;
×
1077
        default:
×
1078
            return ardupilot::PlaneMode::Unknown;
×
1079
    }
1080
}
1081

1082
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
1083
SystemImpl::make_command_px4_mode(FlightMode flight_mode, uint8_t component_id)
×
1084
{
1085
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
1086
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
1087

1088
    const uint8_t mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
1089

1090
    // Note: the safety flag is not needed in future versions of the PX4 Firmware
1091
    //       but want to be rather safe than sorry.
1092
    uint8_t custom_mode = px4::PX4_CUSTOM_MAIN_MODE_AUTO;
×
1093
    uint8_t custom_sub_mode = 0;
×
1094

1095
    switch (flight_mode) {
×
1096
        case FlightMode::Hold:
×
1097
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
×
1098
            break;
×
1099
        case FlightMode::ReturnToLaunch:
×
1100
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_RTL;
×
1101
            break;
×
1102
        case FlightMode::Takeoff:
×
1103
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
×
1104
            break;
×
1105
        case FlightMode::Land:
×
1106
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LAND;
×
1107
            break;
×
1108
        case FlightMode::Mission:
×
1109
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
×
1110
            break;
×
1111
        case FlightMode::FollowMe:
×
1112
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET;
×
1113
            break;
×
1114
        case FlightMode::Offboard:
×
1115
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_OFFBOARD;
×
1116
            break;
×
1117
        case FlightMode::Manual:
×
1118
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_MANUAL;
×
1119
            break;
×
1120
        case FlightMode::Posctl:
×
1121
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_POSCTL;
×
1122
            break;
×
1123
        case FlightMode::Altctl:
×
1124
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ALTCTL;
×
1125
            break;
×
1126
        case FlightMode::Rattitude:
×
1127
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_RATTITUDE;
×
1128
            break;
×
1129
        case FlightMode::Acro:
×
1130
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ACRO;
×
1131
            break;
×
1132
        case FlightMode::Stabilized:
×
1133
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_STABILIZED;
×
1134
            break;
×
1135
        default:
×
1136
            LogErr() << "Unknown Flight mode.";
×
1137
            MavlinkCommandSender::CommandLong empty_command{};
×
1138
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
1139
    }
1140

1141
    MavlinkCommandSender::CommandLong command{};
×
1142

1143
    command.command = MAV_CMD_DO_SET_MODE;
×
1144
    command.params.maybe_param1 = static_cast<float>(mode);
×
1145
    command.params.maybe_param2 = static_cast<float>(custom_mode);
×
1146
    command.params.maybe_param3 = static_cast<float>(custom_sub_mode);
×
1147
    command.target_component_id = component_id;
×
1148

1149
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
1150
}
1151

1152
FlightMode SystemImpl::get_flight_mode() const
9✔
1153
{
1154
    return _flight_mode;
9✔
1155
}
1156

1157
void SystemImpl::receive_float_param(
×
1158
    MavlinkParameterClient::Result result, ParamValue value, const GetParamFloatCallback& callback)
1159
{
1160
    if (callback) {
×
1161
        if (result == MavlinkParameterClient::Result::Success) {
×
1162
            callback(result, value.get<float>());
×
1163
        } else {
1164
            callback(result, NAN);
×
1165
        }
1166
    }
1167
}
×
1168

1169
void SystemImpl::receive_int_param(
×
1170
    MavlinkParameterClient::Result result, ParamValue value, const GetParamIntCallback& callback)
1171
{
1172
    if (callback) {
×
1173
        if (result == MavlinkParameterClient::Result::Success) {
×
1174
            callback(result, value.get<int32_t>());
×
1175
        } else {
1176
            callback(result, 0);
×
1177
        }
1178
    }
1179
}
×
1180

1181
uint8_t SystemImpl::get_autopilot_id() const
306✔
1182
{
1183
    std::lock_guard<std::mutex> lock(_components_mutex);
306✔
1184
    for (auto compid : _components)
405✔
1185
        if (compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
313✔
1186
            return compid;
214✔
1187
        }
1188
    // FIXME: Not sure what should be returned if autopilot is not found
1189
    return uint8_t(0);
92✔
1190
}
306✔
1191

1192
std::vector<uint8_t> SystemImpl::get_camera_ids() const
×
1193
{
1194
    std::lock_guard<std::mutex> lock(_components_mutex);
×
1195
    std::vector<uint8_t> camera_ids{};
×
1196

1197
    for (auto compid : _components)
×
1198
        if (compid >= MAV_COMP_ID_CAMERA && compid <= MAV_COMP_ID_CAMERA6) {
×
1199
            camera_ids.push_back(compid);
×
1200
        }
1201
    return camera_ids;
×
1202
}
×
1203

1204
uint8_t SystemImpl::get_gimbal_id() const
×
1205
{
1206
    std::lock_guard<std::mutex> lock(_components_mutex);
×
1207
    for (auto compid : _components)
×
1208
        if (compid == MAV_COMP_ID_GIMBAL) {
×
1209
            return compid;
×
1210
        }
1211
    return uint8_t(0);
×
1212
}
×
1213

1214
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandLong& command)
5✔
1215
{
1216
    {
1217
        std::lock_guard<std::mutex> lock(_components_mutex);
5✔
1218
        if (_target_address.system_id == 0 && _components.empty()) {
5✔
1219
            return MavlinkCommandSender::Result::NoSystem;
×
1220
        }
1221
    }
5✔
1222
    command.target_system_id = get_system_id();
5✔
1223
    return _command_sender.send_command(command);
5✔
1224
}
1225

1226
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandInt& command)
×
1227
{
1228
    {
1229
        std::lock_guard<std::mutex> lock(_components_mutex);
×
1230
        if (_target_address.system_id == 0 && _components.empty()) {
×
1231
            return MavlinkCommandSender::Result::NoSystem;
×
1232
        }
1233
    }
×
1234
    command.target_system_id = get_system_id();
×
1235
    return _command_sender.send_command(command);
×
1236
}
1237

1238
void SystemImpl::send_command_async(
7✔
1239
    MavlinkCommandSender::CommandLong command, const CommandResultCallback& callback)
1240
{
1241
    {
1242
        std::lock_guard<std::mutex> lock(_components_mutex);
7✔
1243
        if (_target_address.system_id == 0 && _components.empty()) {
7✔
1244
            if (callback) {
×
1245
                callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1246
            }
1247
            return;
×
1248
        }
1249
    }
7✔
1250
    command.target_system_id = get_system_id();
7✔
1251

1252
    _command_sender.queue_command_async(command, callback);
7✔
1253
}
1254

1255
void SystemImpl::send_command_async(
×
1256
    MavlinkCommandSender::CommandInt command, const CommandResultCallback& callback)
1257
{
1258
    {
1259
        std::lock_guard<std::mutex> lock(_components_mutex);
×
1260
        if (_target_address.system_id == 0 && _components.empty()) {
×
1261
            if (callback) {
×
1262
                callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1263
            }
1264
            return;
×
1265
        }
1266
    }
×
1267
    command.target_system_id = get_system_id();
×
1268

1269
    _command_sender.queue_command_async(command, callback);
×
1270
}
1271

1272
MavlinkCommandSender::Result
1273
SystemImpl::set_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
×
1274
{
1275
    MavlinkCommandSender::CommandLong command =
1276
        make_command_msg_rate(message_id, rate_hz, component_id);
×
1277
    return send_command(command);
×
1278
}
1279

1280
void SystemImpl::set_msg_rate_async(
1✔
1281
    uint16_t message_id,
1282
    double rate_hz,
1283
    const CommandResultCallback& callback,
1284
    uint8_t component_id)
1285
{
1286
    MavlinkCommandSender::CommandLong command =
1287
        make_command_msg_rate(message_id, rate_hz, component_id);
1✔
1288
    send_command_async(command, callback);
1✔
1289
}
1✔
1290

1291
MavlinkCommandSender::CommandLong
1292
SystemImpl::make_command_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
1✔
1293
{
1294
    MavlinkCommandSender::CommandLong command{};
1✔
1295

1296
    // 0 to request default rate, -1 to stop stream
1297

1298
    float interval_us = 0.0f;
1✔
1299

1300
    if (rate_hz > 0) {
1✔
1301
        interval_us = 1e6f / static_cast<float>(rate_hz);
1✔
1302
    } else if (rate_hz < 0) {
×
1303
        interval_us = -1.0f;
×
1304
    }
1305

1306
    command.command = MAV_CMD_SET_MESSAGE_INTERVAL;
1✔
1307
    command.params.maybe_param1 = static_cast<float>(message_id);
1✔
1308
    command.params.maybe_param2 = interval_us;
1✔
1309
    command.target_component_id = component_id;
1✔
1310

1311
    return command;
1✔
1312
}
1313

1314
void SystemImpl::register_plugin(PluginImplBase* plugin_impl)
82✔
1315
{
1316
    assert(plugin_impl);
82✔
1317

1318
    plugin_impl->init();
82✔
1319

1320
    {
1321
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
82✔
1322
        _plugin_impls.push_back(plugin_impl);
82✔
1323
    }
82✔
1324

1325
    // If we're connected already, let's enable it straightaway.
1326
    if (_connected) {
82✔
1327
        plugin_impl->enable();
82✔
1328
    }
1329
}
82✔
1330

1331
void SystemImpl::unregister_plugin(PluginImplBase* plugin_impl)
82✔
1332
{
1333
    assert(plugin_impl);
82✔
1334

1335
    plugin_impl->disable();
82✔
1336
    plugin_impl->deinit();
82✔
1337

1338
    // Remove first, so it won't get enabled/disabled anymore.
1339
    {
1340
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
82✔
1341
        auto found = std::find(_plugin_impls.begin(), _plugin_impls.end(), plugin_impl);
82✔
1342
        if (found != _plugin_impls.end()) {
82✔
1343
            _plugin_impls.erase(found);
82✔
1344
        }
1345
    }
82✔
1346
}
82✔
1347

1348
void SystemImpl::call_user_callback_located(
990✔
1349
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1350
{
1351
    _mavsdk_impl.call_user_callback_located(filename, linenumber, func);
990✔
1352
}
990✔
1353

1354
void SystemImpl::param_changed(const std::string& name)
×
1355
{
1356
    for (auto& callback : _param_changed_callbacks) {
×
1357
        callback.second(name);
×
1358
    }
1359
}
×
1360

1361
void SystemImpl::register_param_changed_handler(
×
1362
    const ParamChangedCallback& callback, const void* cookie)
1363
{
1364
    if (!callback) {
×
1365
        LogErr() << "No callback for param_changed_handler supplied.";
×
1366
        return;
×
1367
    }
1368

1369
    if (!cookie) {
×
1370
        LogErr() << "No callback for param_changed_handler supplied.";
×
1371
        return;
×
1372
    }
1373

1374
    _param_changed_callbacks[cookie] = callback;
×
1375
}
1376

1377
void SystemImpl::unregister_param_changed_handler(const void* cookie)
×
1378
{
1379
    auto it = _param_changed_callbacks.find(cookie);
×
1380
    if (it == _param_changed_callbacks.end()) {
×
1381
        LogWarn() << "param_changed_handler for cookie not found";
×
1382
        return;
×
1383
    }
1384
    _param_changed_callbacks.erase(it);
×
1385
}
1386

1387
Time& SystemImpl::get_time()
468✔
1388
{
1389
    return _mavsdk_impl.time;
468✔
1390
}
1391

1392
void SystemImpl::subscribe_param_float(
×
1393
    const std::string& name,
1394
    const MavlinkParameterClient::ParamFloatChangedCallback& callback,
1395
    const void* cookie)
1396
{
1397
    param_sender(1, false)->subscribe_param_float_changed(name, callback, cookie);
×
1398
}
×
1399

1400
void SystemImpl::subscribe_param_int(
×
1401
    const std::string& name,
1402
    const MavlinkParameterClient::ParamIntChangedCallback& callback,
1403
    const void* cookie)
1404
{
1405
    param_sender(1, false)->subscribe_param_int_changed(name, callback, cookie);
×
1406
}
×
1407
void SystemImpl::subscribe_param_custom(
×
1408
    const std::string& name,
1409
    const MavlinkParameterClient::ParamCustomChangedCallback& callback,
1410
    const void* cookie)
1411
{
1412
    param_sender(1, false)->subscribe_param_custom_changed(name, callback, cookie);
×
1413
}
×
1414

1415
MavlinkParameterClient* SystemImpl::param_sender(uint8_t component_id, bool extended)
92✔
1416
{
1417
    std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
92✔
1418

1419
    for (auto& entry : _mavlink_parameter_clients) {
94✔
1420
        if (entry.component_id == component_id && entry.extended == extended) {
82✔
1421
            return entry.parameter_client.get();
80✔
1422
        }
1423
    }
1424

1425
    _mavlink_parameter_clients.push_back(
12✔
1426
        {std::make_unique<MavlinkParameterClient>(
1427
             _mavsdk_impl.default_server_component_impl().sender(),
12✔
1428
             _mavlink_message_handler,
12✔
1429
             _mavsdk_impl.timeout_handler,
12✔
1430
             [this]() { return timeout_s(); },
76✔
1431
             [this]() { return autopilot(); },
42✔
1432
             get_system_id(),
12✔
1433
             component_id,
1434
             extended),
1435
         component_id,
1436
         extended});
1437

1438
    return _mavlink_parameter_clients.back().parameter_client.get();
12✔
1439
}
92✔
1440

1441
std::vector<Connection*> SystemImpl::get_connections() const
×
1442
{
1443
    return _mavsdk_impl.get_connections();
×
1444
}
1445

1446
mav::MessageSet& SystemImpl::get_message_set() const
23✔
1447
{
1448
    return _mavsdk_impl.get_message_set();
23✔
1449
}
1450

1451
bool SystemImpl::load_custom_xml_to_message_set(const std::string& xml_content)
6✔
1452
{
1453
    return _mavsdk_impl.load_custom_xml_to_message_set(xml_content);
6✔
1454
}
1455

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