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

mavlink / MAVSDK / 17058117207

19 Aug 2025 02:44AM UTC coverage: 47.258% (+0.8%) from 46.467%
17058117207

push

github

web-flow
Merge pull request #2638 from mavlink/pr-raw-connection

Add new JSON based interception API

379 of 416 new or added lines in 12 files covered. (91.11%)

19 existing lines in 2 files now uncovered.

16701 of 35340 relevant lines covered (47.26%)

443.76 hits per line

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

45.12
/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) :
119✔
25
    _mavsdk_impl(mavsdk_impl),
119✔
26
    _command_sender(*this),
119✔
27
    _timesync(*this),
119✔
28
    _ping(*this),
119✔
29
    _mission_transfer_client(
238✔
30
        _mavsdk_impl.default_server_component_impl().sender(),
119✔
31
        _mavlink_message_handler,
119✔
32
        _mavsdk_impl.timeout_handler,
119✔
33
        [this]() { return timeout_s(); },
1✔
34
        [this]() { return autopilot(); }),
1✔
35
    _mavlink_request_message(
119✔
36
        *this, _command_sender, _mavlink_message_handler, _mavsdk_impl.timeout_handler),
119✔
37
    _mavlink_ftp_client(*this),
119✔
38
    _mavlink_component_metadata(*this)
238✔
39
{
40
    if (const char* env_p = std::getenv("MAVSDK_MESSAGE_DEBUGGING")) {
119✔
41
        if (std::string(env_p) == "1") {
×
42
            _message_debugging = true;
×
43
        }
44
    }
45

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

49
SystemImpl::~SystemImpl()
119✔
50
{
51
    _should_exit = true;
119✔
52
    _mavlink_message_handler.unregister_all(this);
119✔
53
    unregister_all_libmav_message_handlers(this);
119✔
54

55
    unregister_timeout_handler(_heartbeat_timeout_cookie);
119✔
56

57
    if (_system_thread != nullptr) {
119✔
58
        _system_thread->join();
119✔
59
        delete _system_thread;
119✔
60
        _system_thread = nullptr;
119✔
61
    }
62
}
119✔
63

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

70
    _mavlink_message_handler.register_one(
119✔
71
        MAVLINK_MSG_ID_HEARTBEAT,
72
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
290✔
73
        this);
74

75
    _mavlink_message_handler.register_one(
119✔
76
        MAVLINK_MSG_ID_STATUSTEXT,
77
        [this](const mavlink_message_t& message) { process_statustext(message); },
3✔
78
        this);
79

80
    _mavlink_message_handler.register_one(
119✔
81
        MAVLINK_MSG_ID_AUTOPILOT_VERSION,
82
        [this](const mavlink_message_t& message) { process_autopilot_version(message); },
56✔
83
        this);
84

85
    add_new_component(comp_id);
119✔
86
}
119✔
87

88
bool SystemImpl::is_connected() const
58✔
89
{
90
    return _connected;
58✔
91
}
92

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

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

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

113
void SystemImpl::unregister_all_mavlink_message_handlers(const void* cookie)
493✔
114
{
115
    _mavlink_message_handler.unregister_all(cookie);
493✔
116
}
493✔
117

118
void SystemImpl::update_component_id_messages_handler(
×
119
    uint16_t msg_id, uint8_t component_id, const void* cookie)
120
{
121
    _mavlink_message_handler.update_component_id(msg_id, component_id, cookie);
×
122
}
×
123

124
void SystemImpl::process_libmav_message(const Mavsdk::MavlinkMessage& message)
2,272✔
125
{
126
    // Call all registered libmav message handlers
127
    std::lock_guard<std::mutex> lock(_libmav_message_handlers_mutex);
2,272✔
128

129
    if (_message_debugging) {
2,275✔
130
        LogDebug() << "SystemImpl::process_libmav_message: " << message.message_name
×
131
                   << ", registered handlers: " << _libmav_message_handlers.size();
×
132
    }
133

134
    for (const auto& handler : _libmav_message_handlers) {
2,295✔
135
        if (_message_debugging) {
20✔
136
            LogDebug() << "Checking handler for message: '" << handler.message_name << "' against '"
×
137
                       << message.message_name << "'";
×
138
        }
139
        // Check if message name matches (empty string means match all messages)
140
        if (!handler.message_name.empty() && handler.message_name != message.message_name) {
20✔
141
            if (_message_debugging) {
10✔
142
                LogDebug() << "Handler message name mismatch, skipping";
×
143
            }
144
            continue;
10✔
145
        }
146

147
        // Check if component ID matches (if specified)
148
        if (handler.component_id.has_value() &&
10✔
149
            handler.component_id.value() != message.component_id) {
×
150
            continue;
×
151
        }
152

153
        // Call the handler
154
        if (_message_debugging) {
10✔
155
            LogDebug() << "Calling libmav handler for: " << message.message_name;
×
156
        }
157
        if (handler.callback) {
10✔
158
            handler.callback(message);
10✔
159
        } else {
160
            LogWarn() << "Handler callback is null!";
×
161
        }
162
    }
163
}
2,272✔
164

165
void SystemImpl::register_libmav_message_handler(
8✔
166
    const std::string& message_name, const LibmavMessageCallback& callback, const void* cookie)
167
{
168
    std::lock_guard<std::mutex> lock(_libmav_message_handlers_mutex);
8✔
169
    if (_message_debugging) {
8✔
170
        LogDebug() << "Registering libmav handler for message: '" << message_name
×
171
                   << "', total handlers will be: " << (_libmav_message_handlers.size() + 1);
×
172
    }
173
    _libmav_message_handlers.push_back({message_name, callback, cookie, std::nullopt});
8✔
174
}
8✔
175

176
void SystemImpl::register_libmav_message_handler_with_compid(
×
177
    const std::string& message_name,
178
    uint8_t cmp_id,
179
    const LibmavMessageCallback& callback,
180
    const void* cookie)
181
{
182
    std::lock_guard<std::mutex> lock(_libmav_message_handlers_mutex);
×
183
    _libmav_message_handlers.push_back({message_name, callback, cookie, cmp_id});
×
184
}
×
185

186
void SystemImpl::unregister_libmav_message_handler(
8✔
187
    const std::string& message_name, const void* cookie)
188
{
189
    std::lock_guard<std::mutex> lock(_libmav_message_handlers_mutex);
8✔
190

191
    _libmav_message_handlers.erase(
16✔
192
        std::remove_if(
8✔
193
            _libmav_message_handlers.begin(),
194
            _libmav_message_handlers.end(),
195
            [&](const LibmavMessageHandler& handler) {
8✔
196
                return handler.message_name == message_name && handler.cookie == cookie;
8✔
197
            }),
198
        _libmav_message_handlers.end());
8✔
199
}
8✔
200

201
void SystemImpl::unregister_all_libmav_message_handlers(const void* cookie)
135✔
202
{
203
    std::lock_guard<std::mutex> lock(_libmav_message_handlers_mutex);
135✔
204

205
    _libmav_message_handlers.erase(
270✔
206
        std::remove_if(
135✔
207
            _libmav_message_handlers.begin(),
208
            _libmav_message_handlers.end(),
209
            [&](const LibmavMessageHandler& handler) { return handler.cookie == cookie; }),
16✔
210
        _libmav_message_handlers.end());
135✔
211
}
135✔
212

213
TimeoutHandler::Cookie
214
SystemImpl::register_timeout_handler(const std::function<void()>& callback, double duration_s)
1,131✔
215
{
216
    return _mavsdk_impl.timeout_handler.add(callback, duration_s);
1,131✔
217
}
218

219
void SystemImpl::refresh_timeout_handler(TimeoutHandler::Cookie cookie)
173✔
220
{
221
    _mavsdk_impl.timeout_handler.refresh(cookie);
173✔
222
}
173✔
223

224
void SystemImpl::unregister_timeout_handler(TimeoutHandler::Cookie cookie)
1,308✔
225
{
226
    _mavsdk_impl.timeout_handler.remove(cookie);
1,308✔
227
}
1,308✔
228

229
double SystemImpl::timeout_s() const
1,087✔
230
{
231
    return _mavsdk_impl.timeout_s();
1,087✔
232
}
233

234
void SystemImpl::enable_timesync()
×
235
{
236
    _timesync.enable();
×
237
}
×
238

239
System::IsConnectedHandle
240
SystemImpl::subscribe_is_connected(const System::IsConnectedCallback& callback)
×
241
{
242
    return _is_connected_callbacks.subscribe(callback);
×
243
}
244

245
void SystemImpl::unsubscribe_is_connected(System::IsConnectedHandle handle)
×
246
{
247
    _is_connected_callbacks.unsubscribe(handle);
×
248
}
×
249

250
void SystemImpl::process_mavlink_message(mavlink_message_t& message)
2,244✔
251
{
252
    _mavlink_message_handler.process_message(message);
2,244✔
253
}
2,249✔
254

255
CallEveryHandler::Cookie
256
SystemImpl::add_call_every(std::function<void()> callback, float interval_s)
33✔
257
{
258
    return _mavsdk_impl.call_every_handler.add(
66✔
259
        std::move(callback), static_cast<double>(interval_s));
66✔
260
}
261

262
void SystemImpl::change_call_every(float interval_s, CallEveryHandler::Cookie cookie)
×
263
{
264
    _mavsdk_impl.call_every_handler.change(static_cast<double>(interval_s), cookie);
×
265
}
×
266

267
void SystemImpl::reset_call_every(CallEveryHandler::Cookie cookie)
×
268
{
269
    _mavsdk_impl.call_every_handler.reset(cookie);
×
270
}
×
271

272
void SystemImpl::remove_call_every(CallEveryHandler::Cookie cookie)
33✔
273
{
274
    _mavsdk_impl.call_every_handler.remove(cookie);
33✔
275
}
33✔
276

277
void SystemImpl::register_statustext_handler(
6✔
278
    std::function<void(const MavlinkStatustextHandler::Statustext&)> callback, void* cookie)
279
{
280
    _statustext_handler_callbacks.push_back(StatustextCallback{std::move(callback), cookie});
6✔
281
}
6✔
282

283
void SystemImpl::unregister_statustext_handler(void* cookie)
6✔
284
{
285
    _statustext_handler_callbacks.erase(std::remove_if(
6✔
286
        _statustext_handler_callbacks.begin(),
287
        _statustext_handler_callbacks.end(),
288
        [&](const auto& entry) { return entry.cookie == cookie; }));
6✔
289
}
6✔
290

291
void SystemImpl::process_heartbeat(const mavlink_message_t& message)
291✔
292
{
293
    mavlink_heartbeat_t heartbeat;
294
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
291✔
295

296
    if (heartbeat.autopilot == MAV_AUTOPILOT_PX4) {
293✔
297
        _autopilot = Autopilot::Px4;
×
298
    } else if (heartbeat.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
293✔
299
        _autopilot = Autopilot::ArduPilot;
×
300
    }
301

302
    // Only set the vehicle type if the heartbeat is from an autopilot component
303
    // This check only works if the MAV_TYPE::MAV_TYPE_ENUM_END is actually the
304
    // last enumerator.
305
    if (MAV_TYPE::MAV_TYPE_ENUM_END < heartbeat.type) {
293✔
306
        LogErr() << "type received in HEARTBEAT was not recognized";
×
307
    } else {
308
        const auto new_vehicle_type = static_cast<MAV_TYPE>(heartbeat.type);
293✔
309
        if (heartbeat.autopilot != MAV_AUTOPILOT_INVALID && _vehicle_type != new_vehicle_type &&
293✔
310
            new_vehicle_type != MAV_TYPE_GENERIC) {
311
            LogWarn() << "Vehicle type changed (new type: " << static_cast<unsigned>(heartbeat.type)
×
312
                      << ", old type: " << static_cast<unsigned>(_vehicle_type) << ")";
×
313
            _vehicle_type = new_vehicle_type;
×
314
        }
315
    }
316

317
    if (message.compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
293✔
318
        _armed = (heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) != 0;
131✔
319
        _hitl_enabled = (heartbeat.base_mode & MAV_MODE_FLAG_HIL_ENABLED) != 0;
131✔
320
    }
321
    if (heartbeat.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
290✔
322
        _flight_mode =
×
323
            to_flight_mode_from_custom_mode(_autopilot, _vehicle_type, heartbeat.custom_mode);
324
    }
325

326
    set_connected();
290✔
327
}
291✔
328

329
void SystemImpl::process_statustext(const mavlink_message_t& message)
3✔
330
{
331
    mavlink_statustext_t statustext;
332
    mavlink_msg_statustext_decode(&message, &statustext);
3✔
333

334
    const auto maybe_result = _statustext_handler.process(statustext);
3✔
335

336
    if (maybe_result.has_value()) {
3✔
337
        LogDebug() << "MAVLink: "
3✔
338
                   << MavlinkStatustextHandler::severity_str(maybe_result.value().severity) << ": "
6✔
339
                   << maybe_result.value().text;
3✔
340

341
        for (const auto& entry : _statustext_handler_callbacks) {
6✔
342
            entry.callback(maybe_result.value());
3✔
343
        }
344
    }
345
}
3✔
346

347
void SystemImpl::process_autopilot_version(const mavlink_message_t& message)
56✔
348
{
349
    mavlink_autopilot_version_t autopilot_version;
350
    mavlink_msg_autopilot_version_decode(&message, &autopilot_version);
56✔
351

352
    _mission_transfer_client.set_int_messages_supported(
56✔
353
        autopilot_version.capabilities & MAV_PROTOCOL_CAPABILITY_MISSION_INT);
56✔
354
}
56✔
355

356
void SystemImpl::heartbeats_timed_out()
×
357
{
358
    LogInfo() << "heartbeats timed out";
×
359
    set_disconnected();
×
360
}
×
361

362
void SystemImpl::system_thread()
119✔
363
{
364
    SteadyTimePoint last_ping_time{};
119✔
365

366
    while (!_should_exit) {
12,162✔
367
        {
368
            std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
12,002✔
369
            for (auto& entry : _mavlink_parameter_clients) {
12,917✔
370
                entry.parameter_client->do_work();
943✔
371
            }
372
        }
11,912✔
373
        _command_sender.do_work();
12,001✔
374
        _timesync.do_work();
11,974✔
375
        _mission_transfer_client.do_work();
12,033✔
376
        _mavlink_ftp_client.do_work();
11,975✔
377

378
        if (_mavsdk_impl.time.elapsed_since_s(last_ping_time) >= SystemImpl::_ping_interval_s) {
11,976✔
379
            if (_connected && _autopilot != Autopilot::ArduPilot) {
121✔
380
                _ping.run_once();
12✔
381
            }
382
            last_ping_time = _mavsdk_impl.time.steady_time();
121✔
383
        }
384

385
        if (_connected) {
11,853✔
386
            // Work fairly fast if we're connected.
387
            std::this_thread::sleep_for(std::chrono::milliseconds(10));
11,810✔
388
        } else {
389
            // Be less aggressive when unconnected.
390
            std::this_thread::sleep_for(std::chrono::milliseconds(100));
109✔
391
        }
392
    }
393
}
85✔
394

395
std::string SystemImpl::component_name(uint8_t component_id)
122✔
396
{
397
    switch (component_id) {
122✔
398
        case MAV_COMP_ID_AUTOPILOT1:
48✔
399
            return "Autopilot";
48✔
400
        case MAV_COMP_ID_CAMERA:
9✔
401
            return "Camera 1";
9✔
402
        case MAV_COMP_ID_CAMERA2:
×
403
            return "Camera 2";
×
404
        case MAV_COMP_ID_CAMERA3:
×
405
            return "Camera 3";
×
406
        case MAV_COMP_ID_CAMERA4:
×
407
            return "Camera 4";
×
408
        case MAV_COMP_ID_CAMERA5:
×
409
            return "Camera 5";
×
410
        case MAV_COMP_ID_CAMERA6:
×
411
            return "Camera 6";
×
412
        case MAV_COMP_ID_GIMBAL:
×
413
            return "Gimbal";
×
414
        case MAV_COMP_ID_MISSIONPLANNER:
59✔
415
            return "Ground station";
59✔
416
        case MAV_COMP_ID_ONBOARD_COMPUTER:
1✔
417
            return "Companion Computer";
1✔
418
        case MAV_COMP_ID_WINCH:
×
419
            return "Winch";
×
420
        default:
5✔
421
            return "Unsupported component";
5✔
422
    }
423
}
424

425
ComponentType SystemImpl::component_type(uint8_t component_id)
244✔
426
{
427
    switch (component_id) {
244✔
428
        case MAV_COMP_ID_AUTOPILOT1:
96✔
429
            return ComponentType::Autopilot;
96✔
430
        case MAV_COMP_ID_MISSIONPLANNER:
118✔
431
            return ComponentType::GroundStation;
118✔
432
        case MAV_COMP_ID_ONBOARD_COMPUTER:
2✔
433
        case MAV_COMP_ID_ONBOARD_COMPUTER2:
434
        case MAV_COMP_ID_ONBOARD_COMPUTER3:
435
        case MAV_COMP_ID_ONBOARD_COMPUTER4:
436
            return ComponentType::CompanionComputer;
2✔
437
        case MAV_COMP_ID_CAMERA:
18✔
438
        case MAV_COMP_ID_CAMERA2:
439
        case MAV_COMP_ID_CAMERA3:
440
        case MAV_COMP_ID_CAMERA4:
441
        case MAV_COMP_ID_CAMERA5:
442
        case MAV_COMP_ID_CAMERA6:
443
            return ComponentType::Camera;
18✔
444
        case MAV_COMP_ID_GIMBAL:
×
445
            return ComponentType::Gimbal;
×
446
        case MAV_COMP_ID_ODID_TXRX_1:
×
447
        case MAV_COMP_ID_ODID_TXRX_2:
448
        case MAV_COMP_ID_ODID_TXRX_3:
449
            return ComponentType::RemoteId;
×
450
        default:
10✔
451
            return ComponentType::Custom;
10✔
452
    }
453
}
454

455
void SystemImpl::add_new_component(uint8_t component_id)
4,523✔
456
{
457
    if (component_id == 0) {
4,523✔
458
        return;
×
459
    }
460

461
    bool is_new_component = false;
4,523✔
462
    {
463
        std::lock_guard<std::mutex> lock(_components_mutex);
4,523✔
464
        auto res_pair = _components.insert(component_id);
4,522✔
465
        is_new_component = res_pair.second;
4,521✔
466
    }
4,521✔
467

468
    if (is_new_component) {
4,526✔
469
        _component_discovered_callbacks.queue(
122✔
470
            component_type(component_id), [this](const auto& func) { call_user_callback(func); });
×
471
        _component_discovered_id_callbacks.queue(
122✔
472
            component_type(component_id), component_id, [this](const auto& func) {
×
473
                call_user_callback(func);
×
474
            });
×
475
        LogDebug() << "Component " << component_name(component_id) << " (" << int(component_id)
244✔
476
                   << ") added.";
122✔
477
    }
478
}
479

480
size_t SystemImpl::total_components() const
×
481
{
NEW
482
    std::lock_guard<std::mutex> lock(_components_mutex);
×
UNCOV
483
    return _components.size();
×
UNCOV
484
}
×
485

486
System::ComponentDiscoveredHandle
487
SystemImpl::subscribe_component_discovered(const System::ComponentDiscoveredCallback& callback)
×
488
{
489
    const auto handle = _component_discovered_callbacks.subscribe(callback);
×
490

491
    if (total_components() > 0) {
×
NEW
492
        std::lock_guard<std::mutex> components_lock(_components_mutex);
×
493
        for (const auto& elem : _components) {
×
494
            _component_discovered_callbacks.queue(
×
495
                component_type(elem), [this](const auto& func) { call_user_callback(func); });
×
496
        }
UNCOV
497
    }
×
498
    return handle;
×
499
}
500

501
void SystemImpl::unsubscribe_component_discovered(System::ComponentDiscoveredHandle handle)
×
502
{
503
    _component_discovered_callbacks.unsubscribe(handle);
×
504
}
×
505

506
System::ComponentDiscoveredIdHandle
507
SystemImpl::subscribe_component_discovered_id(const System::ComponentDiscoveredIdCallback& callback)
×
508
{
509
    const auto handle = _component_discovered_id_callbacks.subscribe(callback);
×
510

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

521
void SystemImpl::unsubscribe_component_discovered_id(System::ComponentDiscoveredIdHandle handle)
×
522
{
523
    _component_discovered_id_callbacks.unsubscribe(handle);
×
524
}
×
525

526
bool SystemImpl::is_standalone() const
×
527
{
528
    return !has_autopilot();
×
529
}
530

531
bool SystemImpl::has_autopilot() const
214✔
532
{
533
    return get_autopilot_id() != uint8_t(0);
214✔
534
}
535

536
bool SystemImpl::is_autopilot(uint8_t comp_id)
×
537
{
538
    return comp_id == MAV_COMP_ID_AUTOPILOT1;
×
539
}
540

541
bool SystemImpl::is_camera(uint8_t comp_id)
9✔
542
{
543
    return (comp_id >= MAV_COMP_ID_CAMERA) && (comp_id <= MAV_COMP_ID_CAMERA6);
9✔
544
}
545

546
bool SystemImpl::has_camera(int camera_id) const
9✔
547
{
548
    std::lock_guard<std::mutex> lock(_components_mutex);
9✔
549
    int camera_comp_id = (camera_id == -1) ? camera_id : (MAV_COMP_ID_CAMERA + camera_id);
9✔
550

551
    if (camera_comp_id == -1) { // Check whether the system has any camera.
9✔
552
        if (std::any_of(_components.begin(), _components.end(), is_camera)) {
9✔
553
            return true;
9✔
554
        }
555
    } else { // Look for the camera whose id is `camera_id`.
556
        for (auto compid : _components) {
×
557
            if (compid == camera_comp_id) {
×
558
                return true;
×
559
            }
560
        }
561
    }
562
    return false;
×
563
}
9✔
564

565
bool SystemImpl::has_gimbal() const
×
566
{
567
    return get_gimbal_id() == MAV_COMP_ID_GIMBAL;
×
568
}
569

570
bool SystemImpl::send_message(mavlink_message_t& message)
×
571
{
572
    return _mavsdk_impl.send_message(message);
×
573
}
574

575
bool SystemImpl::queue_message(
799✔
576
    std::function<mavlink_message_t(MavlinkAddress mavlink_address, uint8_t channel)> fun)
577
{
578
    return _mavsdk_impl.default_server_component_impl().queue_message(fun);
799✔
579
}
580

581
void SystemImpl::send_autopilot_version_request()
48✔
582
{
583
    mavlink_request_message().request(
48✔
584
        MAVLINK_MSG_ID_AUTOPILOT_VERSION, MAV_COMP_ID_AUTOPILOT1, nullptr);
585
}
48✔
586

587
void SystemImpl::set_connected()
289✔
588
{
589
    bool enable_needed = false;
289✔
590
    {
591
        if (!_connected) {
289✔
592
            {
593
                std::lock_guard<std::mutex> lock(_components_mutex);
119✔
594
                if (!_components.empty()) {
119✔
595
                    LogDebug() << "Discovered " << _components.size() << " component(s)";
118✔
596
                }
597
            }
119✔
598

599
            _connected = true;
119✔
600

601
            // Only send heartbeats if we're not shutting down
602
            if (!_should_exit) {
119✔
603
                // We call this later to avoid deadlocks on creating the server components.
604
                _mavsdk_impl.call_user_callback([this]() {
238✔
605
                    // Send a heartbeat back immediately.
606
                    _mavsdk_impl.start_sending_heartbeats();
607
                });
608
            }
609

610
            _heartbeat_timeout_cookie =
119✔
611
                register_timeout_handler([this] { heartbeats_timed_out(); }, HEARTBEAT_TIMEOUT_S);
119✔
612

613
            enable_needed = true;
119✔
614

615
            // Queue callbacks without holding any locks to avoid deadlocks
616
            _is_connected_callbacks.queue(
119✔
617
                true, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
618

619
        } else if (_connected) {
168✔
620
            refresh_timeout_handler(_heartbeat_timeout_cookie);
171✔
621
        }
622
        // If not yet connected there is nothing to do
623
    }
624

625
    if (enable_needed) {
292✔
626
        // Notify about the new system without holding any locks
627
        _mavsdk_impl.notify_on_discover();
119✔
628

629
        if (has_autopilot()) {
119✔
630
            send_autopilot_version_request();
48✔
631
        }
632

633
        // Enable plugins
634
        std::vector<PluginImplBase*> plugin_impls_to_enable;
119✔
635
        {
636
            std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
118✔
637
            plugin_impls_to_enable = _plugin_impls;
119✔
638
        }
119✔
639

640
        for (auto plugin_impl : plugin_impls_to_enable) {
119✔
UNCOV
641
            plugin_impl->enable();
×
642
        }
643
    }
118✔
644
}
292✔
645

646
void SystemImpl::set_disconnected()
×
647
{
648
    {
649
        // This might not be needed because this is probably called from the triggered
650
        // timeout anyway, but it should also do no harm.
651
        // unregister_timeout_handler(_heartbeat_timeout_cookie);
652
        //_heartbeat_timeout_cookie = nullptr;
653

654
        _connected = false;
×
655
        _is_connected_callbacks.queue(
×
656
            false, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
657
    }
658
    _mavsdk_impl.notify_on_timeout();
×
659

660
    _mavsdk_impl.stop_sending_heartbeats();
×
661

662
    {
663
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
×
664
        for (auto plugin_impl : _plugin_impls) {
×
665
            plugin_impl->disable();
×
666
        }
667
    }
×
668
}
×
669

670
uint8_t SystemImpl::get_system_id() const
773✔
671
{
672
    return _target_address.system_id;
773✔
673
}
674

675
std::vector<uint8_t> SystemImpl::component_ids() const
7✔
676
{
677
    std::lock_guard<std::mutex> lock(_components_mutex);
7✔
678
    return std::vector<uint8_t>{_components.begin(), _components.end()};
7✔
679
}
7✔
680

681
void SystemImpl::set_system_id(uint8_t system_id)
×
682
{
683
    _target_address.system_id = system_id;
×
684
}
×
685

686
uint8_t SystemImpl::get_own_system_id() const
1,426✔
687
{
688
    return _mavsdk_impl.get_own_system_id();
1,426✔
689
}
690

691
uint8_t SystemImpl::get_own_component_id() const
1,406✔
692
{
693
    return _mavsdk_impl.get_own_component_id();
1,406✔
694
}
695

696
MAV_TYPE SystemImpl::get_vehicle_type() const
×
697
{
698
    return _vehicle_type;
×
699
}
700

701
Vehicle SystemImpl::vehicle() const
×
702
{
703
    return to_vehicle_from_mav_type(_vehicle_type);
×
704
}
705

706
uint8_t SystemImpl::get_own_mav_type() const
×
707
{
708
    return _mavsdk_impl.get_mav_type();
×
709
}
710

711
MavlinkParameterClient::Result SystemImpl::set_param(
×
712
    const std::string& name,
713
    ParamValue value,
714
    std::optional<uint8_t> maybe_component_id,
715
    bool extended)
716
{
717
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
718
        ->set_param(name, value);
×
719
}
720

721
MavlinkParameterClient::Result SystemImpl::set_param_float(
2✔
722
    const std::string& name, float value, std::optional<uint8_t> maybe_component_id, bool extended)
723
{
724
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
725
        ->set_param_float(name, value);
4✔
726
}
727

728
MavlinkParameterClient::Result SystemImpl::set_param_int(
2✔
729
    const std::string& name,
730
    int32_t value,
731
    std::optional<uint8_t> maybe_component_id,
732
    bool extended)
733
{
734
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
735
        ->set_param_int(name, value);
4✔
736
}
737

738
MavlinkParameterClient::Result SystemImpl::set_param_custom(
2✔
739
    const std::string& name, const std::string& value, std::optional<uint8_t> maybe_component_id)
740
{
741
    return param_sender(maybe_component_id.has_value() ? maybe_component_id.value() : 1, true)
4✔
742
        ->set_param_custom(name, value);
4✔
743
}
744

745
std::pair<MavlinkParameterClient::Result, std::map<std::string, ParamValue>>
746
SystemImpl::get_all_params(std::optional<uint8_t> maybe_component_id, bool extended)
4✔
747
{
748
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
4✔
749
        ->get_all_params();
8✔
750
}
751

752
void SystemImpl::set_param_async(
3✔
753
    const std::string& name,
754
    ParamValue value,
755
    const SetParamCallback& callback,
756
    const void* cookie,
757
    std::optional<uint8_t> maybe_component_id,
758
    bool extended)
759
{
760
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
3✔
761
        ->set_param_async(name, value, callback, cookie);
6✔
762
}
3✔
763

764
void SystemImpl::set_param_float_async(
×
765
    const std::string& name,
766
    float value,
767
    const SetParamCallback& callback,
768
    const void* cookie,
769
    std::optional<uint8_t> maybe_component_id,
770
    bool extended)
771
{
772
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
773
        ->set_param_float_async(name, value, callback, cookie);
×
774
}
×
775

776
void SystemImpl::set_param_int_async(
×
777
    const std::string& name,
778
    int32_t value,
779
    const SetParamCallback& callback,
780
    const void* cookie,
781
    std::optional<uint8_t> maybe_component_id,
782
    bool extended)
783
{
784
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
785
        ->set_param_int_async(name, value, callback, cookie);
×
786
}
×
787

788
std::pair<MavlinkParameterClient::Result, float> SystemImpl::get_param_float(
5✔
789
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
790
{
791
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
792
        ->get_param_float(name);
10✔
793
}
794

795
std::pair<MavlinkParameterClient::Result, int> SystemImpl::get_param_int(
5✔
796
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
797
{
798
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
799
        ->get_param_int(name);
10✔
800
}
801

802
std::pair<MavlinkParameterClient::Result, std::string>
803
SystemImpl::get_param_custom(const std::string& name, std::optional<uint8_t> maybe_component_id)
4✔
804
{
805
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, true)
8✔
806
        ->get_param_custom(name);
8✔
807
}
808

809
void SystemImpl::get_param_async(
×
810
    const std::string& name,
811
    ParamValue value,
812
    const GetParamAnyCallback& callback,
813
    const void* cookie,
814
    std::optional<uint8_t> maybe_component_id,
815
    bool extended)
816
{
817
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
818
        ->get_param_async(name, value, callback, cookie);
×
819
}
×
820

821
void SystemImpl::get_param_float_async(
×
822
    const std::string& name,
823
    const GetParamFloatCallback& callback,
824
    const void* cookie,
825
    std::optional<uint8_t> maybe_component_id,
826
    bool extended)
827
{
828
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
829
        ->get_param_float_async(name, callback, cookie);
×
830
}
×
831

832
void SystemImpl::get_param_int_async(
×
833
    const std::string& name,
834
    const GetParamIntCallback& 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_int_async(name, callback, cookie);
×
841
}
×
842

843
void SystemImpl::get_param_custom_async(
×
844
    const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
845
{
846
    param_sender(1, false)->get_param_custom_async(name, callback, cookie);
×
847
}
×
848

849
void SystemImpl::cancel_all_param(const void* cookie)
9✔
850
{
851
    UNUSED(cookie);
9✔
852
    // FIXME: this currently crashes on destruction
853
    // param_sender(1, false)->cancel_all_param(cookie);
854
}
9✔
855

856
MavlinkCommandSender::Result
857
SystemImpl::set_flight_mode(FlightMode system_mode, uint8_t component_id)
×
858
{
859
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
860
        make_command_flight_mode(system_mode, component_id);
×
861

862
    if (result.first != MavlinkCommandSender::Result::Success) {
×
863
        return result.first;
×
864
    }
865

866
    return send_command(result.second);
×
867
}
868

869
void SystemImpl::set_flight_mode_async(
×
870
    FlightMode system_mode, const CommandResultCallback& callback, uint8_t component_id)
871
{
872
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
873
        make_command_flight_mode(system_mode, component_id);
×
874

875
    if (result.first != MavlinkCommandSender::Result::Success) {
×
876
        if (callback) {
×
877
            callback(result.first, NAN);
×
878
        }
879
        return;
×
880
    }
881

882
    send_command_async(result.second, callback);
×
883
}
884

885
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
886
SystemImpl::make_command_flight_mode(FlightMode flight_mode, uint8_t component_id)
×
887
{
888
    if (_autopilot == Autopilot::ArduPilot) {
×
889
        return make_command_ardupilot_mode(flight_mode, component_id);
×
890
    } else {
891
        return make_command_px4_mode(flight_mode, component_id);
×
892
    }
893
}
894

895
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
896
SystemImpl::make_command_ardupilot_mode(FlightMode flight_mode, uint8_t component_id)
×
897
{
898
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
899
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
900
    const uint8_t mode_type =
×
901
        MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
902

903
    MavlinkCommandSender::CommandLong command{};
×
904

905
    command.command = MAV_CMD_DO_SET_MODE;
×
906
    command.params.maybe_param1 = static_cast<float>(mode_type);
×
907

908
    switch (_vehicle_type) {
×
909
        case MAV_TYPE::MAV_TYPE_SURFACE_BOAT:
×
910
        case MAV_TYPE::MAV_TYPE_GROUND_ROVER: {
911
            const auto new_mode = flight_mode_to_ardupilot_rover_mode(flight_mode);
×
912
            if (new_mode == ardupilot::RoverMode::Unknown) {
×
913
                LogErr() << "Cannot translate flight mode to ArduPilot Rover mode.";
×
914
                MavlinkCommandSender::CommandLong empty_command{};
×
915
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
916
            } else {
917
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
918
            }
919
            break;
×
920
        }
921
        case MAV_TYPE::MAV_TYPE_FIXED_WING:
×
922
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
923
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
924
        case MAV_TYPE::MAV_TYPE_VTOL_TILTROTOR:
925
        case MAV_TYPE::MAV_TYPE_VTOL_FIXEDROTOR:
926
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER:
927
        case MAV_TYPE::MAV_TYPE_VTOL_TILTWING: {
928
            const auto new_mode = flight_mode_to_ardupilot_plane_mode(flight_mode);
×
929
            if (new_mode == ardupilot::PlaneMode::Unknown) {
×
930
                LogErr() << "Cannot translate flight mode to ArduPilot Plane mode.";
×
931
                MavlinkCommandSender::CommandLong empty_command{};
×
932
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
933
            } else {
934
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
935
            }
936
            break;
×
937
        }
938

939
        case MAV_TYPE::MAV_TYPE_QUADROTOR:
×
940
        case MAV_TYPE::MAV_TYPE_COAXIAL:
941
        case MAV_TYPE::MAV_TYPE_HELICOPTER:
942
        case MAV_TYPE::MAV_TYPE_HEXAROTOR:
943
        case MAV_TYPE::MAV_TYPE_OCTOROTOR:
944
        case MAV_TYPE::MAV_TYPE_TRICOPTER:
945
        case MAV_TYPE::MAV_TYPE_DODECAROTOR:
946
        case MAV_TYPE::MAV_TYPE_DECAROTOR: {
947
            const auto new_mode = flight_mode_to_ardupilot_copter_mode(flight_mode);
×
948
            if (new_mode == ardupilot::CopterMode::Unknown) {
×
949
                LogErr() << "Cannot translate flight mode to ArduPilot Copter mode.";
×
950
                MavlinkCommandSender::CommandLong empty_command{};
×
951
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
952
            } else {
953
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
954
            }
955
            break;
×
956
        }
957

958
        default:
×
959
            LogErr() << "Cannot translate flight mode to ArduPilot mode, for MAV_TYPE: "
×
960
                     << _vehicle_type;
×
961
            MavlinkCommandSender::CommandLong empty_command{};
×
962
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
963
    }
964
    command.target_component_id = component_id;
×
965

966
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
967
}
968
ardupilot::RoverMode SystemImpl::flight_mode_to_ardupilot_rover_mode(FlightMode flight_mode)
×
969
{
970
    switch (flight_mode) {
×
971
        case FlightMode::Mission:
×
972
            return ardupilot::RoverMode::Auto;
×
973
        case FlightMode::Acro:
×
974
            return ardupilot::RoverMode::Acro;
×
975
        case FlightMode::Hold:
×
976
            return ardupilot::RoverMode::Hold;
×
977
        case FlightMode::ReturnToLaunch:
×
978
            return ardupilot::RoverMode::RTL;
×
979
        case FlightMode::Manual:
×
980
            return ardupilot::RoverMode::Manual;
×
981
        case FlightMode::FollowMe:
×
982
            return ardupilot::RoverMode::Follow;
×
983
        case FlightMode::Offboard:
×
984
            return ardupilot::RoverMode::Guided;
×
985
        case FlightMode::Unknown:
×
986
        case FlightMode::Ready:
987
        case FlightMode::Takeoff:
988
        case FlightMode::Land:
989
        case FlightMode::Altctl:
990
        case FlightMode::Posctl:
991
        case FlightMode::Rattitude:
992
        case FlightMode::Stabilized:
993
        default:
994
            return ardupilot::RoverMode::Unknown;
×
995
    }
996
}
997
ardupilot::CopterMode SystemImpl::flight_mode_to_ardupilot_copter_mode(FlightMode flight_mode)
×
998
{
999
    switch (flight_mode) {
×
1000
        case FlightMode::Mission:
×
1001
            return ardupilot::CopterMode::Auto;
×
1002
        case FlightMode::Acro:
×
1003
            return ardupilot::CopterMode::Acro;
×
1004
        case FlightMode::Hold:
×
1005
            return ardupilot::CopterMode::Loiter;
×
1006
        case FlightMode::ReturnToLaunch:
×
1007
            return ardupilot::CopterMode::Rtl;
×
1008
        case FlightMode::Land:
×
1009
            return ardupilot::CopterMode::Land;
×
1010
        case FlightMode::Manual:
×
1011
            return ardupilot::CopterMode::Stabilize;
×
1012
        case FlightMode::FollowMe:
×
1013
            return ardupilot::CopterMode::Follow;
×
1014
        case FlightMode::Offboard:
×
1015
            return ardupilot::CopterMode::Guided;
×
1016
        case FlightMode::Altctl:
×
1017
            return ardupilot::CopterMode::AltHold;
×
1018
        case FlightMode::Posctl:
×
1019
            return ardupilot::CopterMode::PosHold;
×
1020
        case FlightMode::Stabilized:
×
1021
            return ardupilot::CopterMode::Stabilize;
×
1022
        case FlightMode::Unknown:
×
1023
        case FlightMode::Ready:
1024
        case FlightMode::Takeoff:
1025
        case FlightMode::Rattitude:
1026
        default:
1027
            return ardupilot::CopterMode::Unknown;
×
1028
    }
1029
}
1030
ardupilot::PlaneMode SystemImpl::flight_mode_to_ardupilot_plane_mode(FlightMode flight_mode)
×
1031
{
1032
    switch (flight_mode) {
×
1033
        case FlightMode::Mission:
×
1034
            return ardupilot::PlaneMode::Auto;
×
1035
        case FlightMode::Acro:
×
1036
            return ardupilot::PlaneMode::Acro;
×
1037
        case FlightMode::Hold:
×
1038
            return ardupilot::PlaneMode::Loiter;
×
1039
        case FlightMode::ReturnToLaunch:
×
1040
            return ardupilot::PlaneMode::Rtl;
×
1041
        case FlightMode::Manual:
×
1042
            return ardupilot::PlaneMode::Manual;
×
1043
        case FlightMode::FBWA:
×
1044
            return ardupilot::PlaneMode::Fbwa;
×
1045
        case FlightMode::Stabilized:
×
1046
            return ardupilot::PlaneMode::Stabilize;
×
1047
        case FlightMode::Offboard:
×
1048
            return ardupilot::PlaneMode::Guided;
×
1049
        case FlightMode::Unknown:
×
1050
            return ardupilot::PlaneMode::Unknown;
×
1051
        default:
×
1052
            return ardupilot::PlaneMode::Unknown;
×
1053
    }
1054
}
1055

1056
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
1057
SystemImpl::make_command_px4_mode(FlightMode flight_mode, uint8_t component_id)
×
1058
{
1059
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
1060
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
1061

1062
    const uint8_t mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
1063

1064
    // Note: the safety flag is not needed in future versions of the PX4 Firmware
1065
    //       but want to be rather safe than sorry.
1066
    uint8_t custom_mode = px4::PX4_CUSTOM_MAIN_MODE_AUTO;
×
1067
    uint8_t custom_sub_mode = 0;
×
1068

1069
    switch (flight_mode) {
×
1070
        case FlightMode::Hold:
×
1071
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
×
1072
            break;
×
1073
        case FlightMode::ReturnToLaunch:
×
1074
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_RTL;
×
1075
            break;
×
1076
        case FlightMode::Takeoff:
×
1077
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
×
1078
            break;
×
1079
        case FlightMode::Land:
×
1080
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LAND;
×
1081
            break;
×
1082
        case FlightMode::Mission:
×
1083
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
×
1084
            break;
×
1085
        case FlightMode::FollowMe:
×
1086
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET;
×
1087
            break;
×
1088
        case FlightMode::Offboard:
×
1089
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_OFFBOARD;
×
1090
            break;
×
1091
        case FlightMode::Manual:
×
1092
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_MANUAL;
×
1093
            break;
×
1094
        case FlightMode::Posctl:
×
1095
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_POSCTL;
×
1096
            break;
×
1097
        case FlightMode::Altctl:
×
1098
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ALTCTL;
×
1099
            break;
×
1100
        case FlightMode::Rattitude:
×
1101
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_RATTITUDE;
×
1102
            break;
×
1103
        case FlightMode::Acro:
×
1104
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ACRO;
×
1105
            break;
×
1106
        case FlightMode::Stabilized:
×
1107
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_STABILIZED;
×
1108
            break;
×
1109
        default:
×
1110
            LogErr() << "Unknown Flight mode.";
×
1111
            MavlinkCommandSender::CommandLong empty_command{};
×
1112
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
1113
    }
1114

1115
    MavlinkCommandSender::CommandLong command{};
×
1116

1117
    command.command = MAV_CMD_DO_SET_MODE;
×
1118
    command.params.maybe_param1 = static_cast<float>(mode);
×
1119
    command.params.maybe_param2 = static_cast<float>(custom_mode);
×
1120
    command.params.maybe_param3 = static_cast<float>(custom_sub_mode);
×
1121
    command.target_component_id = component_id;
×
1122

1123
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
1124
}
1125

1126
FlightMode SystemImpl::get_flight_mode() const
9✔
1127
{
1128
    return _flight_mode;
9✔
1129
}
1130

1131
void SystemImpl::receive_float_param(
×
1132
    MavlinkParameterClient::Result result, ParamValue value, const GetParamFloatCallback& callback)
1133
{
1134
    if (callback) {
×
1135
        if (result == MavlinkParameterClient::Result::Success) {
×
1136
            callback(result, value.get<float>());
×
1137
        } else {
1138
            callback(result, NAN);
×
1139
        }
1140
    }
1141
}
×
1142

1143
void SystemImpl::receive_int_param(
×
1144
    MavlinkParameterClient::Result result, ParamValue value, const GetParamIntCallback& callback)
1145
{
1146
    if (callback) {
×
1147
        if (result == MavlinkParameterClient::Result::Success) {
×
1148
            callback(result, value.get<int32_t>());
×
1149
        } else {
1150
            callback(result, 0);
×
1151
        }
1152
    }
1153
}
×
1154

1155
uint8_t SystemImpl::get_autopilot_id() const
259✔
1156
{
1157
    std::lock_guard<std::mutex> lock(_components_mutex);
259✔
1158
    for (auto compid : _components)
344✔
1159
        if (compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
266✔
1160
            return compid;
181✔
1161
        }
1162
    // FIXME: Not sure what should be returned if autopilot is not found
1163
    return uint8_t(0);
78✔
1164
}
259✔
1165

1166
std::vector<uint8_t> SystemImpl::get_camera_ids() const
×
1167
{
NEW
1168
    std::lock_guard<std::mutex> lock(_components_mutex);
×
UNCOV
1169
    std::vector<uint8_t> camera_ids{};
×
1170

1171
    for (auto compid : _components)
×
1172
        if (compid >= MAV_COMP_ID_CAMERA && compid <= MAV_COMP_ID_CAMERA6) {
×
1173
            camera_ids.push_back(compid);
×
1174
        }
1175
    return camera_ids;
×
UNCOV
1176
}
×
1177

1178
uint8_t SystemImpl::get_gimbal_id() const
×
1179
{
NEW
1180
    std::lock_guard<std::mutex> lock(_components_mutex);
×
1181
    for (auto compid : _components)
×
1182
        if (compid == MAV_COMP_ID_GIMBAL) {
×
1183
            return compid;
×
1184
        }
1185
    return uint8_t(0);
×
UNCOV
1186
}
×
1187

1188
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandLong& command)
5✔
1189
{
1190
    {
1191
        std::lock_guard<std::mutex> lock(_components_mutex);
5✔
1192
        if (_target_address.system_id == 0 && _components.empty()) {
5✔
NEW
1193
            return MavlinkCommandSender::Result::NoSystem;
×
1194
        }
1195
    }
5✔
1196
    command.target_system_id = get_system_id();
5✔
1197
    return _command_sender.send_command(command);
5✔
1198
}
1199

1200
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandInt& command)
×
1201
{
1202
    {
NEW
1203
        std::lock_guard<std::mutex> lock(_components_mutex);
×
NEW
1204
        if (_target_address.system_id == 0 && _components.empty()) {
×
NEW
1205
            return MavlinkCommandSender::Result::NoSystem;
×
1206
        }
1207
    }
×
1208
    command.target_system_id = get_system_id();
×
1209
    return _command_sender.send_command(command);
×
1210
}
1211

1212
void SystemImpl::send_command_async(
7✔
1213
    MavlinkCommandSender::CommandLong command, const CommandResultCallback& callback)
1214
{
1215
    {
1216
        std::lock_guard<std::mutex> lock(_components_mutex);
7✔
1217
        if (_target_address.system_id == 0 && _components.empty()) {
7✔
NEW
1218
            if (callback) {
×
NEW
1219
                callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1220
            }
NEW
1221
            return;
×
1222
        }
1223
    }
7✔
1224
    command.target_system_id = get_system_id();
7✔
1225

1226
    _command_sender.queue_command_async(command, callback);
7✔
1227
}
1228

1229
void SystemImpl::send_command_async(
×
1230
    MavlinkCommandSender::CommandInt command, const CommandResultCallback& callback)
1231
{
1232
    {
NEW
1233
        std::lock_guard<std::mutex> lock(_components_mutex);
×
NEW
1234
        if (_target_address.system_id == 0 && _components.empty()) {
×
NEW
1235
            if (callback) {
×
NEW
1236
                callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1237
            }
NEW
1238
            return;
×
1239
        }
1240
    }
×
UNCOV
1241
    command.target_system_id = get_system_id();
×
1242

1243
    _command_sender.queue_command_async(command, callback);
×
1244
}
1245

1246
MavlinkCommandSender::Result
1247
SystemImpl::set_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
×
1248
{
1249
    MavlinkCommandSender::CommandLong command =
1250
        make_command_msg_rate(message_id, rate_hz, component_id);
×
1251
    return send_command(command);
×
1252
}
1253

1254
void SystemImpl::set_msg_rate_async(
1✔
1255
    uint16_t message_id,
1256
    double rate_hz,
1257
    const CommandResultCallback& callback,
1258
    uint8_t component_id)
1259
{
1260
    MavlinkCommandSender::CommandLong command =
1261
        make_command_msg_rate(message_id, rate_hz, component_id);
1✔
1262
    send_command_async(command, callback);
1✔
1263
}
1✔
1264

1265
MavlinkCommandSender::CommandLong
1266
SystemImpl::make_command_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
1✔
1267
{
1268
    MavlinkCommandSender::CommandLong command{};
1✔
1269

1270
    // 0 to request default rate, -1 to stop stream
1271

1272
    float interval_us = 0.0f;
1✔
1273

1274
    if (rate_hz > 0) {
1✔
1275
        interval_us = 1e6f / static_cast<float>(rate_hz);
1✔
1276
    } else if (rate_hz < 0) {
×
1277
        interval_us = -1.0f;
×
1278
    }
1279

1280
    command.command = MAV_CMD_SET_MESSAGE_INTERVAL;
1✔
1281
    command.params.maybe_param1 = static_cast<float>(message_id);
1✔
1282
    command.params.maybe_param2 = interval_us;
1✔
1283
    command.target_component_id = component_id;
1✔
1284

1285
    return command;
1✔
1286
}
1287

1288
void SystemImpl::register_plugin(PluginImplBase* plugin_impl)
66✔
1289
{
1290
    assert(plugin_impl);
66✔
1291

1292
    plugin_impl->init();
66✔
1293

1294
    {
1295
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
66✔
1296
        _plugin_impls.push_back(plugin_impl);
66✔
1297
    }
66✔
1298

1299
    // If we're connected already, let's enable it straightaway.
1300
    if (_connected) {
66✔
1301
        plugin_impl->enable();
66✔
1302
    }
1303
}
66✔
1304

1305
void SystemImpl::unregister_plugin(PluginImplBase* plugin_impl)
66✔
1306
{
1307
    assert(plugin_impl);
66✔
1308

1309
    plugin_impl->disable();
66✔
1310
    plugin_impl->deinit();
66✔
1311

1312
    // Remove first, so it won't get enabled/disabled anymore.
1313
    {
1314
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
66✔
1315
        auto found = std::find(_plugin_impls.begin(), _plugin_impls.end(), plugin_impl);
66✔
1316
        if (found != _plugin_impls.end()) {
66✔
1317
            _plugin_impls.erase(found);
66✔
1318
        }
1319
    }
66✔
1320
}
66✔
1321

1322
void SystemImpl::call_user_callback_located(
922✔
1323
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1324
{
1325
    _mavsdk_impl.call_user_callback_located(filename, linenumber, func);
922✔
1326
}
922✔
1327

1328
void SystemImpl::param_changed(const std::string& name)
×
1329
{
1330
    for (auto& callback : _param_changed_callbacks) {
×
UNCOV
1331
        callback.second(name);
×
1332
    }
1333
}
×
1334

1335
void SystemImpl::register_param_changed_handler(
×
1336
    const ParamChangedCallback& callback, const void* cookie)
1337
{
1338
    if (!callback) {
×
1339
        LogErr() << "No callback for param_changed_handler supplied.";
×
1340
        return;
×
1341
    }
1342

1343
    if (!cookie) {
×
1344
        LogErr() << "No callback for param_changed_handler supplied.";
×
1345
        return;
×
1346
    }
1347

1348
    _param_changed_callbacks[cookie] = callback;
×
1349
}
1350

1351
void SystemImpl::unregister_param_changed_handler(const void* cookie)
×
1352
{
1353
    auto it = _param_changed_callbacks.find(cookie);
×
UNCOV
1354
    if (it == _param_changed_callbacks.end()) {
×
1355
        LogWarn() << "param_changed_handler for cookie not found";
×
1356
        return;
×
1357
    }
1358
    _param_changed_callbacks.erase(it);
×
1359
}
1360

1361
Time& SystemImpl::get_time()
394✔
1362
{
1363
    return _mavsdk_impl.time;
394✔
1364
}
1365

1366
void SystemImpl::subscribe_param_float(
×
1367
    const std::string& name,
1368
    const MavlinkParameterClient::ParamFloatChangedCallback& callback,
1369
    const void* cookie)
1370
{
1371
    param_sender(1, false)->subscribe_param_float_changed(name, callback, cookie);
×
1372
}
×
1373

1374
void SystemImpl::subscribe_param_int(
×
1375
    const std::string& name,
1376
    const MavlinkParameterClient::ParamIntChangedCallback& callback,
1377
    const void* cookie)
1378
{
1379
    param_sender(1, false)->subscribe_param_int_changed(name, callback, cookie);
×
1380
}
×
1381
void SystemImpl::subscribe_param_custom(
×
1382
    const std::string& name,
1383
    const MavlinkParameterClient::ParamCustomChangedCallback& callback,
1384
    const void* cookie)
1385
{
1386
    param_sender(1, false)->subscribe_param_custom_changed(name, callback, cookie);
×
1387
}
×
1388

1389
MavlinkParameterClient* SystemImpl::param_sender(uint8_t component_id, bool extended)
85✔
1390
{
1391
    std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
85✔
1392

1393
    for (auto& entry : _mavlink_parameter_clients) {
87✔
1394
        if (entry.component_id == component_id && entry.extended == extended) {
77✔
1395
            return entry.parameter_client.get();
75✔
1396
        }
1397
    }
1398

1399
    _mavlink_parameter_clients.push_back(
10✔
1400
        {std::make_unique<MavlinkParameterClient>(
1401
             _mavsdk_impl.default_server_component_impl().sender(),
10✔
1402
             _mavlink_message_handler,
10✔
1403
             _mavsdk_impl.timeout_handler,
10✔
1404
             [this]() { return timeout_s(); },
79✔
1405
             [this]() { return autopilot(); },
34✔
1406
             get_system_id(),
10✔
1407
             component_id,
1408
             extended),
1409
         component_id,
1410
         extended});
1411

1412
    return _mavlink_parameter_clients.back().parameter_client.get();
10✔
1413
}
85✔
1414

1415
std::vector<Connection*> SystemImpl::get_connections() const
×
1416
{
1417
    return _mavsdk_impl.get_connections();
×
1418
}
1419

1420
mav::MessageSet& SystemImpl::get_message_set() const
10✔
1421
{
1422
    return _mavsdk_impl.get_message_set();
10✔
1423
}
1424

1425
bool SystemImpl::load_custom_xml_to_message_set(const std::string& xml_content)
4✔
1426
{
1427
    return _mavsdk_impl.load_custom_xml_to_message_set(xml_content);
4✔
1428
}
1429

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