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

mavlink / MAVSDK / 16485391475

24 Jul 2025 01:13AM UTC coverage: 46.33% (+1.2%) from 45.096%
16485391475

push

github

web-flow
Merge pull request #2610 from mavlink/pr-add-libmavlike

Integrate parts of libmav into MAVSDK and add MavlinkDirect plugin

764 of 987 new or added lines in 14 files covered. (77.41%)

10 existing lines in 1 file now uncovered.

16272 of 35122 relevant lines covered (46.33%)

359.99 hits per line

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

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

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

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

55
    unregister_timeout_handler(_heartbeat_timeout_cookie);
100✔
56

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

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

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

75
    _mavlink_message_handler.register_one(
100✔
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(
100✔
81
        MAVLINK_MSG_ID_AUTOPILOT_VERSION,
82
        [this](const mavlink_message_t& message) { process_autopilot_version(message); },
40✔
83
        this);
84

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

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

93
void SystemImpl::register_mavlink_message_handler(
424✔
94
    uint16_t msg_id, const MavlinkMessageHandler::Callback& callback, const void* cookie)
95
{
96
    _mavlink_message_handler.register_one(msg_id, callback, cookie);
424✔
97
}
424✔
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)
413✔
114
{
115
    _mavlink_message_handler.unregister_all(cookie);
413✔
116
}
413✔
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 LibmavMessage& message)
2,114✔
125
{
126
    // Call all registered libmav message handlers
127
    std::lock_guard<std::mutex> lock(_libmav_message_handlers_mutex);
2,114✔
128

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

134
    for (const auto& handler : _libmav_message_handlers) {
2,135✔
135
        if (_message_debugging) {
20✔
NEW
136
            LogDebug() << "Checking handler for message: '" << handler.message_name << "' against '"
×
NEW
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) {
12✔
NEW
142
                LogDebug() << "Handler message name mismatch, skipping";
×
143
            }
144
            continue;
12✔
145
        }
146

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

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

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

NEW
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
{
NEW
182
    std::lock_guard<std::mutex> lock(_libmav_message_handlers_mutex);
×
NEW
183
    _libmav_message_handlers.push_back({message_name, callback, cookie, cmp_id});
×
NEW
184
}
×
185

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

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

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

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

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

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

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

229
double SystemImpl::timeout_s() const
1,090✔
230
{
231
    return _mavsdk_impl.timeout_s();
1,090✔
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,102✔
251
{
252
    _mavlink_message_handler.process_message(message);
2,102✔
253
}
2,102✔
254

255
CallEveryHandler::Cookie
256
SystemImpl::add_call_every(std::function<void()> callback, float interval_s)
29✔
257
{
258
    return _mavsdk_impl.call_every_handler.add(
58✔
259
        std::move(callback), static_cast<double>(interval_s));
29✔
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)
29✔
273
{
274
    _mavsdk_impl.call_every_handler.remove(cookie);
29✔
275
}
29✔
276

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

284
void SystemImpl::unregister_statustext_handler(void* cookie)
2✔
285
{
286
    std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
2✔
287
    _statustext_handler_callbacks.erase(std::remove_if(
2✔
288
        _statustext_handler_callbacks.begin(),
289
        _statustext_handler_callbacks.end(),
290
        [&](const auto& entry) { return entry.cookie == cookie; }));
2✔
291
}
2✔
292

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

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

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

319
    if (message.compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
191✔
320
        _armed = (heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) != 0;
78✔
321
        _hitl_enabled = (heartbeat.base_mode & MAV_MODE_FLAG_HIL_ENABLED) != 0;
78✔
322
    }
323
    if (heartbeat.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
190✔
324
        _flight_mode =
×
325
            to_flight_mode_from_custom_mode(_autopilot, _vehicle_type, heartbeat.custom_mode);
326
    }
327

328
    set_connected();
190✔
329
}
193✔
330

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

336
    const auto maybe_result = _statustext_handler.process(statustext);
3✔
337

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

343
        std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
3✔
344
        for (const auto& entry : _statustext_handler_callbacks) {
6✔
345
            entry.callback(maybe_result.value());
3✔
346
        }
347
    }
3✔
348
}
3✔
349

350
void SystemImpl::process_autopilot_version(const mavlink_message_t& message)
40✔
351
{
352
    mavlink_autopilot_version_t autopilot_version;
40✔
353
    mavlink_msg_autopilot_version_decode(&message, &autopilot_version);
40✔
354

355
    _mission_transfer_client.set_int_messages_supported(
40✔
356
        autopilot_version.capabilities & MAV_PROTOCOL_CAPABILITY_MISSION_INT);
40✔
357
}
40✔
358

359
void SystemImpl::heartbeats_timed_out()
×
360
{
361
    LogInfo() << "heartbeats timed out";
×
362
    set_disconnected();
×
363
}
×
364

365
void SystemImpl::system_thread()
100✔
366
{
367
    SteadyTimePoint last_ping_time{};
100✔
368

369
    while (!_should_exit) {
9,424✔
370
        {
371
            std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
9,249✔
372
            for (auto& entry : _mavlink_parameter_clients) {
10,188✔
373
                entry.parameter_client->do_work();
941✔
374
            }
375
        }
9,280✔
376
        _command_sender.do_work();
9,314✔
377
        _timesync.do_work();
9,296✔
378
        _mission_transfer_client.do_work();
9,267✔
379
        _mavlink_ftp_client.do_work();
9,249✔
380

381
        if (_mavsdk_impl.time.elapsed_since_s(last_ping_time) >= SystemImpl::_ping_interval_s) {
9,261✔
382
            if (_connected && _autopilot != Autopilot::ArduPilot) {
102✔
383
                _ping.run_once();
2✔
384
            }
385
            last_ping_time = _mavsdk_impl.time.steady_time();
102✔
386
        }
387

388
        if (_connected) {
9,256✔
389
            // Work fairly fast if we're connected.
390
            std::this_thread::sleep_for(std::chrono::milliseconds(10));
9,123✔
391
        } else {
392
            // Be less aggressive when unconnected.
393
            std::this_thread::sleep_for(std::chrono::milliseconds(100));
100✔
394
        }
395
    }
396
}
100✔
397

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

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

458
void SystemImpl::add_new_component(uint8_t component_id)
4,217✔
459
{
460
    if (component_id == 0) {
4,217✔
461
        return;
×
462
    }
463

464
    auto res_pair = _components.insert(component_id);
4,217✔
465
    if (res_pair.second) {
4,214✔
466
        std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
101✔
467
        _component_discovered_callbacks.queue(
101✔
468
            component_type(component_id), [this](const auto& func) { call_user_callback(func); });
×
469
        _component_discovered_id_callbacks.queue(
101✔
470
            component_type(component_id), component_id, [this](const auto& func) {
×
471
                call_user_callback(func);
×
472
            });
×
473
        LogDebug() << "Component " << component_name(component_id) << " (" << int(component_id)
404✔
474
                   << ") added.";
404✔
475
    }
101✔
476
}
477

478
size_t SystemImpl::total_components() const
×
479
{
480
    return _components.size();
×
481
}
482

483
System::ComponentDiscoveredHandle
484
SystemImpl::subscribe_component_discovered(const System::ComponentDiscoveredCallback& callback)
×
485
{
486
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
487
    const auto handle = _component_discovered_callbacks.subscribe(callback);
×
488

489
    if (total_components() > 0) {
×
490
        for (const auto& elem : _components) {
×
491
            _component_discovered_callbacks.queue(
×
492
                component_type(elem), [this](const auto& func) { call_user_callback(func); });
×
493
        }
494
    }
495
    return handle;
×
496
}
×
497

498
void SystemImpl::unsubscribe_component_discovered(System::ComponentDiscoveredHandle handle)
×
499
{
500
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
501
    _component_discovered_callbacks.unsubscribe(handle);
×
502
}
×
503

504
System::ComponentDiscoveredIdHandle
505
SystemImpl::subscribe_component_discovered_id(const System::ComponentDiscoveredIdCallback& callback)
×
506
{
507
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
508
    const auto handle = _component_discovered_id_callbacks.subscribe(callback);
×
509

510
    if (total_components() > 0) {
×
511
        for (const auto& elem : _components) {
×
512
            _component_discovered_id_callbacks.queue(
×
513
                component_type(elem), elem, [this](const auto& func) { call_user_callback(func); });
×
514
        }
515
    }
516
    return handle;
×
517
}
×
518

519
void SystemImpl::unsubscribe_component_discovered_id(System::ComponentDiscoveredIdHandle handle)
×
520
{
521
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
522
    _component_discovered_id_callbacks.unsubscribe(handle);
×
523
}
×
524

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

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

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

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

545
bool SystemImpl::has_camera(int camera_id) const
9✔
546
{
547
    int camera_comp_id = (camera_id == -1) ? camera_id : (MAV_COMP_ID_CAMERA + camera_id);
9✔
548

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

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

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

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

579
void SystemImpl::send_autopilot_version_request()
40✔
580
{
581
    mavlink_request_message().request(
40✔
582
        MAVLINK_MSG_ID_AUTOPILOT_VERSION, MAV_COMP_ID_AUTOPILOT1, nullptr);
583
}
40✔
584

585
void SystemImpl::set_connected()
187✔
586
{
587
    bool enable_needed = false;
187✔
588
    {
589
        if (!_connected) {
187✔
590
            if (!_components.empty()) {
100✔
591
                LogDebug() << "Discovered " << _components.size() << " component(s)";
100✔
592
            }
593

594
            _connected = true;
100✔
595

596
            // Only send heartbeats if we're not shutting down
597
            if (!_should_exit) {
100✔
598
                // We call this later to avoid deadlocks on creating the server components.
599
                _mavsdk_impl.call_user_callback([this]() {
200✔
600
                    // Send a heartbeat back immediately.
601
                    _mavsdk_impl.start_sending_heartbeats();
602
                });
603
            }
604

605
            _heartbeat_timeout_cookie =
100✔
606
                register_timeout_handler([this] { heartbeats_timed_out(); }, HEARTBEAT_TIMEOUT_S);
100✔
607

608
            enable_needed = true;
100✔
609

610
            // Queue callbacks without holding any locks to avoid deadlocks
611
            _is_connected_callbacks.queue(
100✔
612
                true, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
613

614
        } else if (_connected) {
91✔
615
            refresh_timeout_handler(_heartbeat_timeout_cookie);
92✔
616
        }
617
        // If not yet connected there is nothing to do
618
    }
619

620
    if (enable_needed) {
193✔
621
        // Notify about the new system without holding any locks
622
        _mavsdk_impl.notify_on_discover();
100✔
623

624
        if (has_autopilot()) {
100✔
625
            send_autopilot_version_request();
40✔
626
        }
627

628
        // Enable plugins
629
        std::vector<PluginImplBase*> plugin_impls_to_enable;
100✔
630
        {
631
            std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
100✔
632
            plugin_impls_to_enable = _plugin_impls;
100✔
633
        }
100✔
634

635
        for (auto plugin_impl : plugin_impls_to_enable) {
100✔
636
            plugin_impl->enable();
×
637
        }
638
    }
100✔
639
}
193✔
640

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

649
        _connected = false;
×
650
        _is_connected_callbacks.queue(
×
651
            false, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
652
    }
653
    _mavsdk_impl.notify_on_timeout();
×
654

655
    _mavsdk_impl.stop_sending_heartbeats();
×
656

657
    {
658
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
×
659
        for (auto plugin_impl : _plugin_impls) {
×
660
            plugin_impl->disable();
×
661
        }
662
    }
×
663
}
×
664

665
uint8_t SystemImpl::get_system_id() const
775✔
666
{
667
    return _target_address.system_id;
775✔
668
}
669

670
std::vector<uint8_t> SystemImpl::component_ids() const
7✔
671
{
672
    return std::vector<uint8_t>{_components.begin(), _components.end()};
7✔
673
}
674

675
void SystemImpl::set_system_id(uint8_t system_id)
×
676
{
677
    _target_address.system_id = system_id;
×
678
}
×
679

680
uint8_t SystemImpl::get_own_system_id() const
1,406✔
681
{
682
    return _mavsdk_impl.get_own_system_id();
1,406✔
683
}
684

685
uint8_t SystemImpl::get_own_component_id() const
1,388✔
686
{
687
    return _mavsdk_impl.get_own_component_id();
1,388✔
688
}
689

690
MAV_TYPE SystemImpl::get_vehicle_type() const
×
691
{
692
    return _vehicle_type;
×
693
}
694

695
Vehicle SystemImpl::vehicle() const
×
696
{
697
    return to_vehicle_from_mav_type(_vehicle_type);
×
698
}
699

700
uint8_t SystemImpl::get_own_mav_type() const
×
701
{
702
    return _mavsdk_impl.get_mav_type();
×
703
}
704

705
MavlinkParameterClient::Result SystemImpl::set_param(
×
706
    const std::string& name,
707
    ParamValue value,
708
    std::optional<uint8_t> maybe_component_id,
709
    bool extended)
710
{
711
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
712
        ->set_param(name, value);
×
713
}
714

715
MavlinkParameterClient::Result SystemImpl::set_param_float(
2✔
716
    const std::string& name, float value, std::optional<uint8_t> maybe_component_id, bool extended)
717
{
718
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
719
        ->set_param_float(name, value);
4✔
720
}
721

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

732
MavlinkParameterClient::Result SystemImpl::set_param_custom(
2✔
733
    const std::string& name, const std::string& value, std::optional<uint8_t> maybe_component_id)
734
{
735
    return param_sender(maybe_component_id.has_value() ? maybe_component_id.value() : 1, true)
4✔
736
        ->set_param_custom(name, value);
4✔
737
}
738

739
std::pair<MavlinkParameterClient::Result, std::map<std::string, ParamValue>>
740
SystemImpl::get_all_params(std::optional<uint8_t> maybe_component_id, bool extended)
4✔
741
{
742
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
4✔
743
        ->get_all_params();
8✔
744
}
745

746
void SystemImpl::set_param_async(
3✔
747
    const std::string& name,
748
    ParamValue value,
749
    const SetParamCallback& callback,
750
    const void* cookie,
751
    std::optional<uint8_t> maybe_component_id,
752
    bool extended)
753
{
754
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
3✔
755
        ->set_param_async(name, value, callback, cookie);
6✔
756
}
3✔
757

758
void SystemImpl::set_param_float_async(
×
759
    const std::string& name,
760
    float value,
761
    const SetParamCallback& callback,
762
    const void* cookie,
763
    std::optional<uint8_t> maybe_component_id,
764
    bool extended)
765
{
766
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
767
        ->set_param_float_async(name, value, callback, cookie);
×
768
}
×
769

770
void SystemImpl::set_param_int_async(
×
771
    const std::string& name,
772
    int32_t value,
773
    const SetParamCallback& callback,
774
    const void* cookie,
775
    std::optional<uint8_t> maybe_component_id,
776
    bool extended)
777
{
778
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
779
        ->set_param_int_async(name, value, callback, cookie);
×
780
}
×
781

782
std::pair<MavlinkParameterClient::Result, float> SystemImpl::get_param_float(
5✔
783
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
784
{
785
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
786
        ->get_param_float(name);
10✔
787
}
788

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

796
std::pair<MavlinkParameterClient::Result, std::string>
797
SystemImpl::get_param_custom(const std::string& name, std::optional<uint8_t> maybe_component_id)
4✔
798
{
799
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, true)
8✔
800
        ->get_param_custom(name);
8✔
801
}
802

803
void SystemImpl::get_param_async(
×
804
    const std::string& name,
805
    ParamValue value,
806
    const GetParamAnyCallback& callback,
807
    const void* cookie,
808
    std::optional<uint8_t> maybe_component_id,
809
    bool extended)
810
{
811
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
812
        ->get_param_async(name, value, callback, cookie);
×
813
}
×
814

815
void SystemImpl::get_param_float_async(
×
816
    const std::string& name,
817
    const GetParamFloatCallback& callback,
818
    const void* cookie,
819
    std::optional<uint8_t> maybe_component_id,
820
    bool extended)
821
{
822
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
823
        ->get_param_float_async(name, callback, cookie);
×
824
}
×
825

826
void SystemImpl::get_param_int_async(
×
827
    const std::string& name,
828
    const GetParamIntCallback& callback,
829
    const void* cookie,
830
    std::optional<uint8_t> maybe_component_id,
831
    bool extended)
832
{
833
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
834
        ->get_param_int_async(name, callback, cookie);
×
835
}
×
836

837
void SystemImpl::get_param_custom_async(
×
838
    const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
839
{
840
    param_sender(1, false)->get_param_custom_async(name, callback, cookie);
×
841
}
×
842

843
void SystemImpl::cancel_all_param(const void* cookie)
9✔
844
{
845
    UNUSED(cookie);
9✔
846
    // FIXME: this currently crashes on destruction
847
    // param_sender(1, false)->cancel_all_param(cookie);
848
}
9✔
849

850
MavlinkCommandSender::Result
851
SystemImpl::set_flight_mode(FlightMode system_mode, uint8_t component_id)
×
852
{
853
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
854
        make_command_flight_mode(system_mode, component_id);
×
855

856
    if (result.first != MavlinkCommandSender::Result::Success) {
×
857
        return result.first;
×
858
    }
859

860
    return send_command(result.second);
×
861
}
862

863
void SystemImpl::set_flight_mode_async(
×
864
    FlightMode system_mode, const CommandResultCallback& callback, uint8_t component_id)
865
{
866
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
867
        make_command_flight_mode(system_mode, component_id);
×
868

869
    if (result.first != MavlinkCommandSender::Result::Success) {
×
870
        if (callback) {
×
871
            callback(result.first, NAN);
×
872
        }
873
        return;
×
874
    }
875

876
    send_command_async(result.second, callback);
×
877
}
878

879
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
880
SystemImpl::make_command_flight_mode(FlightMode flight_mode, uint8_t component_id)
×
881
{
882
    if (_autopilot == Autopilot::ArduPilot) {
×
883
        return make_command_ardupilot_mode(flight_mode, component_id);
×
884
    } else {
885
        return make_command_px4_mode(flight_mode, component_id);
×
886
    }
887
}
888

889
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
890
SystemImpl::make_command_ardupilot_mode(FlightMode flight_mode, uint8_t component_id)
×
891
{
892
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
893
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
894
    const uint8_t mode_type =
×
895
        MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
896

897
    MavlinkCommandSender::CommandLong command{};
×
898

899
    command.command = MAV_CMD_DO_SET_MODE;
×
900
    command.params.maybe_param1 = static_cast<float>(mode_type);
×
901

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

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

952
        default:
×
953
            LogErr() << "Cannot translate flight mode to ArduPilot mode, for MAV_TYPE: "
×
954
                     << _vehicle_type;
×
955
            MavlinkCommandSender::CommandLong empty_command{};
×
956
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
957
    }
958
    command.target_component_id = component_id;
×
959

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

1050
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
1051
SystemImpl::make_command_px4_mode(FlightMode flight_mode, uint8_t component_id)
×
1052
{
1053
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
1054
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
1055

1056
    const uint8_t mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
1057

1058
    // Note: the safety flag is not needed in future versions of the PX4 Firmware
1059
    //       but want to be rather safe than sorry.
1060
    uint8_t custom_mode = px4::PX4_CUSTOM_MAIN_MODE_AUTO;
×
1061
    uint8_t custom_sub_mode = 0;
×
1062

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

1109
    MavlinkCommandSender::CommandLong command{};
×
1110

1111
    command.command = MAV_CMD_DO_SET_MODE;
×
1112
    command.params.maybe_param1 = static_cast<float>(mode);
×
1113
    command.params.maybe_param2 = static_cast<float>(custom_mode);
×
1114
    command.params.maybe_param3 = static_cast<float>(custom_sub_mode);
×
1115
    command.target_component_id = component_id;
×
1116

1117
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
1118
}
1119

1120
FlightMode SystemImpl::get_flight_mode() const
7✔
1121
{
1122
    return _flight_mode;
7✔
1123
}
1124

1125
void SystemImpl::receive_float_param(
×
1126
    MavlinkParameterClient::Result result, ParamValue value, const GetParamFloatCallback& callback)
1127
{
1128
    if (callback) {
×
1129
        if (result == MavlinkParameterClient::Result::Success) {
×
1130
            callback(result, value.get<float>());
×
1131
        } else {
1132
            callback(result, NAN);
×
1133
        }
1134
    }
1135
}
×
1136

1137
void SystemImpl::receive_int_param(
×
1138
    MavlinkParameterClient::Result result, ParamValue value, const GetParamIntCallback& callback)
1139
{
1140
    if (callback) {
×
1141
        if (result == MavlinkParameterClient::Result::Success) {
×
1142
            callback(result, value.get<int32_t>());
×
1143
        } else {
1144
            callback(result, 0);
×
1145
        }
1146
    }
1147
}
×
1148

1149
uint8_t SystemImpl::get_autopilot_id() const
225✔
1150
{
1151
    for (auto compid : _components)
292✔
1152
        if (compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
228✔
1153
            return compid;
161✔
1154
        }
1155
    // FIXME: Not sure what should be returned if autopilot is not found
1156
    return uint8_t(0);
64✔
1157
}
1158

1159
std::vector<uint8_t> SystemImpl::get_camera_ids() const
×
1160
{
1161
    std::vector<uint8_t> camera_ids{};
×
1162

1163
    for (auto compid : _components)
×
1164
        if (compid >= MAV_COMP_ID_CAMERA && compid <= MAV_COMP_ID_CAMERA6) {
×
1165
            camera_ids.push_back(compid);
×
1166
        }
1167
    return camera_ids;
×
1168
}
1169

1170
uint8_t SystemImpl::get_gimbal_id() const
×
1171
{
1172
    for (auto compid : _components)
×
1173
        if (compid == MAV_COMP_ID_GIMBAL) {
×
1174
            return compid;
×
1175
        }
1176
    return uint8_t(0);
×
1177
}
1178

1179
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandLong& command)
5✔
1180
{
1181
    if (_target_address.system_id == 0 && _components.empty()) {
5✔
1182
        return MavlinkCommandSender::Result::NoSystem;
×
1183
    }
1184
    command.target_system_id = get_system_id();
5✔
1185
    return _command_sender.send_command(command);
5✔
1186
}
1187

1188
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandInt& command)
×
1189
{
1190
    if (_target_address.system_id == 0 && _components.empty()) {
×
1191
        return MavlinkCommandSender::Result::NoSystem;
×
1192
    }
1193
    command.target_system_id = get_system_id();
×
1194
    return _command_sender.send_command(command);
×
1195
}
1196

1197
void SystemImpl::send_command_async(
7✔
1198
    MavlinkCommandSender::CommandLong command, const CommandResultCallback& callback)
1199
{
1200
    if (_target_address.system_id == 0 && _components.empty()) {
7✔
1201
        if (callback) {
×
1202
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1203
        }
1204
        return;
×
1205
    }
1206
    command.target_system_id = get_system_id();
7✔
1207

1208
    _command_sender.queue_command_async(command, callback);
7✔
1209
}
1210

1211
void SystemImpl::send_command_async(
×
1212
    MavlinkCommandSender::CommandInt command, const CommandResultCallback& callback)
1213
{
1214
    if (_target_address.system_id == 0 && _components.empty()) {
×
1215
        if (callback) {
×
1216
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1217
        }
1218
        return;
×
1219
    }
1220
    command.target_system_id = get_system_id();
×
1221

1222
    _command_sender.queue_command_async(command, callback);
×
1223
}
1224

1225
MavlinkCommandSender::Result
1226
SystemImpl::set_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
×
1227
{
1228
    MavlinkCommandSender::CommandLong command =
×
1229
        make_command_msg_rate(message_id, rate_hz, component_id);
×
1230
    return send_command(command);
×
1231
}
1232

1233
void SystemImpl::set_msg_rate_async(
1✔
1234
    uint16_t message_id,
1235
    double rate_hz,
1236
    const CommandResultCallback& callback,
1237
    uint8_t component_id)
1238
{
1239
    MavlinkCommandSender::CommandLong command =
1✔
1240
        make_command_msg_rate(message_id, rate_hz, component_id);
1✔
1241
    send_command_async(command, callback);
1✔
1242
}
1✔
1243

1244
MavlinkCommandSender::CommandLong
1245
SystemImpl::make_command_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
1✔
1246
{
1247
    MavlinkCommandSender::CommandLong command{};
1✔
1248

1249
    // 0 to request default rate, -1 to stop stream
1250

1251
    float interval_us = 0.0f;
1✔
1252

1253
    if (rate_hz > 0) {
1✔
1254
        interval_us = 1e6f / static_cast<float>(rate_hz);
1✔
1255
    } else if (rate_hz < 0) {
×
1256
        interval_us = -1.0f;
×
1257
    }
1258

1259
    command.command = MAV_CMD_SET_MESSAGE_INTERVAL;
1✔
1260
    command.params.maybe_param1 = static_cast<float>(message_id);
1✔
1261
    command.params.maybe_param2 = interval_us;
1✔
1262
    command.target_component_id = component_id;
1✔
1263

1264
    return command;
1✔
1265
}
1266

1267
void SystemImpl::register_plugin(PluginImplBase* plugin_impl)
58✔
1268
{
1269
    assert(plugin_impl);
58✔
1270

1271
    plugin_impl->init();
58✔
1272

1273
    {
1274
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
58✔
1275
        _plugin_impls.push_back(plugin_impl);
58✔
1276
    }
58✔
1277

1278
    // If we're connected already, let's enable it straightaway.
1279
    if (_connected) {
58✔
1280
        plugin_impl->enable();
58✔
1281
    }
1282
}
58✔
1283

1284
void SystemImpl::unregister_plugin(PluginImplBase* plugin_impl)
58✔
1285
{
1286
    assert(plugin_impl);
58✔
1287

1288
    plugin_impl->disable();
58✔
1289
    plugin_impl->deinit();
58✔
1290

1291
    // Remove first, so it won't get enabled/disabled anymore.
1292
    {
1293
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
58✔
1294
        auto found = std::find(_plugin_impls.begin(), _plugin_impls.end(), plugin_impl);
58✔
1295
        if (found != _plugin_impls.end()) {
58✔
1296
            _plugin_impls.erase(found);
58✔
1297
        }
1298
    }
58✔
1299
}
58✔
1300

1301
void SystemImpl::call_user_callback_located(
914✔
1302
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1303
{
1304
    _mavsdk_impl.call_user_callback_located(filename, linenumber, func);
914✔
1305
}
914✔
1306

1307
void SystemImpl::param_changed(const std::string& name)
×
1308
{
1309
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1310

1311
    for (auto& callback : _param_changed_callbacks) {
×
1312
        callback.second(name);
×
1313
    }
1314
}
×
1315

1316
void SystemImpl::register_param_changed_handler(
×
1317
    const ParamChangedCallback& callback, const void* cookie)
1318
{
1319
    if (!callback) {
×
1320
        LogErr() << "No callback for param_changed_handler supplied.";
×
1321
        return;
×
1322
    }
1323

1324
    if (!cookie) {
×
1325
        LogErr() << "No callback for param_changed_handler supplied.";
×
1326
        return;
×
1327
    }
1328

1329
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1330

1331
    _param_changed_callbacks[cookie] = callback;
×
1332
}
×
1333

1334
void SystemImpl::unregister_param_changed_handler(const void* cookie)
×
1335
{
1336
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1337

1338
    auto it = _param_changed_callbacks.find(cookie);
×
1339
    if (it == _param_changed_callbacks.end()) {
×
1340
        LogWarn() << "param_changed_handler for cookie not found";
×
1341
        return;
×
1342
    }
1343
    _param_changed_callbacks.erase(it);
×
1344
}
×
1345

1346
Time& SystemImpl::get_time()
430✔
1347
{
1348
    return _mavsdk_impl.time;
430✔
1349
}
1350

1351
void SystemImpl::subscribe_param_float(
×
1352
    const std::string& name,
1353
    const MavlinkParameterClient::ParamFloatChangedCallback& callback,
1354
    const void* cookie)
1355
{
1356
    param_sender(1, false)->subscribe_param_float_changed(name, callback, cookie);
×
1357
}
×
1358

1359
void SystemImpl::subscribe_param_int(
×
1360
    const std::string& name,
1361
    const MavlinkParameterClient::ParamIntChangedCallback& callback,
1362
    const void* cookie)
1363
{
1364
    param_sender(1, false)->subscribe_param_int_changed(name, callback, cookie);
×
1365
}
×
1366
void SystemImpl::subscribe_param_custom(
×
1367
    const std::string& name,
1368
    const MavlinkParameterClient::ParamCustomChangedCallback& callback,
1369
    const void* cookie)
1370
{
1371
    param_sender(1, false)->subscribe_param_custom_changed(name, callback, cookie);
×
1372
}
×
1373

1374
MavlinkParameterClient* SystemImpl::param_sender(uint8_t component_id, bool extended)
85✔
1375
{
1376
    std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
85✔
1377

1378
    for (auto& entry : _mavlink_parameter_clients) {
87✔
1379
        if (entry.component_id == component_id && entry.extended == extended) {
77✔
1380
            return entry.parameter_client.get();
75✔
1381
        }
1382
    }
1383

1384
    _mavlink_parameter_clients.push_back(
30✔
1385
        {std::make_unique<MavlinkParameterClient>(
1386
             _mavsdk_impl.default_server_component_impl().sender(),
10✔
1387
             _mavlink_message_handler,
10✔
1388
             _mavsdk_impl.timeout_handler,
10✔
1389
             [this]() { return timeout_s(); },
79✔
1390
             [this]() { return autopilot(); },
34✔
1391
             get_system_id(),
20✔
1392
             component_id,
1393
             extended),
1394
         component_id,
1395
         extended});
1396

1397
    return _mavlink_parameter_clients.back().parameter_client.get();
10✔
1398
}
85✔
1399

NEW
1400
std::vector<Connection*> SystemImpl::get_connections() const
×
1401
{
NEW
1402
    return _mavsdk_impl.get_connections();
×
1403
}
1404

1405
mav::MessageSet& SystemImpl::get_message_set() const
10✔
1406
{
1407
    return _mavsdk_impl.get_message_set();
10✔
1408
}
1409

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