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

mavlink / MAVSDK / 7233481265

16 Dec 2023 06:06PM UTC coverage: 37.088% (+0.09%) from 36.997%
7233481265

push

github

web-flow
Merge pull request #2192 from mavlink/pr-fix-sysid-filter

core: fix incoming messages by sysid

32 of 52 new or added lines in 4 files covered. (61.54%)

1 existing line in 1 file now uncovered.

10002 of 26968 relevant lines covered (37.09%)

113.62 hits per line

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

40.68
/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 "server_component_impl.h"
6
#include "plugin_impl_base.h"
7
#include "px4_custom_mode.h"
8
#include "ardupilot_custom_mode.h"
9
#include "request_message.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<System::ComponentType>;
22
template class CallbackList<System::ComponentType, uint8_t>;
23

24
SystemImpl::SystemImpl(MavsdkImpl& mavsdk_impl) :
68✔
25
    _mavsdk_impl(mavsdk_impl),
26
    _command_sender(*this),
27
    _timesync(*this),
28
    _ping(*this),
29
    _mission_transfer_client(
30
        _mavsdk_impl.default_server_component_impl().sender(),
68✔
31
        _mavlink_message_handler,
68✔
32
        _mavsdk_impl.timeout_handler,
68✔
33
        [this]() { return timeout_s(); }),
1✔
34
    _request_message(
35
        *this, _command_sender, _mavlink_message_handler, _mavsdk_impl.timeout_handler),
68✔
36
    _mavlink_ftp_client(*this)
136✔
37
{
38
    _system_thread = new std::thread(&SystemImpl::system_thread, this);
68✔
39
}
68✔
40

41
SystemImpl::~SystemImpl()
68✔
42
{
43
    _should_exit = true;
68✔
44
    _mavlink_message_handler.unregister_all(this);
68✔
45

46
    unregister_timeout_handler(_heartbeat_timeout_cookie);
68✔
47

48
    if (_system_thread != nullptr) {
68✔
49
        _system_thread->join();
68✔
50
        delete _system_thread;
68✔
51
        _system_thread = nullptr;
68✔
52
    }
53
}
68✔
54

55
void SystemImpl::init(uint8_t system_id, uint8_t comp_id)
68✔
56
{
57
    _target_address.system_id = system_id;
68✔
58
    // We use this as a default.
59
    _target_address.component_id = MAV_COMP_ID_AUTOPILOT1;
68✔
60

61
    _mavlink_message_handler.register_one(
68✔
62
        MAVLINK_MSG_ID_HEARTBEAT,
63
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
82✔
64
        this);
65

66
    _mavlink_message_handler.register_one(
68✔
67
        MAVLINK_MSG_ID_STATUSTEXT,
68
        [this](const mavlink_message_t& message) { process_statustext(message); },
3✔
69
        this);
70

71
    _mavlink_message_handler.register_one(
68✔
72
        MAVLINK_MSG_ID_AUTOPILOT_VERSION,
73
        [this](const mavlink_message_t& message) { process_autopilot_version(message); },
37✔
74
        this);
75

76
    // register_mavlink_command_handler(
77
    //    MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
78
    //    [this](const MavlinkCommandReceiver::CommandLong& command) {
79
    //        return process_autopilot_version_request(command);
80
    //    },
81
    //    this);
82

83
    //// TO-DO!
84
    // register_mavlink_command_handler(
85
    //    MAV_CMD_REQUEST_MESSAGE,
86
    //    [this](const MavlinkCommandReceiver::CommandLong& command) {
87
    //        return make_command_ack_message(command, MAV_RESULT::MAV_RESULT_UNSUPPORTED);
88
    //    },
89
    //    this);
90

91
    add_new_component(comp_id);
68✔
92
}
68✔
93

94
bool SystemImpl::is_connected() const
34✔
95
{
96
    return _connected;
34✔
97
}
98

99
void SystemImpl::register_mavlink_message_handler(
233✔
100
    uint16_t msg_id, const MavlinkMessageHandler::Callback& callback, const void* cookie)
101
{
102
    _mavlink_message_handler.register_one(msg_id, callback, cookie);
233✔
103
}
233✔
104

105
void SystemImpl::register_mavlink_message_handler_with_compid(
7✔
106
    uint16_t msg_id,
107
    uint8_t component_id,
108
    const MavlinkMessageHandler::Callback& callback,
109
    const void* cookie)
110
{
111
    _mavlink_message_handler.register_one_with_component_id(msg_id, component_id, callback, cookie);
7✔
112
}
7✔
113

114
void SystemImpl::unregister_mavlink_message_handler(uint16_t msg_id, const void* cookie)
×
115
{
NEW
116
    _mavlink_message_handler.unregister_one(msg_id, cookie);
×
117
}
×
118

119
void SystemImpl::unregister_all_mavlink_message_handlers(const void* cookie)
276✔
120
{
121
    _mavlink_message_handler.unregister_all(cookie);
276✔
122
}
276✔
123

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

130
void SystemImpl::register_timeout_handler(
864✔
131
    const std::function<void()>& callback, double duration_s, void** cookie)
132
{
133
    _mavsdk_impl.timeout_handler.add(callback, duration_s, cookie);
864✔
134
}
864✔
135

136
void SystemImpl::refresh_timeout_handler(const void* cookie)
16✔
137
{
138
    _mavsdk_impl.timeout_handler.refresh(cookie);
16✔
139
}
16✔
140

141
void SystemImpl::unregister_timeout_handler(const void* cookie)
893✔
142
{
143
    _mavsdk_impl.timeout_handler.remove(cookie);
893✔
144
}
893✔
145

146
double SystemImpl::timeout_s() const
835✔
147
{
148
    return _mavsdk_impl.timeout_s();
835✔
149
}
150

151
void SystemImpl::enable_timesync()
×
152
{
153
    _timesync.enable();
×
154
}
×
155

156
System::IsConnectedHandle
157
SystemImpl::subscribe_is_connected(const System::IsConnectedCallback& callback)
×
158
{
159
    std::lock_guard<std::mutex> lock(_connection_mutex);
×
160
    return _is_connected_callbacks.subscribe(callback);
×
161
}
162

163
void SystemImpl::unsubscribe_is_connected(System::IsConnectedHandle handle)
×
164
{
165
    _is_connected_callbacks.unsubscribe(handle);
×
166
}
×
167

168
void SystemImpl::process_mavlink_message(mavlink_message_t& message)
1,405✔
169
{
170
    _mavlink_message_handler.process_message(message);
1,405✔
171
}
1,405✔
172

173
void SystemImpl::add_call_every(std::function<void()> callback, float interval_s, void** cookie)
4✔
174
{
175
    _mavsdk_impl.call_every_handler.add(
8✔
176
        std::move(callback), static_cast<double>(interval_s), cookie);
4✔
177
}
4✔
178

179
void SystemImpl::change_call_every(float interval_s, const void* cookie)
×
180
{
181
    _mavsdk_impl.call_every_handler.change(static_cast<double>(interval_s), cookie);
×
182
}
×
183

184
void SystemImpl::reset_call_every(const void* cookie)
×
185
{
186
    _mavsdk_impl.call_every_handler.reset(cookie);
×
187
}
×
188

189
void SystemImpl::remove_call_every(const void* cookie)
10✔
190
{
191
    _mavsdk_impl.call_every_handler.remove(cookie);
10✔
192
}
10✔
193

194
void SystemImpl::register_statustext_handler(
1✔
195
    std::function<void(const MavlinkStatustextHandler::Statustext&)> callback, void* cookie)
196
{
197
    std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
2✔
198
    _statustext_handler_callbacks.push_back(StatustextCallback{std::move(callback), cookie});
1✔
199
}
1✔
200

201
void SystemImpl::unregister_statustext_handler(void* cookie)
1✔
202
{
203
    std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
2✔
204
    _statustext_handler_callbacks.erase(std::remove_if(
1✔
205
        _statustext_handler_callbacks.begin(),
206
        _statustext_handler_callbacks.end(),
207
        [&](const auto& entry) { return entry.cookie == cookie; }));
2✔
208
}
1✔
209

210
void SystemImpl::process_heartbeat(const mavlink_message_t& message)
82✔
211
{
212
    mavlink_heartbeat_t heartbeat;
82✔
213
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
82✔
214

215
    if (heartbeat.autopilot == MAV_AUTOPILOT_PX4) {
82✔
216
        _autopilot = Autopilot::Px4;
×
217
    } else if (heartbeat.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
82✔
218
        _autopilot = Autopilot::ArduPilot;
×
219
    }
220

221
    // Only set the vehicle type if the heartbeat is from an autopilot component
222
    // This check only works if the MAV_TYPE::MAV_TYPE_ENUM_END is actually the
223
    // last enumerator.
224
    if (MAV_TYPE::MAV_TYPE_ENUM_END < heartbeat.type) {
82✔
225
        LogErr() << "type received in HEARTBEAT was not recognized";
×
226
    } else {
227
        const auto new_vehicle_type = static_cast<MAV_TYPE>(heartbeat.type);
82✔
228
        if (heartbeat.autopilot != MAV_AUTOPILOT_INVALID && _vehicle_type != new_vehicle_type &&
82✔
229
            new_vehicle_type != MAV_TYPE_GENERIC) {
230
            LogWarn() << "Vehicle type changed (new type: " << static_cast<unsigned>(heartbeat.type)
×
231
                      << ", old type: " << static_cast<unsigned>(_vehicle_type) << ")";
×
232
            _vehicle_type = new_vehicle_type;
×
233
        }
234
    }
235

236
    if (message.compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
82✔
237
        _armed = (heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) != 0;
41✔
238
        _hitl_enabled = (heartbeat.base_mode & MAV_MODE_FLAG_HIL_ENABLED) != 0;
41✔
239
    }
240
    if (heartbeat.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
82✔
241
        _flight_mode =
×
242
            to_flight_mode_from_custom_mode(_autopilot, _vehicle_type, heartbeat.custom_mode);
243
    }
244

245
    set_connected();
82✔
246
}
82✔
247

248
void SystemImpl::process_statustext(const mavlink_message_t& message)
3✔
249
{
250
    mavlink_statustext_t statustext;
3✔
251
    mavlink_msg_statustext_decode(&message, &statustext);
3✔
252

253
    const auto maybe_result = _statustext_handler.process(statustext);
6✔
254

255
    if (maybe_result.has_value()) {
3✔
256
        LogDebug() << "MAVLink: "
6✔
257
                   << MavlinkStatustextHandler::severity_str(maybe_result.value().severity) << ": "
6✔
258
                   << maybe_result.value().text;
9✔
259

260
        std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
6✔
261
        for (const auto& entry : _statustext_handler_callbacks) {
6✔
262
            entry.callback(maybe_result.value());
3✔
263
        }
264
    }
265
}
3✔
266

267
void SystemImpl::process_autopilot_version(const mavlink_message_t& message)
37✔
268
{
269
    mavlink_autopilot_version_t autopilot_version;
37✔
270
    mavlink_msg_autopilot_version_decode(&message, &autopilot_version);
37✔
271

272
    _mission_transfer_client.set_int_messages_supported(
37✔
273
        autopilot_version.capabilities & MAV_PROTOCOL_CAPABILITY_MISSION_INT);
37✔
274
}
37✔
275

276
void SystemImpl::heartbeats_timed_out()
×
277
{
278
    LogInfo() << "heartbeats timed out";
×
279
    set_disconnected();
×
280
}
×
281

282
void SystemImpl::system_thread()
68✔
283
{
284
    SteadyTimePoint last_ping_time{};
68✔
285

286
    while (!_should_exit) {
3,013✔
287
        {
288
            std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
5,900✔
289
            for (auto& entry : _mavlink_parameter_clients) {
3,271✔
290
                entry.parameter_client->do_work();
316✔
291
            }
292
        }
293
        _command_sender.do_work();
3,006✔
294
        _timesync.do_work();
2,998✔
295
        _mission_transfer_client.do_work();
2,992✔
296
        _mavlink_ftp_client.do_work();
2,993✔
297

298
        if (_mavsdk_impl.time.elapsed_since_s(last_ping_time) >= SystemImpl::_ping_interval_s) {
3,019✔
299
            if (_connected && _autopilot != Autopilot::ArduPilot) {
68✔
300
                _ping.run_once();
×
301
            }
302
            last_ping_time = _mavsdk_impl.time.steady_time();
68✔
303
        }
304

305
        if (_connected) {
2,986✔
306
            // Work fairly fast if we're connected.
307
            std::this_thread::sleep_for(std::chrono::milliseconds(10));
2,842✔
308
        } else {
309
            // Be less aggressive when unconnected.
310
            std::this_thread::sleep_for(std::chrono::milliseconds(100));
128✔
311
        }
312
    }
313
}
68✔
314

315
// std::optional<mavlink_message_t>
316
// SystemImpl::process_autopilot_version_request(const MavlinkCommandReceiver::CommandLong& command)
317
//{
318
//    if (_should_send_autopilot_version) {
319
//        send_autopilot_version();
320
//        return make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
321
//    }
322
//
323
//    return {};
324
//}
325

326
std::string SystemImpl::component_name(uint8_t component_id)
68✔
327
{
328
    switch (component_id) {
68✔
329
        case MAV_COMP_ID_AUTOPILOT1:
33✔
330
            return "Autopilot";
33✔
331
        case MAV_COMP_ID_CAMERA:
1✔
332
            return "Camera 1";
1✔
333
        case MAV_COMP_ID_CAMERA2:
×
334
            return "Camera 2";
×
335
        case MAV_COMP_ID_CAMERA3:
×
336
            return "Camera 3";
×
337
        case MAV_COMP_ID_CAMERA4:
×
338
            return "Camera 4";
×
339
        case MAV_COMP_ID_CAMERA5:
×
340
            return "Camera 5";
×
341
        case MAV_COMP_ID_CAMERA6:
×
342
            return "Camera 6";
×
343
        case MAV_COMP_ID_GIMBAL:
×
344
            return "Gimbal";
×
345
        case MAV_COMP_ID_MISSIONPLANNER:
34✔
346
            return "Ground station";
34✔
347
        case MAV_COMP_ID_WINCH:
×
348
            return "Winch";
×
349
        default:
×
350
            return "Unsupported component";
×
351
    }
352
}
353

354
System::ComponentType SystemImpl::component_type(uint8_t component_id)
136✔
355
{
356
    switch (component_id) {
136✔
357
        case MAV_COMP_ID_AUTOPILOT1:
66✔
358
            return System::ComponentType::AUTOPILOT;
66✔
359
        case MAV_COMP_ID_CAMERA:
2✔
360
        case MAV_COMP_ID_CAMERA2:
361
        case MAV_COMP_ID_CAMERA3:
362
        case MAV_COMP_ID_CAMERA4:
363
        case MAV_COMP_ID_CAMERA5:
364
        case MAV_COMP_ID_CAMERA6:
365
            return System::ComponentType::CAMERA;
2✔
366
        case MAV_COMP_ID_GIMBAL:
×
367
            return System::ComponentType::GIMBAL;
×
368
        default:
68✔
369
            return System::ComponentType::UNKNOWN;
68✔
370
    }
371
}
372

373
void SystemImpl::add_new_component(uint8_t component_id)
1,441✔
374
{
375
    if (component_id == 0) {
1,441✔
376
        return;
34✔
377
    }
378

379
    auto res_pair = _components.insert(component_id);
1,407✔
380
    if (res_pair.second) {
1,406✔
381
        std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
136✔
382
        _component_discovered_callbacks.queue(
68✔
383
            component_type(component_id), [this](const auto& func) { call_user_callback(func); });
×
384
        _component_discovered_id_callbacks.queue(
68✔
385
            component_type(component_id), component_id, [this](const auto& func) {
×
386
                call_user_callback(func);
×
387
            });
×
388
        LogDebug() << "Component " << component_name(component_id) << " (" << int(component_id)
272✔
389
                   << ") added.";
272✔
390
    }
391
}
392

393
size_t SystemImpl::total_components() const
×
394
{
395
    return _components.size();
×
396
}
397

398
System::ComponentDiscoveredHandle
399
SystemImpl::subscribe_component_discovered(const System::ComponentDiscoveredCallback& callback)
×
400
{
401
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
402
    const auto handle = _component_discovered_callbacks.subscribe(callback);
×
403

404
    if (total_components() > 0) {
×
405
        for (const auto& elem : _components) {
×
406
            _component_discovered_callbacks.queue(
×
407
                component_type(elem), [this](const auto& func) { call_user_callback(func); });
×
408
        }
409
    }
410
    return handle;
×
411
}
412

413
void SystemImpl::unsubscribe_component_discovered(System::ComponentDiscoveredHandle handle)
×
414
{
415
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
416
    _component_discovered_callbacks.unsubscribe(handle);
×
417
}
×
418

419
System::ComponentDiscoveredIdHandle
420
SystemImpl::subscribe_component_discovered_id(const System::ComponentDiscoveredIdCallback& callback)
×
421
{
422
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
423
    const auto handle = _component_discovered_id_callbacks.subscribe(callback);
×
424

425
    if (total_components() > 0) {
×
426
        for (const auto& elem : _components) {
×
427
            _component_discovered_id_callbacks.queue(
×
428
                component_type(elem), elem, [this](const auto& func) { call_user_callback(func); });
×
429
        }
430
    }
431
    return handle;
×
432
}
433

434
void SystemImpl::unsubscribe_component_discovered_id(System::ComponentDiscoveredIdHandle handle)
×
435
{
436
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
437
    _component_discovered_id_callbacks.unsubscribe(handle);
×
438
}
×
439

440
bool SystemImpl::is_standalone() const
×
441
{
442
    return !has_autopilot();
×
443
}
444

445
bool SystemImpl::has_autopilot() const
133✔
446
{
447
    return get_autopilot_id() != uint8_t(0);
133✔
448
}
449

450
bool SystemImpl::is_autopilot(uint8_t comp_id)
×
451
{
452
    return comp_id == MAV_COMP_ID_AUTOPILOT1;
×
453
}
454

455
bool SystemImpl::is_camera(uint8_t comp_id)
1✔
456
{
457
    return (comp_id >= MAV_COMP_ID_CAMERA) && (comp_id <= MAV_COMP_ID_CAMERA6);
1✔
458
}
459

460
bool SystemImpl::has_camera(int camera_id) const
1✔
461
{
462
    int camera_comp_id = (camera_id == -1) ? camera_id : (MAV_COMP_ID_CAMERA + camera_id);
1✔
463

464
    if (camera_comp_id == -1) { // Check whether the system has any camera.
1✔
465
        if (std::any_of(_components.begin(), _components.end(), is_camera)) {
1✔
466
            return true;
1✔
467
        }
468
    } else { // Look for the camera whose id is `camera_id`.
469
        for (auto compid : _components) {
×
470
            if (compid == camera_comp_id) {
×
471
                return true;
×
472
            }
473
        }
474
    }
475
    return false;
×
476
}
477

478
bool SystemImpl::has_gimbal() const
×
479
{
480
    return get_gimbal_id() == MAV_COMP_ID_GIMBAL;
×
481
}
482

483
bool SystemImpl::send_message(mavlink_message_t& message)
×
484
{
485
    return _mavsdk_impl.send_message(message);
×
486
}
487

488
bool SystemImpl::queue_message(
548✔
489
    std::function<mavlink_message_t(MavlinkAddress mavlink_address, uint8_t channel)> fun)
490
{
491
    return _mavsdk_impl.default_server_component_impl().queue_message(fun);
548✔
492
}
493

494
void SystemImpl::send_autopilot_version_request()
×
495
{
496
    auto prom = std::promise<MavlinkCommandSender::Result>();
×
497
    auto fut = prom.get_future();
×
498

499
    send_autopilot_version_request_async(
×
500
        [&prom](MavlinkCommandSender::Result result, float) { prom.set_value(result); });
×
501

502
    if (fut.get() == MavlinkCommandSender::Result::Unsupported) {
×
503
        _old_message_520_supported = false;
×
504
        LogWarn() << "Trying alternative command (512).";
×
505
        send_autopilot_version_request();
×
506
    }
507
}
×
508

509
void SystemImpl::send_autopilot_version_request_async(
33✔
510
    const MavlinkCommandSender::CommandResultCallback& callback)
511
{
512
    MavlinkCommandSender::CommandLong command{};
33✔
513
    command.target_component_id = get_autopilot_id();
33✔
514

515
    if (_old_message_520_supported) {
33✔
516
        // Note: This MAVLINK message is deprecated and would be removed from MAVSDK in a future
517
        // release.
518
        command.command = MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES;
33✔
519
        command.params.maybe_param1 = 1.0f;
33✔
520
    } else {
521
        command.command = MAV_CMD_REQUEST_MESSAGE;
×
522
        command.params.maybe_param1 = {static_cast<float>(MAVLINK_MSG_ID_AUTOPILOT_VERSION)};
×
523
    }
524

525
    send_command_async(command, callback);
33✔
526
}
33✔
527

528
void SystemImpl::send_flight_information_request()
×
529
{
530
    auto prom = std::promise<MavlinkCommandSender::Result>();
×
531
    auto fut = prom.get_future();
×
532

533
    MavlinkCommandSender::CommandLong command{};
×
534
    command.target_component_id = get_autopilot_id();
×
535

536
    if (_old_message_528_supported) {
×
537
        // Note: This MAVLINK message is deprecated and would be removed from MAVSDK in a future
538
        // release.
539
        command.command = MAV_CMD_REQUEST_FLIGHT_INFORMATION;
×
540
        command.params.maybe_param1 = 1.0f;
×
541
    } else {
542
        command.command = MAV_CMD_REQUEST_MESSAGE;
×
543
        command.params.maybe_param1 = {static_cast<float>(MAVLINK_MSG_ID_FLIGHT_INFORMATION)};
×
544
    }
545

546
    send_command_async(
×
547
        command, [&prom](MavlinkCommandSender::Result result, float) { prom.set_value(result); });
×
548
    if (fut.get() == MavlinkCommandSender::Result::Unsupported) {
×
549
        _old_message_528_supported = false;
×
550
        LogWarn() << "Trying alternative command (512)..";
×
551
        send_flight_information_request();
×
552
    }
553
}
×
554

555
void SystemImpl::set_connected()
82✔
556
{
557
    bool enable_needed = false;
82✔
558
    {
559
        std::lock_guard<std::mutex> lock(_connection_mutex);
164✔
560

561
        if (!_connected) {
82✔
562
            if (!_components.empty()) {
66✔
563
                LogDebug() << "Discovered " << _components.size() << " component(s)";
66✔
564
            }
565

566
            _connected = true;
66✔
567

568
            // System with sysid 0 is a bit special: it is a placeholder for a connection initiated
569
            // by MAVSDK. As such, it should not be advertised as a newly discovered system.
570
            if (static_cast<int>(get_system_id()) != 0) {
66✔
571
                _mavsdk_impl.notify_on_discover();
66✔
572
            }
573

574
            // We call this later to avoid deadlocks on creating the server components.
575
            _mavsdk_impl.call_user_callback([this]() {
132✔
576
                // Send a heartbeat back immediately.
577
                _mavsdk_impl.start_sending_heartbeats();
578
            });
579

580
            register_timeout_handler(
66✔
581
                [this] { heartbeats_timed_out(); },
×
582
                HEARTBEAT_TIMEOUT_S,
583
                &_heartbeat_timeout_cookie);
584

585
            enable_needed = true;
66✔
586

587
            _is_connected_callbacks.queue(
66✔
588
                true, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
589

590
        } else if (_connected) {
16✔
591
            refresh_timeout_handler(_heartbeat_timeout_cookie);
16✔
592
        }
593
        // If not yet connected there is nothing to do/
594
    }
595
    if (enable_needed) {
82✔
596
        if (has_autopilot()) {
66✔
597
            send_autopilot_version_request_async(nullptr);
33✔
598
        }
599

600
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
132✔
601
        for (auto plugin_impl : _plugin_impls) {
66✔
602
            plugin_impl->enable();
×
603
        }
604
    }
605
}
82✔
606

607
void SystemImpl::set_disconnected()
×
608
{
609
    {
610
        std::lock_guard<std::mutex> lock(_connection_mutex);
×
611

612
        // This might not be needed because this is probably called from the triggered
613
        // timeout anyway, but it should also do no harm.
614
        // unregister_timeout_handler(_heartbeat_timeout_cookie);
615
        //_heartbeat_timeout_cookie = nullptr;
616

617
        _connected = false;
×
618
        _mavsdk_impl.notify_on_timeout();
×
619
        _is_connected_callbacks.queue(
×
620
            false, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
621
    }
622

623
    _mavsdk_impl.stop_sending_heartbeats();
×
624

625
    {
626
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
×
627
        for (auto plugin_impl : _plugin_impls) {
×
628
            plugin_impl->disable();
×
629
        }
630
    }
631
}
×
632

633
uint8_t SystemImpl::get_system_id() const
618✔
634
{
635
    return _target_address.system_id;
618✔
636
}
637

638
std::vector<uint8_t> SystemImpl::component_ids() const
×
639
{
640
    return std::vector<uint8_t>{_components.begin(), _components.end()};
×
641
}
642

643
void SystemImpl::set_system_id(uint8_t system_id)
34✔
644
{
645
    _target_address.system_id = system_id;
34✔
646
}
34✔
647

648
uint8_t SystemImpl::get_own_system_id() const
1,136✔
649
{
650
    return _mavsdk_impl.get_own_system_id();
1,136✔
651
}
652

653
uint8_t SystemImpl::get_own_component_id() const
1,136✔
654
{
655
    return _mavsdk_impl.get_own_component_id();
1,136✔
656
}
657

658
MAV_TYPE SystemImpl::get_vehicle_type() const
×
659
{
660
    return _vehicle_type;
×
661
}
662

663
uint8_t SystemImpl::get_own_mav_type() const
×
664
{
665
    return _mavsdk_impl.get_mav_type();
×
666
}
667

668
MavlinkParameterClient::Result SystemImpl::set_param(
×
669
    const std::string& name,
670
    ParamValue value,
671
    std::optional<uint8_t> maybe_component_id,
672
    bool extended)
673
{
674
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
675
        ->set_param(name, value);
×
676
}
677

678
MavlinkParameterClient::Result SystemImpl::set_param_float(
2✔
679
    const std::string& name, float value, std::optional<uint8_t> maybe_component_id, bool extended)
680
{
681
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
682
        ->set_param_float(name, value);
4✔
683
}
684

685
MavlinkParameterClient::Result SystemImpl::set_param_int(
2✔
686
    const std::string& name,
687
    int32_t value,
688
    std::optional<uint8_t> maybe_component_id,
689
    bool extended)
690
{
691
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
692
        ->set_param_int(name, value);
4✔
693
}
694

695
MavlinkParameterClient::Result SystemImpl::set_param_custom(
2✔
696
    const std::string& name, const std::string& value, std::optional<uint8_t> maybe_component_id)
697
{
698
    return param_sender(maybe_component_id.has_value() ? maybe_component_id.value() : 1, true)
4✔
699
        ->set_param_custom(name, value);
4✔
700
}
701

702
std::pair<MavlinkParameterClient::Result, std::map<std::string, ParamValue>>
703
SystemImpl::get_all_params(std::optional<uint8_t> maybe_component_id, bool extended)
4✔
704
{
705
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
4✔
706
        ->get_all_params();
8✔
707
}
708

709
void SystemImpl::set_param_async(
×
710
    const std::string& name,
711
    ParamValue value,
712
    const SetParamCallback& callback,
713
    const void* cookie,
714
    std::optional<uint8_t> maybe_component_id,
715
    bool extended)
716
{
717
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
718
        ->set_param_async(name, value, callback, cookie);
×
719
}
×
720

721
void SystemImpl::set_param_float_async(
×
722
    const std::string& name,
723
    float value,
724
    const SetParamCallback& callback,
725
    const void* cookie,
726
    std::optional<uint8_t> maybe_component_id,
727
    bool extended)
728
{
729
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
730
        ->set_param_float_async(name, value, callback, cookie);
×
731
}
×
732

733
void SystemImpl::set_param_int_async(
×
734
    const std::string& name,
735
    int32_t value,
736
    const SetParamCallback& callback,
737
    const void* cookie,
738
    std::optional<uint8_t> maybe_component_id,
739
    bool extended)
740
{
741
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
742
        ->set_param_int_async(name, value, callback, cookie);
×
743
}
×
744

745
std::pair<MavlinkParameterClient::Result, float> SystemImpl::get_param_float(
5✔
746
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
747
{
748
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
749
        ->get_param_float(name);
10✔
750
}
751

752
std::pair<MavlinkParameterClient::Result, int> SystemImpl::get_param_int(
5✔
753
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
754
{
755
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
756
        ->get_param_int(name);
10✔
757
}
758

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

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

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

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

800
void SystemImpl::get_param_custom_async(
×
801
    const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
802
{
803
    param_sender(1, false)->get_param_custom_async(name, callback, cookie);
×
804
}
×
805

806
void SystemImpl::cancel_all_param(const void* cookie)
2✔
807
{
808
    UNUSED(cookie);
2✔
809
    // FIXME: this currently crashes on destruction
810
    // param_sender(1, false)->cancel_all_param(cookie);
811
}
2✔
812

813
MavlinkCommandSender::Result
814
SystemImpl::set_flight_mode(FlightMode system_mode, uint8_t component_id)
×
815
{
816
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
817
        make_command_flight_mode(system_mode, component_id);
×
818

819
    if (result.first != MavlinkCommandSender::Result::Success) {
×
820
        return result.first;
×
821
    }
822

823
    return send_command(result.second);
×
824
}
825

826
void SystemImpl::set_flight_mode_async(
×
827
    FlightMode system_mode, const CommandResultCallback& callback, uint8_t component_id)
828
{
829
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
830
        make_command_flight_mode(system_mode, component_id);
×
831

832
    if (result.first != MavlinkCommandSender::Result::Success) {
×
833
        if (callback) {
×
834
            callback(result.first, NAN);
×
835
        }
836
        return;
×
837
    }
838

839
    send_command_async(result.second, callback);
×
840
}
841

842
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
843
SystemImpl::make_command_flight_mode(FlightMode flight_mode, uint8_t component_id)
×
844
{
845
    if (_autopilot == Autopilot::ArduPilot) {
×
846
        return make_command_ardupilot_mode(flight_mode, component_id);
×
847
    } else {
848
        return make_command_px4_mode(flight_mode, component_id);
×
849
    }
850
}
851

852
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
853
SystemImpl::make_command_ardupilot_mode(FlightMode flight_mode, uint8_t component_id)
×
854
{
855
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
856
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
857
    const uint8_t mode_type =
×
858
        MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
859

860
    MavlinkCommandSender::CommandLong command{};
×
861

862
    command.command = MAV_CMD_DO_SET_MODE;
×
863
    command.params.maybe_param1 = static_cast<float>(mode_type);
×
864

865
    switch (_vehicle_type) {
×
866
        case MAV_TYPE::MAV_TYPE_SURFACE_BOAT:
×
867
        case MAV_TYPE::MAV_TYPE_GROUND_ROVER: {
868
            const auto new_mode = flight_mode_to_ardupilot_rover_mode(flight_mode);
×
869
            if (new_mode == ardupilot::RoverMode::Unknown) {
×
870
                LogErr() << "Cannot translate flight mode to ArduPilot Rover mode.";
×
871
                MavlinkCommandSender::CommandLong empty_command{};
×
872
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
873
            } else {
874
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
875
            }
876
            break;
×
877
        }
878
        case MAV_TYPE::MAV_TYPE_FIXED_WING:
×
879
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
880
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
881
        case MAV_TYPE::MAV_TYPE_VTOL_TILTROTOR:
882
        case MAV_TYPE::MAV_TYPE_VTOL_FIXEDROTOR:
883
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER:
884
        case MAV_TYPE::MAV_TYPE_VTOL_TILTWING: {
885
            const auto new_mode = flight_mode_to_ardupilot_plane_mode(flight_mode);
×
886
            if (new_mode == ardupilot::PlaneMode::Unknown) {
×
887
                LogErr() << "Cannot translate flight mode to ArduPilot Plane mode.";
×
888
                MavlinkCommandSender::CommandLong empty_command{};
×
889
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
890
            } else {
891
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
892
            }
893
            break;
×
894
        }
895

896
        case MAV_TYPE::MAV_TYPE_QUADROTOR:
×
897
        case MAV_TYPE::MAV_TYPE_COAXIAL:
898
        case MAV_TYPE::MAV_TYPE_HELICOPTER:
899
        case MAV_TYPE::MAV_TYPE_HEXAROTOR:
900
        case MAV_TYPE::MAV_TYPE_OCTOROTOR:
901
        case MAV_TYPE::MAV_TYPE_TRICOPTER:
902
        case MAV_TYPE::MAV_TYPE_DODECAROTOR:
903
        case MAV_TYPE::MAV_TYPE_DECAROTOR: {
904
            const auto new_mode = flight_mode_to_ardupilot_copter_mode(flight_mode);
×
905
            if (new_mode == ardupilot::CopterMode::Unknown) {
×
906
                LogErr() << "Cannot translate flight mode to ArduPilot Copter mode.";
×
907
                MavlinkCommandSender::CommandLong empty_command{};
×
908
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
909
            } else {
910
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
911
            }
912
            break;
×
913
        }
914

915
        default:
×
916
            LogErr() << "Cannot translate flight mode to ArduPilot mode, for MAV_TYPE: "
×
917
                     << _vehicle_type;
×
918
            MavlinkCommandSender::CommandLong empty_command{};
×
919
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
920
    }
921
    command.target_component_id = component_id;
×
922

923
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
924
}
925
ardupilot::RoverMode SystemImpl::flight_mode_to_ardupilot_rover_mode(FlightMode flight_mode)
×
926
{
927
    switch (flight_mode) {
×
928
        case FlightMode::Mission:
×
929
            return ardupilot::RoverMode::Auto;
×
930
        case FlightMode::Acro:
×
931
            return ardupilot::RoverMode::Acro;
×
932
        case FlightMode::Hold:
×
933
            return ardupilot::RoverMode::Hold;
×
934
        case FlightMode::ReturnToLaunch:
×
935
            return ardupilot::RoverMode::RTL;
×
936
        case FlightMode::Manual:
×
937
            return ardupilot::RoverMode::Manual;
×
938
        case FlightMode::FollowMe:
×
939
            return ardupilot::RoverMode::Follow;
×
940
        case FlightMode::Offboard:
×
941
            return ardupilot::RoverMode::Guided;
×
942
        case FlightMode::Unknown:
×
943
        case FlightMode::Ready:
944
        case FlightMode::Takeoff:
945
        case FlightMode::Land:
946
        case FlightMode::Altctl:
947
        case FlightMode::Posctl:
948
        case FlightMode::Rattitude:
949
        case FlightMode::Stabilized:
950
        default:
951
            return ardupilot::RoverMode::Unknown;
×
952
    }
953
}
954
ardupilot::CopterMode SystemImpl::flight_mode_to_ardupilot_copter_mode(FlightMode flight_mode)
×
955
{
956
    switch (flight_mode) {
×
957
        case FlightMode::Mission:
×
958
            return ardupilot::CopterMode::Auto;
×
959
        case FlightMode::Acro:
×
960
            return ardupilot::CopterMode::Acro;
×
961
        case FlightMode::Hold:
×
962
            return ardupilot::CopterMode::Loiter;
×
963
        case FlightMode::ReturnToLaunch:
×
964
            return ardupilot::CopterMode::Rtl;
×
965
        case FlightMode::Land:
×
966
            return ardupilot::CopterMode::Land;
×
967
        case FlightMode::Manual:
×
968
            return ardupilot::CopterMode::Stabilize;
×
969
        case FlightMode::FollowMe:
×
970
            return ardupilot::CopterMode::Follow;
×
971
        case FlightMode::Offboard:
×
972
            return ardupilot::CopterMode::Guided;
×
973
        case FlightMode::Altctl:
×
974
            return ardupilot::CopterMode::AltHold;
×
975
        case FlightMode::Posctl:
×
976
            return ardupilot::CopterMode::PosHold;
×
977
        case FlightMode::Stabilized:
×
978
            return ardupilot::CopterMode::Stabilize;
×
979
        case FlightMode::Unknown:
×
980
        case FlightMode::Ready:
981
        case FlightMode::Takeoff:
982
        case FlightMode::Rattitude:
983
        default:
984
            return ardupilot::CopterMode::Unknown;
×
985
    }
986
}
987
ardupilot::PlaneMode SystemImpl::flight_mode_to_ardupilot_plane_mode(FlightMode flight_mode)
×
988
{
989
    switch (flight_mode) {
×
990
        case FlightMode::Mission:
×
991
            return ardupilot::PlaneMode::Auto;
×
992
        case FlightMode::Acro:
×
993
            return ardupilot::PlaneMode::Acro;
×
994
        case FlightMode::Hold:
×
995
            return ardupilot::PlaneMode::Loiter;
×
996
        case FlightMode::ReturnToLaunch:
×
997
            return ardupilot::PlaneMode::Rtl;
×
998
        case FlightMode::Manual:
×
999
            return ardupilot::PlaneMode::Manual;
×
1000
        case FlightMode::FBWA:
×
1001
            return ardupilot::PlaneMode::Fbwa;
×
1002
        case FlightMode::Stabilized:
×
1003
            return ardupilot::PlaneMode::Stabilize;
×
1004
        case FlightMode::Unknown:
×
1005
            return ardupilot::PlaneMode::Unknown;
×
1006
        default:
×
1007
            return ardupilot::PlaneMode::Unknown;
×
1008
    }
1009
}
1010

1011
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
1012
SystemImpl::make_command_px4_mode(FlightMode flight_mode, uint8_t component_id)
×
1013
{
1014
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
1015
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
1016

1017
    const uint8_t mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
1018

1019
    // Note: the safety flag is not needed in future versions of the PX4 Firmware
1020
    //       but want to be rather safe than sorry.
1021
    uint8_t custom_mode = px4::PX4_CUSTOM_MAIN_MODE_AUTO;
×
1022
    uint8_t custom_sub_mode = 0;
×
1023

1024
    switch (flight_mode) {
×
1025
        case FlightMode::Hold:
×
1026
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
×
1027
            break;
×
1028
        case FlightMode::ReturnToLaunch:
×
1029
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_RTL;
×
1030
            break;
×
1031
        case FlightMode::Takeoff:
×
1032
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
×
1033
            break;
×
1034
        case FlightMode::Land:
×
1035
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LAND;
×
1036
            break;
×
1037
        case FlightMode::Mission:
×
1038
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
×
1039
            break;
×
1040
        case FlightMode::FollowMe:
×
1041
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET;
×
1042
            break;
×
1043
        case FlightMode::Offboard:
×
1044
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_OFFBOARD;
×
1045
            break;
×
1046
        case FlightMode::Manual:
×
1047
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_MANUAL;
×
1048
            break;
×
1049
        case FlightMode::Posctl:
×
1050
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_POSCTL;
×
1051
            break;
×
1052
        case FlightMode::Altctl:
×
1053
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ALTCTL;
×
1054
            break;
×
1055
        case FlightMode::Rattitude:
×
1056
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_RATTITUDE;
×
1057
            break;
×
1058
        case FlightMode::Acro:
×
1059
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ACRO;
×
1060
            break;
×
1061
        case FlightMode::Stabilized:
×
1062
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_STABILIZED;
×
1063
            break;
×
1064
        default:
×
1065
            LogErr() << "Unknown Flight mode.";
×
1066
            MavlinkCommandSender::CommandLong empty_command{};
×
1067
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
1068
    }
1069

1070
    MavlinkCommandSender::CommandLong command{};
×
1071

1072
    command.command = MAV_CMD_DO_SET_MODE;
×
1073
    command.params.maybe_param1 = static_cast<float>(mode);
×
1074
    command.params.maybe_param2 = static_cast<float>(custom_mode);
×
1075
    command.params.maybe_param3 = static_cast<float>(custom_sub_mode);
×
1076
    command.target_component_id = component_id;
×
1077

1078
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
1079
}
1080

1081
FlightMode SystemImpl::get_flight_mode() const
6✔
1082
{
1083
    return _flight_mode;
6✔
1084
}
1085

1086
void SystemImpl::receive_float_param(
×
1087
    MavlinkParameterClient::Result result, ParamValue value, const GetParamFloatCallback& callback)
1088
{
1089
    if (callback) {
×
1090
        if (result == MavlinkParameterClient::Result::Success) {
×
1091
            callback(result, value.get<float>());
×
1092
        } else {
1093
            callback(result, NAN);
×
1094
        }
1095
    }
1096
}
×
1097

1098
void SystemImpl::receive_int_param(
×
1099
    MavlinkParameterClient::Result result, ParamValue value, const GetParamIntCallback& callback)
1100
{
1101
    if (callback) {
×
1102
        if (result == MavlinkParameterClient::Result::Success) {
×
1103
            callback(result, value.get<int32_t>());
×
1104
        } else {
1105
            callback(result, 0);
×
1106
        }
1107
    }
1108
}
×
1109

1110
uint8_t SystemImpl::get_autopilot_id() const
675✔
1111
{
1112
    for (auto compid : _components)
709✔
1113
        if (compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
675✔
1114
            return compid;
641✔
1115
        }
1116
    // FIXME: Not sure what should be returned if autopilot is not found
1117
    return uint8_t(0);
34✔
1118
}
1119

1120
std::vector<uint8_t> SystemImpl::get_camera_ids() const
×
1121
{
1122
    std::vector<uint8_t> camera_ids{};
×
1123

1124
    for (auto compid : _components)
×
1125
        if (compid >= MAV_COMP_ID_CAMERA && compid <= MAV_COMP_ID_CAMERA6) {
×
1126
            camera_ids.push_back(compid);
×
1127
        }
1128
    return camera_ids;
×
1129
}
1130

1131
uint8_t SystemImpl::get_gimbal_id() const
×
1132
{
1133
    for (auto compid : _components)
×
1134
        if (compid == MAV_COMP_ID_GIMBAL) {
×
1135
            return compid;
×
1136
        }
1137
    return uint8_t(0);
×
1138
}
1139

1140
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandLong& command)
×
1141
{
1142
    if (_target_address.system_id == 0 && _components.empty()) {
×
1143
        return MavlinkCommandSender::Result::NoSystem;
×
1144
    }
1145
    command.target_system_id = get_system_id();
×
1146
    return _command_sender.send_command(command);
×
1147
}
1148

1149
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandInt& command)
×
1150
{
1151
    if (_target_address.system_id == 0 && _components.empty()) {
×
1152
        return MavlinkCommandSender::Result::NoSystem;
×
1153
    }
1154
    command.target_system_id = get_system_id();
×
1155
    return _command_sender.send_command(command);
×
1156
}
1157

1158
void SystemImpl::send_command_async(
38✔
1159
    MavlinkCommandSender::CommandLong command, const CommandResultCallback& callback)
1160
{
1161
    if (_target_address.system_id == 0 && _components.empty()) {
38✔
1162
        if (callback) {
×
1163
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1164
        }
1165
        return;
×
1166
    }
1167
    command.target_system_id = get_system_id();
38✔
1168

1169
    _command_sender.queue_command_async(command, callback);
38✔
1170
}
1171

1172
void SystemImpl::send_command_async(
×
1173
    MavlinkCommandSender::CommandInt command, const CommandResultCallback& callback)
1174
{
1175
    if (_target_address.system_id == 0 && _components.empty()) {
×
1176
        if (callback) {
×
1177
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1178
        }
1179
        return;
×
1180
    }
1181
    command.target_system_id = get_system_id();
×
1182

1183
    _command_sender.queue_command_async(command, callback);
×
1184
}
1185

1186
MavlinkCommandSender::Result
1187
SystemImpl::set_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
×
1188
{
1189
    MavlinkCommandSender::CommandLong command =
×
1190
        make_command_msg_rate(message_id, rate_hz, component_id);
×
1191
    return send_command(command);
×
1192
}
1193

1194
void SystemImpl::set_msg_rate_async(
1✔
1195
    uint16_t message_id,
1196
    double rate_hz,
1197
    const CommandResultCallback& callback,
1198
    uint8_t component_id)
1199
{
1200
    MavlinkCommandSender::CommandLong command =
1✔
1201
        make_command_msg_rate(message_id, rate_hz, component_id);
1✔
1202
    send_command_async(command, callback);
1✔
1203
}
1✔
1204

1205
MavlinkCommandSender::CommandLong
1206
SystemImpl::make_command_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
1✔
1207
{
1208
    MavlinkCommandSender::CommandLong command{};
1✔
1209

1210
    // 0 to request default rate, -1 to stop stream
1211

1212
    float interval_us = 0.0f;
1✔
1213

1214
    if (rate_hz > 0) {
1✔
1215
        interval_us = 1e6f / static_cast<float>(rate_hz);
1✔
1216
    } else if (rate_hz < 0) {
×
1217
        interval_us = -1.0f;
×
1218
    }
1219

1220
    command.command = MAV_CMD_SET_MESSAGE_INTERVAL;
1✔
1221
    command.params.maybe_param1 = static_cast<float>(message_id);
1✔
1222
    command.params.maybe_param2 = interval_us;
1✔
1223
    command.target_component_id = component_id;
1✔
1224

1225
    return command;
1✔
1226
}
1227

1228
void SystemImpl::register_plugin(PluginImplBase* plugin_impl)
36✔
1229
{
1230
    assert(plugin_impl);
36✔
1231

1232
    plugin_impl->init();
36✔
1233

1234
    {
1235
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
72✔
1236
        _plugin_impls.push_back(plugin_impl);
36✔
1237
    }
1238

1239
    // If we're connected already, let's enable it straightaway.
1240
    if (_connected) {
36✔
1241
        plugin_impl->enable();
36✔
1242
    }
1243
}
36✔
1244

1245
void SystemImpl::unregister_plugin(PluginImplBase* plugin_impl)
36✔
1246
{
1247
    assert(plugin_impl);
36✔
1248

1249
    plugin_impl->disable();
36✔
1250
    plugin_impl->deinit();
36✔
1251

1252
    // Remove first, so it won't get enabled/disabled anymore.
1253
    {
1254
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
72✔
1255
        auto found = std::find(_plugin_impls.begin(), _plugin_impls.end(), plugin_impl);
36✔
1256
        if (found != _plugin_impls.end()) {
36✔
1257
            _plugin_impls.erase(found);
36✔
1258
        }
1259
    }
1260
}
36✔
1261

1262
void SystemImpl::call_user_callback_located(
16✔
1263
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1264
{
1265
    _mavsdk_impl.call_user_callback_located(filename, linenumber, func);
16✔
1266
}
16✔
1267

1268
void SystemImpl::param_changed(const std::string& name)
×
1269
{
1270
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1271

1272
    for (auto& callback : _param_changed_callbacks) {
×
1273
        callback.second(name);
×
1274
    }
1275
}
×
1276

1277
void SystemImpl::register_param_changed_handler(
1✔
1278
    const ParamChangedCallback& callback, const void* cookie)
1279
{
1280
    if (!callback) {
1✔
1281
        LogErr() << "No callback for param_changed_handler supplied.";
×
1282
        return;
×
1283
    }
1284

1285
    if (!cookie) {
1✔
1286
        LogErr() << "No callback for param_changed_handler supplied.";
×
1287
        return;
×
1288
    }
1289

1290
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
2✔
1291

1292
    _param_changed_callbacks[cookie] = callback;
1✔
1293
}
1294

1295
void SystemImpl::unregister_param_changed_handler(const void* cookie)
1✔
1296
{
1297
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
1✔
1298

1299
    auto it = _param_changed_callbacks.find(cookie);
1✔
1300
    if (it == _param_changed_callbacks.end()) {
1✔
1301
        LogWarn() << "param_changed_handler for cookie not found";
×
1302
        return;
×
1303
    }
1304
    _param_changed_callbacks.erase(it);
1✔
1305
}
1306

1307
Time& SystemImpl::get_time()
81✔
1308
{
1309
    return _mavsdk_impl.time;
81✔
1310
}
1311

1312
void SystemImpl::subscribe_param_float(
×
1313
    const std::string& name,
1314
    const MavlinkParameterClient::ParamFloatChangedCallback& callback,
1315
    const void* cookie)
1316
{
1317
    param_sender(1, false)->subscribe_param_float_changed(name, callback, cookie);
×
1318
}
×
1319

1320
void SystemImpl::subscribe_param_int(
×
1321
    const std::string& name,
1322
    const MavlinkParameterClient::ParamIntChangedCallback& callback,
1323
    const void* cookie)
1324
{
1325
    param_sender(1, false)->subscribe_param_int_changed(name, callback, cookie);
×
1326
}
×
1327
void SystemImpl::subscribe_param_custom(
×
1328
    const std::string& name,
1329
    const MavlinkParameterClient::ParamCustomChangedCallback& callback,
1330
    const void* cookie)
1331
{
1332
    param_sender(1, false)->subscribe_param_custom_changed(name, callback, cookie);
×
1333
}
×
1334

1335
MavlinkParameterClient* SystemImpl::param_sender(uint8_t component_id, bool extended)
24✔
1336
{
1337
    std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
48✔
1338

1339
    for (auto& entry : _mavlink_parameter_clients) {
26✔
1340
        if (entry.component_id == component_id && entry.extended == extended) {
18✔
1341
            return entry.parameter_client.get();
16✔
1342
        }
1343
    }
1344

1345
    _mavlink_parameter_clients.push_back(
16✔
1346
        {std::make_unique<MavlinkParameterClient>(
1347
             _mavsdk_impl.default_server_component_impl().sender(),
8✔
1348
             _mavlink_message_handler,
8✔
1349
             _mavsdk_impl.timeout_handler,
8✔
1350
             [this]() { return timeout_s(); },
43✔
1351
             get_system_id(),
16✔
1352
             component_id,
1353
             extended),
1354
         component_id,
1355
         extended});
1356

1357
    return _mavlink_parameter_clients.back().parameter_client.get();
8✔
1358
}
1359

1360
} // namespace mavsdk
STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2026 Coveralls, Inc