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

mavlink / MAVSDK / 5227557003

pending completion
5227557003

push

github

web-flow
Merge pull request #2077 from mavlink/pr-remove-always-connected

core: remove always connected flag

10 of 10 new or added lines in 3 files covered. (100.0%)

7689 of 24891 relevant lines covered (30.89%)

21.06 hits per line

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

40.2
/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 "plugin_impl_base.h"
6
#include "px4_custom_mode.h"
7
#include "ardupilot_custom_mode.h"
8
#include "request_message.h"
9
#include "callback_list.tpp"
10
#include "unused.h"
11
#include <cassert>
12
#include <cstdlib>
13
#include <functional>
14
#include <future>
15
#include <utility>
16

17
namespace mavsdk {
18

19
template class CallbackList<bool>;
20
template class CallbackList<System::ComponentType>;
21
template class CallbackList<System::ComponentType, uint8_t>;
22

23
SystemImpl::SystemImpl(MavsdkImpl& parent) :
20✔
24
    Sender(),
25
    _mavsdk_impl(parent),
26
    _command_sender(*this),
27
    _timesync(*this),
28
    _ping(*this),
29
    _mission_transfer(
30
        *this,
31
        _mavsdk_impl.mavlink_message_handler,
20✔
32
        _mavsdk_impl.timeout_handler,
20✔
33
        [this]() { return timeout_s(); }),
1✔
34
    _request_message(
35
        *this, _command_sender, _mavsdk_impl.mavlink_message_handler, _mavsdk_impl.timeout_handler),
20✔
36
    _mavlink_ftp(*this)
20✔
37
{
38
    _system_thread = new std::thread(&SystemImpl::system_thread, this);
20✔
39
}
20✔
40

41
SystemImpl::~SystemImpl()
20✔
42
{
43
    _should_exit = true;
20✔
44
    _mavsdk_impl.mavlink_message_handler.unregister_all(this);
20✔
45

46
    unregister_timeout_handler(_heartbeat_timeout_cookie);
20✔
47

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

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

61
    _mavsdk_impl.mavlink_message_handler.register_one(
20✔
62
        MAVLINK_MSG_ID_HEARTBEAT,
63
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
20✔
64
        this);
65

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

71
    _mavsdk_impl.mavlink_message_handler.register_one(
20✔
72
        MAVLINK_MSG_ID_AUTOPILOT_VERSION,
73
        [this](const mavlink_message_t& message) { process_autopilot_version(message); },
10✔
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);
20✔
92
}
20✔
93

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

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

105
void SystemImpl::register_mavlink_message_handler(
7✔
106
    uint16_t msg_id, uint8_t cmp_id, const MavlinkMessageHandler& callback, const void* cookie)
107
{
108
    _mavsdk_impl.mavlink_message_handler.register_one(msg_id, cmp_id, callback, cookie);
7✔
109
}
7✔
110

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

116
void SystemImpl::unregister_all_mavlink_message_handlers(const void* cookie)
64✔
117
{
118
    _mavsdk_impl.mavlink_message_handler.unregister_all(cookie);
64✔
119
}
64✔
120

121
void SystemImpl::update_componentid_messages_handler(
×
122
    uint16_t msg_id, uint8_t cmp_id, const void* cookie)
123
{
124
    _mavsdk_impl.mavlink_message_handler.update_component_id(msg_id, cmp_id, cookie);
×
125
}
×
126

127
void SystemImpl::register_timeout_handler(
34✔
128
    const std::function<void()>& callback, double duration_s, void** cookie)
129
{
130
    _mavsdk_impl.timeout_handler.add(callback, duration_s, cookie);
34✔
131
}
34✔
132

133
void SystemImpl::refresh_timeout_handler(const void* cookie)
2✔
134
{
135
    _mavsdk_impl.timeout_handler.refresh(cookie);
2✔
136
}
2✔
137

138
void SystemImpl::unregister_timeout_handler(const void* cookie)
34✔
139
{
140
    _mavsdk_impl.timeout_handler.remove(cookie);
34✔
141
}
34✔
142

143
double SystemImpl::timeout_s() const
60✔
144
{
145
    return _mavsdk_impl.timeout_s();
60✔
146
}
147

148
void SystemImpl::enable_timesync()
×
149
{
150
    _timesync.enable();
×
151
}
×
152

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

160
void SystemImpl::unsubscribe_is_connected(System::IsConnectedHandle handle)
×
161
{
162
    _is_connected_callbacks.unsubscribe(handle);
×
163
}
×
164

165
void SystemImpl::add_call_every(std::function<void()> callback, float interval_s, void** cookie)
4✔
166
{
167
    _mavsdk_impl.call_every_handler.add(
8✔
168
        std::move(callback), static_cast<double>(interval_s), cookie);
4✔
169
}
4✔
170

171
void SystemImpl::change_call_every(float interval_s, const void* cookie)
×
172
{
173
    _mavsdk_impl.call_every_handler.change(static_cast<double>(interval_s), cookie);
×
174
}
×
175

176
void SystemImpl::reset_call_every(const void* cookie)
×
177
{
178
    _mavsdk_impl.call_every_handler.reset(cookie);
×
179
}
×
180

181
void SystemImpl::remove_call_every(const void* cookie)
10✔
182
{
183
    _mavsdk_impl.call_every_handler.remove(cookie);
10✔
184
}
10✔
185

186
void SystemImpl::register_statustext_handler(
1✔
187
    std::function<void(const MavlinkStatustextHandler::Statustext&)> callback, void* cookie)
188
{
189
    std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
2✔
190
    _statustext_handler_callbacks.push_back(StatustextCallback{std::move(callback), cookie});
1✔
191
}
1✔
192

193
void SystemImpl::unregister_statustext_handler(void* cookie)
1✔
194
{
195
    std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
2✔
196
    _statustext_handler_callbacks.erase(std::remove_if(
1✔
197
        _statustext_handler_callbacks.begin(),
198
        _statustext_handler_callbacks.end(),
199
        [&](const auto& entry) { return entry.cookie == cookie; }));
2✔
200
}
1✔
201

202
void SystemImpl::process_heartbeat(const mavlink_message_t& message)
20✔
203
{
204
    mavlink_heartbeat_t heartbeat;
20✔
205
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
20✔
206

207
    if (heartbeat.autopilot == MAV_AUTOPILOT_PX4) {
20✔
208
        _autopilot = Autopilot::Px4;
×
209
    } else if (heartbeat.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
20✔
210
        _autopilot = Autopilot::ArduPilot;
×
211
    }
212

213
    // Only set the vehicle type if the heartbeat is from an autopilot component
214
    // This check only works if the MAV_TYPE::MAV_TYPE_ENUM_END is actually the
215
    // last enumerator.
216
    if (MAV_TYPE::MAV_TYPE_ENUM_END < heartbeat.type) {
20✔
217
        LogErr() << "type received in HEARTBEAT was not recognized";
×
218
    } else {
219
        const auto new_vehicle_type = static_cast<MAV_TYPE>(heartbeat.type);
20✔
220
        if (heartbeat.autopilot != MAV_AUTOPILOT_INVALID && _vehicle_type != new_vehicle_type &&
20✔
221
            new_vehicle_type != MAV_TYPE_GENERIC) {
222
            LogWarn() << "Vehicle type changed (new type: " << static_cast<unsigned>(heartbeat.type)
×
223
                      << ", old type: " << static_cast<unsigned>(_vehicle_type) << ")";
×
224
            _vehicle_type = new_vehicle_type;
×
225
        }
226
    }
227

228
    if (message.compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
20✔
229
        _armed = (heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) != 0;
10✔
230
        _hitl_enabled = (heartbeat.base_mode & MAV_MODE_FLAG_HIL_ENABLED) != 0;
10✔
231
    }
232
    if (heartbeat.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
20✔
233
        _flight_mode =
×
234
            to_flight_mode_from_custom_mode(_autopilot, _vehicle_type, heartbeat.custom_mode);
235
    }
236

237
    set_connected();
20✔
238
}
20✔
239

240
void SystemImpl::process_statustext(const mavlink_message_t& message)
3✔
241
{
242
    mavlink_statustext_t statustext;
3✔
243
    mavlink_msg_statustext_decode(&message, &statustext);
3✔
244

245
    const auto maybe_result = _statustext_handler.process(statustext);
6✔
246

247
    if (maybe_result.has_value()) {
3✔
248
        LogDebug() << "MAVLink: "
6✔
249
                   << MavlinkStatustextHandler::severity_str(maybe_result.value().severity) << ": "
6✔
250
                   << maybe_result.value().text;
9✔
251

252
        std::lock_guard<std::mutex> lock(_statustext_handler_callbacks_mutex);
6✔
253
        for (const auto& entry : _statustext_handler_callbacks) {
6✔
254
            entry.callback(maybe_result.value());
3✔
255
        }
256
    }
257
}
3✔
258

259
void SystemImpl::process_autopilot_version(const mavlink_message_t& message)
10✔
260
{
261
    mavlink_autopilot_version_t autopilot_version;
10✔
262
    mavlink_msg_autopilot_version_decode(&message, &autopilot_version);
10✔
263

264
    _mission_transfer.set_int_messages_supported(
10✔
265
        autopilot_version.capabilities & MAV_PROTOCOL_CAPABILITY_MISSION_INT);
10✔
266
}
10✔
267

268
void SystemImpl::heartbeats_timed_out()
×
269
{
270
    LogInfo() << "heartbeats timed out";
×
271
    set_disconnected();
×
272
}
×
273

274
void SystemImpl::system_thread()
20✔
275
{
276
    SteadyTimePoint last_ping_time{};
20✔
277

278
    while (!_should_exit) {
629✔
279
        {
280
            std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
1,218✔
281
            for (auto& entry : _mavlink_parameter_clients) {
916✔
282
                entry.parameter_client->do_work();
307✔
283
            }
284
        }
285
        _command_sender.do_work();
609✔
286
        _timesync.do_work();
609✔
287
        _mission_transfer.do_work();
609✔
288

289
        if (_mavsdk_impl.time.elapsed_since_s(last_ping_time) >= SystemImpl::_ping_interval_s) {
609✔
290
            if (_connected) {
20✔
291
                _ping.run_once();
×
292
            }
293
            last_ping_time = _mavsdk_impl.time.steady_time();
20✔
294
        }
295

296
        if (_connected) {
609✔
297
            // Work fairly fast if we're connected.
298
            std::this_thread::sleep_for(std::chrono::milliseconds(10));
559✔
299
        } else {
300
            // Be less aggressive when unconnected.
301
            std::this_thread::sleep_for(std::chrono::milliseconds(100));
50✔
302
        }
303
    }
304
}
20✔
305

306
// std::optional<mavlink_message_t>
307
// SystemImpl::process_autopilot_version_request(const MavlinkCommandReceiver::CommandLong& command)
308
//{
309
//    if (_should_send_autopilot_version) {
310
//        send_autopilot_version();
311
//        return make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED);
312
//    }
313
//
314
//    return {};
315
//}
316

317
std::string SystemImpl::component_name(uint8_t component_id)
20✔
318
{
319
    switch (component_id) {
20✔
320
        case MAV_COMP_ID_AUTOPILOT1:
9✔
321
            return "Autopilot";
9✔
322
        case MAV_COMP_ID_CAMERA:
1✔
323
            return "Camera 1";
1✔
324
        case MAV_COMP_ID_CAMERA2:
×
325
            return "Camera 2";
×
326
        case MAV_COMP_ID_CAMERA3:
×
327
            return "Camera 3";
×
328
        case MAV_COMP_ID_CAMERA4:
×
329
            return "Camera 4";
×
330
        case MAV_COMP_ID_CAMERA5:
×
331
            return "Camera 5";
×
332
        case MAV_COMP_ID_CAMERA6:
×
333
            return "Camera 6";
×
334
        case MAV_COMP_ID_GIMBAL:
×
335
            return "Gimbal";
×
336
        case MAV_COMP_ID_MISSIONPLANNER:
10✔
337
            return "Ground station";
10✔
338
        case MAV_COMP_ID_WINCH:
×
339
            return "Winch";
×
340
        default:
×
341
            return "Unsupported component";
×
342
    }
343
}
344

345
System::ComponentType SystemImpl::component_type(uint8_t component_id)
40✔
346
{
347
    switch (component_id) {
40✔
348
        case MAV_COMP_ID_AUTOPILOT1:
18✔
349
            return System::ComponentType::AUTOPILOT;
18✔
350
        case MAV_COMP_ID_CAMERA:
2✔
351
        case MAV_COMP_ID_CAMERA2:
352
        case MAV_COMP_ID_CAMERA3:
353
        case MAV_COMP_ID_CAMERA4:
354
        case MAV_COMP_ID_CAMERA5:
355
        case MAV_COMP_ID_CAMERA6:
356
            return System::ComponentType::CAMERA;
2✔
357
        case MAV_COMP_ID_GIMBAL:
×
358
            return System::ComponentType::GIMBAL;
×
359
        default:
20✔
360
            return System::ComponentType::UNKNOWN;
20✔
361
    }
362
}
363

364
void SystemImpl::add_new_component(uint8_t component_id)
181✔
365
{
366
    if (component_id == 0) {
181✔
367
        return;
10✔
368
    }
369

370
    auto res_pair = _components.insert(component_id);
171✔
371
    if (res_pair.second) {
171✔
372
        std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
40✔
373
        _component_discovered_callbacks.queue(
20✔
374
            component_type(component_id), [this](const auto& func) { call_user_callback(func); });
×
375
        _component_discovered_id_callbacks.queue(
20✔
376
            component_type(component_id), component_id, [this](const auto& func) {
×
377
                call_user_callback(func);
×
378
            });
×
379
        LogDebug() << "Component " << component_name(component_id) << " (" << int(component_id)
80✔
380
                   << ") added.";
80✔
381
    }
382
}
383

384
size_t SystemImpl::total_components() const
×
385
{
386
    return _components.size();
×
387
}
388

389
System::ComponentDiscoveredHandle
390
SystemImpl::subscribe_component_discovered(const System::ComponentDiscoveredCallback& callback)
×
391
{
392
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
393
    const auto handle = _component_discovered_callbacks.subscribe(callback);
×
394

395
    if (total_components() > 0) {
×
396
        for (const auto& elem : _components) {
×
397
            _component_discovered_callbacks.queue(
×
398
                component_type(elem), [this](const auto& func) { call_user_callback(func); });
×
399
        }
400
    }
401
    return handle;
×
402
}
403

404
void SystemImpl::unsubscribe_component_discovered(System::ComponentDiscoveredHandle handle)
×
405
{
406
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
407
    _component_discovered_callbacks.unsubscribe(handle);
×
408
}
×
409

410
System::ComponentDiscoveredIdHandle
411
SystemImpl::subscribe_component_discovered_id(const System::ComponentDiscoveredIdCallback& callback)
×
412
{
413
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
414
    const auto handle = _component_discovered_id_callbacks.subscribe(callback);
×
415

416
    if (total_components() > 0) {
×
417
        for (const auto& elem : _components) {
×
418
            _component_discovered_id_callbacks.queue(
×
419
                component_type(elem), elem, [this](const auto& func) { call_user_callback(func); });
×
420
        }
421
    }
422
    return handle;
×
423
}
424

425
void SystemImpl::unsubscribe_component_discovered_id(System::ComponentDiscoveredIdHandle handle)
×
426
{
427
    std::lock_guard<std::mutex> lock(_component_discovered_callback_mutex);
×
428
    _component_discovered_id_callbacks.unsubscribe(handle);
×
429
}
×
430

431
bool SystemImpl::is_standalone() const
×
432
{
433
    return !has_autopilot();
×
434
}
435

436
bool SystemImpl::has_autopilot() const
37✔
437
{
438
    return get_autopilot_id() != uint8_t(0);
37✔
439
}
440

441
bool SystemImpl::is_autopilot(uint8_t comp_id)
×
442
{
443
    return comp_id == MAV_COMP_ID_AUTOPILOT1;
×
444
}
445

446
bool SystemImpl::is_camera(uint8_t comp_id)
1✔
447
{
448
    return (comp_id >= MAV_COMP_ID_CAMERA) && (comp_id <= MAV_COMP_ID_CAMERA6);
1✔
449
}
450

451
bool SystemImpl::has_camera(int camera_id) const
1✔
452
{
453
    int camera_comp_id = (camera_id == -1) ? camera_id : (MAV_COMP_ID_CAMERA + camera_id);
1✔
454

455
    if (camera_comp_id == -1) { // Check whether the system has any camera.
1✔
456
        if (std::any_of(_components.begin(), _components.end(), is_camera)) {
1✔
457
            return true;
1✔
458
        }
459
    } else { // Look for the camera whose id is `camera_id`.
460
        for (auto compid : _components) {
×
461
            if (compid == camera_comp_id) {
×
462
                return true;
×
463
            }
464
        }
465
    }
466
    return false;
×
467
}
468

469
bool SystemImpl::has_gimbal() const
×
470
{
471
    return get_gimbal_id() == MAV_COMP_ID_GIMBAL;
×
472
}
473

474
bool SystemImpl::send_message(mavlink_message_t& message)
66✔
475
{
476
    return _mavsdk_impl.send_message(message);
66✔
477
}
478

479
void SystemImpl::send_autopilot_version_request()
×
480
{
481
    auto prom = std::promise<MavlinkCommandSender::Result>();
×
482
    auto fut = prom.get_future();
×
483

484
    send_autopilot_version_request_async(
×
485
        [&prom](MavlinkCommandSender::Result result, float) { prom.set_value(result); });
×
486

487
    if (fut.get() == MavlinkCommandSender::Result::Unsupported) {
×
488
        _old_message_520_supported = false;
×
489
        LogWarn() << "Trying alternative command (512).";
×
490
        send_autopilot_version_request();
×
491
    }
492
}
×
493

494
void SystemImpl::send_autopilot_version_request_async(
9✔
495
    const MavlinkCommandSender::CommandResultCallback& callback)
496
{
497
    MavlinkCommandSender::CommandLong command{};
9✔
498
    command.target_component_id = get_autopilot_id();
9✔
499

500
    if (_old_message_520_supported) {
9✔
501
        // Note: This MAVLINK message is deprecated and would be removed from MAVSDK in a future
502
        // release.
503
        command.command = MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES;
9✔
504
        command.params.maybe_param1 = 1.0f;
9✔
505
    } else {
506
        command.command = MAV_CMD_REQUEST_MESSAGE;
×
507
        command.params.maybe_param1 = {static_cast<float>(MAVLINK_MSG_ID_AUTOPILOT_VERSION)};
×
508
    }
509

510
    send_command_async(command, callback);
9✔
511
}
9✔
512

513
void SystemImpl::send_flight_information_request()
×
514
{
515
    auto prom = std::promise<MavlinkCommandSender::Result>();
×
516
    auto fut = prom.get_future();
×
517

518
    MavlinkCommandSender::CommandLong command{};
×
519
    command.target_component_id = get_autopilot_id();
×
520

521
    if (_old_message_528_supported) {
×
522
        // Note: This MAVLINK message is deprecated and would be removed from MAVSDK in a future
523
        // release.
524
        command.command = MAV_CMD_REQUEST_FLIGHT_INFORMATION;
×
525
        command.params.maybe_param1 = 1.0f;
×
526
    } else {
527
        command.command = MAV_CMD_REQUEST_MESSAGE;
×
528
        command.params.maybe_param1 = {static_cast<float>(MAVLINK_MSG_ID_FLIGHT_INFORMATION)};
×
529
    }
530

531
    send_command_async(
×
532
        command, [&prom](MavlinkCommandSender::Result result, float) { prom.set_value(result); });
×
533
    if (fut.get() == MavlinkCommandSender::Result::Unsupported) {
×
534
        _old_message_528_supported = false;
×
535
        LogWarn() << "Trying alternative command (512)..";
×
536
        send_flight_information_request();
×
537
    }
538
}
×
539

540
void SystemImpl::set_connected()
20✔
541
{
542
    bool enable_needed = false;
20✔
543
    {
544
        std::lock_guard<std::mutex> lock(_connection_mutex);
40✔
545

546
        if (!_connected) {
20✔
547
            if (!_components.empty()) {
18✔
548
                LogDebug() << "Discovered " << _components.size() << " component(s)";
18✔
549
            }
550

551
            _connected = true;
18✔
552

553
            // System with sysid 0 is a bit special: it is a placeholder for a connection initiated
554
            // by MAVSDK. As such, it should not be advertised as a newly discovered system.
555
            if (static_cast<int>(get_system_id()) != 0) {
18✔
556
                _mavsdk_impl.notify_on_discover();
18✔
557
            }
558

559
            // We call this later to avoid deadlocks on creating the server components.
560
            _mavsdk_impl.call_user_callback([this]() {
36✔
561
                // Send a heartbeat back immediately.
562
                _mavsdk_impl.start_sending_heartbeats();
563
            });
564

565
            register_timeout_handler(
18✔
566
                [this] { heartbeats_timed_out(); },
×
567
                HEARTBEAT_TIMEOUT_S,
568
                &_heartbeat_timeout_cookie);
569

570
            enable_needed = true;
18✔
571

572
            _is_connected_callbacks.queue(
18✔
573
                true, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
574

575
        } else if (_connected) {
2✔
576
            refresh_timeout_handler(_heartbeat_timeout_cookie);
2✔
577
        }
578
        // If not yet connected there is nothing to do/
579
    }
580
    if (enable_needed) {
20✔
581
        if (has_autopilot()) {
18✔
582
            send_autopilot_version_request_async(nullptr);
9✔
583
        }
584

585
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
36✔
586
        for (auto plugin_impl : _plugin_impls) {
18✔
587
            plugin_impl->enable();
×
588
        }
589
    }
590
}
20✔
591

592
void SystemImpl::set_disconnected()
×
593
{
594
    {
595
        std::lock_guard<std::mutex> lock(_connection_mutex);
×
596

597
        // This might not be needed because this is probably called from the triggered
598
        // timeout anyway, but it should also do no harm.
599
        // unregister_timeout_handler(_heartbeat_timeout_cookie);
600
        //_heartbeat_timeout_cookie = nullptr;
601

602
        _connected = false;
×
603
        _mavsdk_impl.notify_on_timeout();
×
604
        _is_connected_callbacks.queue(
×
605
            false, [this](const auto& func) { _mavsdk_impl.call_user_callback(func); });
×
606
    }
607

608
    _mavsdk_impl.stop_sending_heartbeats();
×
609

610
    {
611
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
×
612
        for (auto plugin_impl : _plugin_impls) {
×
613
            plugin_impl->disable();
×
614
        }
615
    }
616
}
×
617

618
uint8_t SystemImpl::get_system_id() const
84✔
619
{
620
    return _target_address.system_id;
84✔
621
}
622

623
std::vector<uint8_t> SystemImpl::component_ids() const
×
624
{
625
    return std::vector<uint8_t>{_components.begin(), _components.end()};
×
626
}
627

628
void SystemImpl::set_system_id(uint8_t system_id)
10✔
629
{
630
    _target_address.system_id = system_id;
10✔
631
}
10✔
632

633
uint8_t SystemImpl::get_own_system_id() const
80✔
634
{
635
    return _mavsdk_impl.get_own_system_id();
80✔
636
}
637

638
uint8_t SystemImpl::get_own_component_id() const
80✔
639
{
640
    return _mavsdk_impl.get_own_component_id();
80✔
641
}
642

643
MAV_TYPE SystemImpl::get_vehicle_type() const
×
644
{
645
    return _vehicle_type;
×
646
}
647

648
uint8_t SystemImpl::get_own_mav_type() const
×
649
{
650
    return _mavsdk_impl.get_mav_type();
×
651
}
652

653
MavlinkParameterClient::Result SystemImpl::set_param(
×
654
    const std::string& name,
655
    ParamValue value,
656
    std::optional<uint8_t> maybe_component_id,
657
    bool extended)
658
{
659
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
660
        ->set_param(name, value);
×
661
}
662

663
MavlinkParameterClient::Result SystemImpl::set_param_float(
2✔
664
    const std::string& name, float value, std::optional<uint8_t> maybe_component_id, bool extended)
665
{
666
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
667
        ->set_param_float(name, value);
4✔
668
}
669

670
MavlinkParameterClient::Result SystemImpl::set_param_int(
2✔
671
    const std::string& name,
672
    int32_t value,
673
    std::optional<uint8_t> maybe_component_id,
674
    bool extended)
675
{
676
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
2✔
677
        ->set_param_int(name, value);
4✔
678
}
679

680
MavlinkParameterClient::Result SystemImpl::set_param_custom(
2✔
681
    const std::string& name, const std::string& value, std::optional<uint8_t> maybe_component_id)
682
{
683
    return param_sender(maybe_component_id.has_value() ? maybe_component_id.value() : 1, true)
4✔
684
        ->set_param_custom(name, value);
4✔
685
}
686

687
std::pair<MavlinkParameterClient::Result, std::map<std::string, ParamValue>>
688
SystemImpl::get_all_params(std::optional<uint8_t> maybe_component_id, bool extended)
4✔
689
{
690
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
4✔
691
        ->get_all_params();
8✔
692
}
693

694
void SystemImpl::set_param_async(
×
695
    const std::string& name,
696
    ParamValue value,
697
    const SetParamCallback& callback,
698
    const void* cookie,
699
    std::optional<uint8_t> maybe_component_id,
700
    bool extended)
701
{
702
    param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
×
703
        ->set_param_async(name, value, callback, cookie);
×
704
}
×
705

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

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

730
std::pair<MavlinkParameterClient::Result, float> SystemImpl::get_param_float(
5✔
731
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
732
{
733
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
734
        ->get_param_float(name);
10✔
735
}
736

737
std::pair<MavlinkParameterClient::Result, int> SystemImpl::get_param_int(
5✔
738
    const std::string& name, std::optional<uint8_t> maybe_component_id, bool extended)
739
{
740
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, extended)
5✔
741
        ->get_param_int(name);
10✔
742
}
743

744
std::pair<MavlinkParameterClient::Result, std::string>
745
SystemImpl::get_param_custom(const std::string& name, std::optional<uint8_t> maybe_component_id)
4✔
746
{
747
    return param_sender(maybe_component_id ? maybe_component_id.value() : 1, true)
8✔
748
        ->get_param_custom(name);
8✔
749
}
750

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

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

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

785
void SystemImpl::get_param_custom_async(
×
786
    const std::string& name, const GetParamCustomCallback& callback, const void* cookie)
787
{
788
    param_sender(1, false)->get_param_custom_async(name, callback, cookie);
×
789
}
×
790

791
void SystemImpl::cancel_all_param(const void* cookie)
2✔
792
{
793
    UNUSED(cookie);
2✔
794
    // FIXME: this currently crashes on destruction
795
    // param_sender(1, false)->cancel_all_param(cookie);
796
}
2✔
797

798
MavlinkCommandSender::Result
799
SystemImpl::set_flight_mode(FlightMode system_mode, uint8_t component_id)
×
800
{
801
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
802
        make_command_flight_mode(system_mode, component_id);
×
803

804
    if (result.first != MavlinkCommandSender::Result::Success) {
×
805
        return result.first;
×
806
    }
807

808
    return send_command(result.second);
×
809
}
810

811
void SystemImpl::set_flight_mode_async(
×
812
    FlightMode system_mode, const CommandResultCallback& callback, uint8_t component_id)
813
{
814
    std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong> result =
×
815
        make_command_flight_mode(system_mode, component_id);
×
816

817
    if (result.first != MavlinkCommandSender::Result::Success) {
×
818
        if (callback) {
×
819
            callback(result.first, NAN);
×
820
        }
821
        return;
×
822
    }
823

824
    send_command_async(result.second, callback);
×
825
}
826

827
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
828
SystemImpl::make_command_flight_mode(FlightMode flight_mode, uint8_t component_id)
×
829
{
830
    if (_autopilot == Autopilot::ArduPilot) {
×
831
        return make_command_ardupilot_mode(flight_mode, component_id);
×
832
    } else {
833
        return make_command_px4_mode(flight_mode, component_id);
×
834
    }
835
}
836

837
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
838
SystemImpl::make_command_ardupilot_mode(FlightMode flight_mode, uint8_t component_id)
×
839
{
840
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
841
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
842
    const uint8_t mode_type =
×
843
        MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
844

845
    MavlinkCommandSender::CommandLong command{};
×
846

847
    command.command = MAV_CMD_DO_SET_MODE;
×
848
    command.params.maybe_param1 = static_cast<float>(mode_type);
×
849

850
    switch (_vehicle_type) {
×
851
        case MAV_TYPE::MAV_TYPE_SURFACE_BOAT:
×
852
        case MAV_TYPE::MAV_TYPE_GROUND_ROVER: {
853
            const auto new_mode = flight_mode_to_ardupilot_rover_mode(flight_mode);
×
854
            if (new_mode == ardupilot::RoverMode::Unknown) {
×
855
                LogErr() << "Cannot translate flight mode to ArduPilot Rover mode.";
×
856
                MavlinkCommandSender::CommandLong empty_command{};
×
857
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
858
            } else {
859
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
860
            }
861
            break;
×
862
        }
863
        case MAV_TYPE::MAV_TYPE_FIXED_WING:
×
864
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
865
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
866
        case MAV_TYPE::MAV_TYPE_VTOL_TILTROTOR:
867
        case MAV_TYPE::MAV_TYPE_VTOL_FIXEDROTOR:
868
        case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER:
869
        case MAV_TYPE::MAV_TYPE_VTOL_TILTWING: {
870
            const auto new_mode = flight_mode_to_ardupilot_plane_mode(flight_mode);
×
871
            if (new_mode == ardupilot::PlaneMode::Unknown) {
×
872
                LogErr() << "Cannot translate flight mode to ArduPilot Plane mode.";
×
873
                MavlinkCommandSender::CommandLong empty_command{};
×
874
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
875
            } else {
876
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
877
            }
878
            break;
×
879
        }
880

881
        case MAV_TYPE::MAV_TYPE_QUADROTOR:
×
882
        case MAV_TYPE::MAV_TYPE_COAXIAL:
883
        case MAV_TYPE::MAV_TYPE_HELICOPTER:
884
        case MAV_TYPE::MAV_TYPE_HEXAROTOR:
885
        case MAV_TYPE::MAV_TYPE_OCTOROTOR:
886
        case MAV_TYPE::MAV_TYPE_TRICOPTER:
887
        case MAV_TYPE::MAV_TYPE_DODECAROTOR:
888
        case MAV_TYPE::MAV_TYPE_DECAROTOR: {
889
            const auto new_mode = flight_mode_to_ardupilot_copter_mode(flight_mode);
×
890
            if (new_mode == ardupilot::CopterMode::Unknown) {
×
891
                LogErr() << "Cannot translate flight mode to ArduPilot Copter mode.";
×
892
                MavlinkCommandSender::CommandLong empty_command{};
×
893
                return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
894
            } else {
895
                command.params.maybe_param2 = static_cast<float>(new_mode);
×
896
            }
897
            break;
×
898
        }
899

900
        default:
×
901
            LogErr() << "Cannot translate flight mode to ArduPilot mode, for MAV_TYPE: "
×
902
                     << _vehicle_type;
×
903
            MavlinkCommandSender::CommandLong empty_command{};
×
904
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
905
    }
906
    command.target_component_id = component_id;
×
907

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

996
std::pair<MavlinkCommandSender::Result, MavlinkCommandSender::CommandLong>
997
SystemImpl::make_command_px4_mode(FlightMode flight_mode, uint8_t component_id)
×
998
{
999
    const uint8_t flag_safety_armed = is_armed() ? MAV_MODE_FLAG_SAFETY_ARMED : 0;
×
1000
    const uint8_t flag_hitl_enabled = _hitl_enabled ? MAV_MODE_FLAG_HIL_ENABLED : 0;
×
1001

1002
    const uint8_t mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | flag_safety_armed | flag_hitl_enabled;
×
1003

1004
    // Note: the safety flag is not needed in future versions of the PX4 Firmware
1005
    //       but want to be rather safe than sorry.
1006
    uint8_t custom_mode = px4::PX4_CUSTOM_MAIN_MODE_AUTO;
×
1007
    uint8_t custom_sub_mode = 0;
×
1008

1009
    switch (flight_mode) {
×
1010
        case FlightMode::Hold:
×
1011
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
×
1012
            break;
×
1013
        case FlightMode::ReturnToLaunch:
×
1014
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_RTL;
×
1015
            break;
×
1016
        case FlightMode::Takeoff:
×
1017
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF;
×
1018
            break;
×
1019
        case FlightMode::Land:
×
1020
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_LAND;
×
1021
            break;
×
1022
        case FlightMode::Mission:
×
1023
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
×
1024
            break;
×
1025
        case FlightMode::FollowMe:
×
1026
            custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET;
×
1027
            break;
×
1028
        case FlightMode::Offboard:
×
1029
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_OFFBOARD;
×
1030
            break;
×
1031
        case FlightMode::Manual:
×
1032
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_MANUAL;
×
1033
            break;
×
1034
        case FlightMode::Posctl:
×
1035
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_POSCTL;
×
1036
            break;
×
1037
        case FlightMode::Altctl:
×
1038
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ALTCTL;
×
1039
            break;
×
1040
        case FlightMode::Rattitude:
×
1041
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_RATTITUDE;
×
1042
            break;
×
1043
        case FlightMode::Acro:
×
1044
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_ACRO;
×
1045
            break;
×
1046
        case FlightMode::Stabilized:
×
1047
            custom_mode = px4::PX4_CUSTOM_MAIN_MODE_STABILIZED;
×
1048
            break;
×
1049
        default:
×
1050
            LogErr() << "Unknown Flight mode.";
×
1051
            MavlinkCommandSender::CommandLong empty_command{};
×
1052
            return std::make_pair<>(MavlinkCommandSender::Result::UnknownError, empty_command);
×
1053
    }
1054

1055
    MavlinkCommandSender::CommandLong command{};
×
1056

1057
    command.command = MAV_CMD_DO_SET_MODE;
×
1058
    command.params.maybe_param1 = static_cast<float>(mode);
×
1059
    command.params.maybe_param2 = static_cast<float>(custom_mode);
×
1060
    command.params.maybe_param3 = static_cast<float>(custom_sub_mode);
×
1061
    command.target_component_id = component_id;
×
1062

1063
    return std::make_pair<>(MavlinkCommandSender::Result::Success, command);
×
1064
}
1065

1066
FlightMode SystemImpl::get_flight_mode() const
6✔
1067
{
1068
    return _flight_mode;
6✔
1069
}
1070

1071
void SystemImpl::receive_float_param(
×
1072
    MavlinkParameterClient::Result result, ParamValue value, const GetParamFloatCallback& callback)
1073
{
1074
    if (callback) {
×
1075
        if (result == MavlinkParameterClient::Result::Success) {
×
1076
            callback(result, value.get<float>());
×
1077
        } else {
1078
            callback(result, NAN);
×
1079
        }
1080
    }
1081
}
×
1082

1083
void SystemImpl::receive_int_param(
×
1084
    MavlinkParameterClient::Result result, ParamValue value, const GetParamIntCallback& callback)
1085
{
1086
    if (callback) {
×
1087
        if (result == MavlinkParameterClient::Result::Success) {
×
1088
            callback(result, value.get<int32_t>());
×
1089
        } else {
1090
            callback(result, 0);
×
1091
        }
1092
    }
1093
}
×
1094

1095
uint8_t SystemImpl::get_autopilot_id() const
50✔
1096
{
1097
    for (auto compid : _components)
60✔
1098
        if (compid == MavlinkCommandSender::DEFAULT_COMPONENT_ID_AUTOPILOT) {
50✔
1099
            return compid;
40✔
1100
        }
1101
    // FIXME: Not sure what should be returned if autopilot is not found
1102
    return uint8_t(0);
10✔
1103
}
1104

1105
std::vector<uint8_t> SystemImpl::get_camera_ids() const
×
1106
{
1107
    std::vector<uint8_t> camera_ids{};
×
1108

1109
    for (auto compid : _components)
×
1110
        if (compid >= MAV_COMP_ID_CAMERA && compid <= MAV_COMP_ID_CAMERA6) {
×
1111
            camera_ids.push_back(compid);
×
1112
        }
1113
    return camera_ids;
×
1114
}
1115

1116
uint8_t SystemImpl::get_gimbal_id() const
×
1117
{
1118
    for (auto compid : _components)
×
1119
        if (compid == MAV_COMP_ID_GIMBAL) {
×
1120
            return compid;
×
1121
        }
1122
    return uint8_t(0);
×
1123
}
1124

1125
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandLong& command)
×
1126
{
1127
    if (_target_address.system_id == 0 && _components.empty()) {
×
1128
        return MavlinkCommandSender::Result::NoSystem;
×
1129
    }
1130
    command.target_system_id = get_system_id();
×
1131
    return _command_sender.send_command(command);
×
1132
}
1133

1134
MavlinkCommandSender::Result SystemImpl::send_command(MavlinkCommandSender::CommandInt& command)
×
1135
{
1136
    if (_target_address.system_id == 0 && _components.empty()) {
×
1137
        return MavlinkCommandSender::Result::NoSystem;
×
1138
    }
1139
    command.target_system_id = get_system_id();
×
1140
    return _command_sender.send_command(command);
×
1141
}
1142

1143
void SystemImpl::send_command_async(
14✔
1144
    MavlinkCommandSender::CommandLong command, const CommandResultCallback& callback)
1145
{
1146
    if (_target_address.system_id == 0 && _components.empty()) {
14✔
1147
        if (callback) {
×
1148
            callback(MavlinkCommandSender::Result::NoSystem, NAN);
×
1149
        }
1150
        return;
×
1151
    }
1152
    command.target_system_id = get_system_id();
14✔
1153

1154
    _command_sender.queue_command_async(command, callback);
14✔
1155
}
1156

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

1168
    _command_sender.queue_command_async(command, callback);
×
1169
}
1170

1171
MavlinkCommandSender::Result
1172
SystemImpl::set_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
×
1173
{
1174
    MavlinkCommandSender::CommandLong command =
×
1175
        make_command_msg_rate(message_id, rate_hz, component_id);
×
1176
    return send_command(command);
×
1177
}
1178

1179
void SystemImpl::set_msg_rate_async(
1✔
1180
    uint16_t message_id,
1181
    double rate_hz,
1182
    const CommandResultCallback& callback,
1183
    uint8_t component_id)
1184
{
1185
    MavlinkCommandSender::CommandLong command =
1✔
1186
        make_command_msg_rate(message_id, rate_hz, component_id);
1✔
1187
    send_command_async(command, callback);
1✔
1188
}
1✔
1189

1190
MavlinkCommandSender::CommandLong
1191
SystemImpl::make_command_msg_rate(uint16_t message_id, double rate_hz, uint8_t component_id)
1✔
1192
{
1193
    MavlinkCommandSender::CommandLong command{};
1✔
1194

1195
    // 0 to request default rate, -1 to stop stream
1196

1197
    float interval_us = 0.0f;
1✔
1198

1199
    if (rate_hz > 0) {
1✔
1200
        interval_us = 1e6f / static_cast<float>(rate_hz);
1✔
1201
    } else if (rate_hz < 0) {
×
1202
        interval_us = -1.0f;
×
1203
    }
1204

1205
    command.command = MAV_CMD_SET_MESSAGE_INTERVAL;
1✔
1206
    command.params.maybe_param1 = static_cast<float>(message_id);
1✔
1207
    command.params.maybe_param2 = interval_us;
1✔
1208
    command.target_component_id = component_id;
1✔
1209

1210
    return command;
1✔
1211
}
1212

1213
void SystemImpl::register_plugin(PluginImplBase* plugin_impl)
12✔
1214
{
1215
    assert(plugin_impl);
12✔
1216

1217
    plugin_impl->init();
12✔
1218

1219
    {
1220
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
24✔
1221
        _plugin_impls.push_back(plugin_impl);
12✔
1222
    }
1223

1224
    // If we're connected already, let's enable it straightaway.
1225
    if (_connected) {
12✔
1226
        plugin_impl->enable();
12✔
1227
    }
1228
}
12✔
1229

1230
void SystemImpl::unregister_plugin(PluginImplBase* plugin_impl)
12✔
1231
{
1232
    assert(plugin_impl);
12✔
1233

1234
    plugin_impl->disable();
12✔
1235
    plugin_impl->deinit();
12✔
1236

1237
    // Remove first, so it won't get enabled/disabled anymore.
1238
    {
1239
        std::lock_guard<std::mutex> lock(_plugin_impls_mutex);
24✔
1240
        auto found = std::find(_plugin_impls.begin(), _plugin_impls.end(), plugin_impl);
12✔
1241
        if (found != _plugin_impls.end()) {
12✔
1242
            _plugin_impls.erase(found);
12✔
1243
        }
1244
    }
1245
}
12✔
1246

1247
void SystemImpl::call_user_callback_located(
14✔
1248
    const std::string& filename, const int linenumber, const std::function<void()>& func)
1249
{
1250
    _mavsdk_impl.call_user_callback_located(filename, linenumber, func);
14✔
1251
}
14✔
1252

1253
void SystemImpl::param_changed(const std::string& name)
×
1254
{
1255
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
×
1256

1257
    for (auto& callback : _param_changed_callbacks) {
×
1258
        callback.second(name);
×
1259
    }
1260
}
×
1261

1262
void SystemImpl::register_param_changed_handler(
1✔
1263
    const ParamChangedCallback& callback, const void* cookie)
1264
{
1265
    if (!callback) {
1✔
1266
        LogErr() << "No callback for param_changed_handler supplied.";
×
1267
        return;
×
1268
    }
1269

1270
    if (!cookie) {
1✔
1271
        LogErr() << "No callback for param_changed_handler supplied.";
×
1272
        return;
×
1273
    }
1274

1275
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
2✔
1276

1277
    _param_changed_callbacks[cookie] = callback;
1✔
1278
}
1279

1280
void SystemImpl::unregister_param_changed_handler(const void* cookie)
1✔
1281
{
1282
    std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);
1✔
1283

1284
    auto it = _param_changed_callbacks.find(cookie);
1✔
1285
    if (it == _param_changed_callbacks.end()) {
1✔
1286
        LogWarn() << "param_changed_handler for cookie not found";
×
1287
        return;
×
1288
    }
1289
    _param_changed_callbacks.erase(it);
1✔
1290
}
1291

1292
Time& SystemImpl::get_time()
28✔
1293
{
1294
    return _mavsdk_impl.time;
28✔
1295
}
1296

1297
void SystemImpl::subscribe_param_float(
×
1298
    const std::string& name,
1299
    const MavlinkParameterClient::ParamFloatChangedCallback& callback,
1300
    const void* cookie)
1301
{
1302
    param_sender(1, false)->subscribe_param_float_changed(name, callback, cookie);
×
1303
}
×
1304

1305
void SystemImpl::subscribe_param_int(
×
1306
    const std::string& name,
1307
    const MavlinkParameterClient::ParamIntChangedCallback& callback,
1308
    const void* cookie)
1309
{
1310
    param_sender(1, false)->subscribe_param_int_changed(name, callback, cookie);
×
1311
}
×
1312
void SystemImpl::subscribe_param_custom(
×
1313
    const std::string& name,
1314
    const MavlinkParameterClient::ParamCustomChangedCallback& callback,
1315
    const void* cookie)
1316
{
1317
    param_sender(1, false)->subscribe_param_custom_changed(name, callback, cookie);
×
1318
}
×
1319

1320
MavlinkParameterClient* SystemImpl::param_sender(uint8_t component_id, bool extended)
24✔
1321
{
1322
    std::lock_guard<std::mutex> lock(_mavlink_parameter_clients_mutex);
48✔
1323

1324
    for (auto& entry : _mavlink_parameter_clients) {
26✔
1325
        if (entry.component_id == component_id && entry.extended == extended) {
18✔
1326
            return entry.parameter_client.get();
16✔
1327
        }
1328
    }
1329

1330
    _mavlink_parameter_clients.push_back(
16✔
1331
        {std::make_unique<MavlinkParameterClient>(
1332
             *this,
1333
             _mavsdk_impl.mavlink_message_handler,
8✔
1334
             _mavsdk_impl.timeout_handler,
8✔
1335
             [this]() { return timeout_s(); },
45✔
1336
             component_id,
1337
             extended),
1338
         component_id,
1339
         extended});
1340

1341
    return _mavlink_parameter_clients.back().parameter_client.get();
8✔
1342
}
1343

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