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

mavlink / MAVSDK / 15060565035

16 May 2025 04:20AM UTC coverage: 44.332% (+0.06%) from 44.27%
15060565035

push

github

web-flow
Merge pull request #2573 from mavlink/pr-threading

Add incoming and outgoing message queue, fixing threading/locking issues

159 of 185 new or added lines in 7 files covered. (85.95%)

60 existing lines in 8 files now uncovered.

14901 of 33612 relevant lines covered (44.33%)

285.36 hits per line

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

5.05
/src/mavsdk/plugins/telemetry/telemetry_impl.cpp
1
#include "telemetry_impl.h"
2
#include "system.h"
3
#include "math_utils.h"
4
#include "callback_list.tpp"
5

6
#include <cmath>
7
#include <functional>
8
#include <string>
9
#include <array>
10
#include <cassert>
11
#include <unused.h>
12

13
namespace mavsdk {
14

15
template class CallbackList<Telemetry::PositionVelocityNed>;
16
template class CallbackList<Telemetry::Position>;
17
template class CallbackList<bool>;
18
template class CallbackList<Telemetry::StatusText>;
19
template class CallbackList<Telemetry::Quaternion>;
20
template class CallbackList<Telemetry::AngularVelocityBody>;
21
template class CallbackList<Telemetry::GroundTruth>;
22
template class CallbackList<Telemetry::FixedwingMetrics>;
23
template class CallbackList<Telemetry::EulerAngle>;
24
template class CallbackList<Telemetry::VelocityNed>;
25
template class CallbackList<Telemetry::Imu>;
26
template class CallbackList<Telemetry::GpsInfo>;
27
template class CallbackList<Telemetry::RawGps>;
28
template class CallbackList<Telemetry::Battery>;
29
template class CallbackList<Telemetry::FlightMode>;
30
template class CallbackList<Telemetry::Health>;
31
template class CallbackList<Telemetry::VtolState>;
32
template class CallbackList<Telemetry::LandedState>;
33
template class CallbackList<Telemetry::RcStatus>;
34
template class CallbackList<uint64_t>;
35
template class CallbackList<Telemetry::ActuatorControlTarget>;
36
template class CallbackList<Telemetry::ActuatorOutputStatus>;
37
template class CallbackList<Telemetry::Odometry>;
38
template class CallbackList<Telemetry::DistanceSensor>;
39
template class CallbackList<Telemetry::ScaledPressure>;
40
template class CallbackList<Telemetry::Heading>;
41
template class CallbackList<Telemetry::Altitude>;
42
template class CallbackList<Telemetry::Wind>;
43

44
TelemetryImpl::TelemetryImpl(System& system) : PluginImplBase(system)
×
45
{
46
    _system_impl->register_plugin(this);
×
47
}
×
48

49
TelemetryImpl::TelemetryImpl(std::shared_ptr<System> system) : PluginImplBase(std::move(system))
1✔
50
{
51
    _system_impl->register_plugin(this);
1✔
52
}
1✔
53

54
TelemetryImpl::~TelemetryImpl()
2✔
55
{
56
    _system_impl->unregister_plugin(this);
1✔
57
}
2✔
58

59
void TelemetryImpl::init()
1✔
60
{
61
    _system_impl->register_mavlink_message_handler(
1✔
62
        MAVLINK_MSG_ID_LOCAL_POSITION_NED,
63
        [this](const mavlink_message_t& message) { process_position_velocity_ned(message); },
×
64
        this);
65

66
    _system_impl->register_mavlink_message_handler(
1✔
67
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
68
        [this](const mavlink_message_t& message) { process_global_position_int(message); },
×
69
        this);
70

71
    _system_impl->register_mavlink_message_handler(
1✔
72
        MAVLINK_MSG_ID_HOME_POSITION,
73
        [this](const mavlink_message_t& message) { process_home_position(message); },
×
74
        this);
75

76
    _system_impl->register_mavlink_message_handler(
1✔
77
        MAVLINK_MSG_ID_ATTITUDE,
78
        [this](const mavlink_message_t& message) { process_attitude(message); },
×
79
        this);
80

81
    _system_impl->register_mavlink_message_handler(
1✔
82
        MAVLINK_MSG_ID_ATTITUDE_QUATERNION,
83
        [this](const mavlink_message_t& message) { process_attitude_quaternion(message); },
×
84
        this);
85

86
    _system_impl->register_mavlink_message_handler(
1✔
87
        MAVLINK_MSG_ID_GPS_RAW_INT,
88
        [this](const mavlink_message_t& message) { process_gps_raw_int(message); },
×
89
        this);
90

91
    _system_impl->register_mavlink_message_handler(
1✔
92
        MAVLINK_MSG_ID_EXTENDED_SYS_STATE,
93
        [this](const mavlink_message_t& message) { process_extended_sys_state(message); },
×
94
        this);
95

96
    _system_impl->register_mavlink_message_handler(
1✔
97
        MAVLINK_MSG_ID_SYS_STATUS,
98
        [this](const mavlink_message_t& message) { process_sys_status(message); },
×
99
        this);
100

101
    _system_impl->register_mavlink_message_handler(
1✔
102
        MAVLINK_MSG_ID_BATTERY_STATUS,
103
        [this](const mavlink_message_t& message) { process_battery_status(message); },
×
104
        this);
105

106
    _system_impl->register_mavlink_message_handler(
1✔
107
        MAVLINK_MSG_ID_HEARTBEAT,
UNCOV
108
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
×
109
        this);
110

111
    _system_impl->register_mavlink_message_handler(
1✔
112
        MAVLINK_MSG_ID_RC_CHANNELS,
113
        [this](const mavlink_message_t& message) { process_rc_channels(message); },
×
114
        this);
115

116
    _system_impl->register_mavlink_message_handler(
1✔
117
        MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET,
118
        [this](const mavlink_message_t& message) { process_actuator_control_target(message); },
×
119
        this);
120

121
    _system_impl->register_mavlink_message_handler(
1✔
122
        MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS,
123
        [this](const mavlink_message_t& message) { process_actuator_output_status(message); },
×
124
        this);
125

126
    _system_impl->register_mavlink_message_handler(
1✔
127
        MAVLINK_MSG_ID_ODOMETRY,
128
        [this](const mavlink_message_t& message) { process_odometry(message); },
×
129
        this);
130

131
    _system_impl->register_mavlink_message_handler(
1✔
132
        MAVLINK_MSG_ID_DISTANCE_SENSOR,
133
        [this](const mavlink_message_t& message) { process_distance_sensor(message); },
×
134
        this);
135

136
    _system_impl->register_mavlink_message_handler(
1✔
137
        MAVLINK_MSG_ID_SCALED_PRESSURE,
138
        [this](const mavlink_message_t& message) { process_scaled_pressure(message); },
×
139
        this);
140

141
    _system_impl->register_mavlink_message_handler(
1✔
142
        MAVLINK_MSG_ID_SYSTEM_TIME,
143
        [this](const mavlink_message_t& message) { process_unix_epoch_time(message); },
×
144
        this);
145

146
    _system_impl->register_mavlink_message_handler(
1✔
147
        MAVLINK_MSG_ID_HIGHRES_IMU,
148
        [this](const mavlink_message_t& message) { process_imu_reading_ned(message); },
×
149
        this);
150

151
    _system_impl->register_mavlink_message_handler(
1✔
152
        MAVLINK_MSG_ID_SCALED_IMU,
153
        [this](const mavlink_message_t& message) { process_scaled_imu(message); },
×
154
        this);
155

156
    _system_impl->register_mavlink_message_handler(
1✔
157
        MAVLINK_MSG_ID_RAW_IMU,
158
        [this](const mavlink_message_t& message) { process_raw_imu(message); },
×
159
        this);
160

161
    _system_impl->register_mavlink_message_handler(
1✔
162
        MAVLINK_MSG_ID_VFR_HUD,
163
        [this](const mavlink_message_t& message) { process_fixedwing_metrics(message); },
×
164
        this);
165

166
    _system_impl->register_mavlink_message_handler(
1✔
167
        MAVLINK_MSG_ID_HIL_STATE_QUATERNION,
168
        [this](const mavlink_message_t& message) { process_ground_truth(message); },
×
169
        this);
170

171
    _system_impl->register_mavlink_message_handler(
1✔
172
        MAVLINK_MSG_ID_ALTITUDE,
173
        [this](const mavlink_message_t& message) { process_altitude(message); },
×
174
        this);
175

176
    _system_impl->register_mavlink_message_handler(
1✔
177
        MAVLINK_MSG_ID_WIND_COV,
178
        [this](const mavlink_message_t& message) { process_wind(message); },
×
179
        this);
180

181
    _system_impl->register_statustext_handler(
1✔
182
        [this](const MavlinkStatustextHandler::Statustext& statustext) {
3✔
183
            receive_statustext(statustext);
3✔
184
        },
3✔
185
        this);
186
}
1✔
187

188
void TelemetryImpl::deinit()
1✔
189
{
190
    _system_impl->unregister_statustext_handler(this);
1✔
191
    _system_impl->unregister_all_mavlink_message_handlers(this);
1✔
192
}
1✔
193

194
void TelemetryImpl::enable()
1✔
195
{
196
    // We're going to retry until we have the Home Position.
197
    _homepos_cookie =
1✔
198
        _system_impl->add_call_every([this]() { request_home_position_again(); }, 2.0f);
3✔
199
}
1✔
200

201
void TelemetryImpl::disable()
1✔
202
{
203
    _system_impl->remove_call_every(_homepos_cookie);
1✔
204
    {
205
        std::lock_guard<std::mutex> lock(_health_mutex);
1✔
206
        _health.is_home_position_ok = false;
1✔
207
    }
1✔
208

209
    // FIXME: this is a race condition where request_home_position_again
210
    //        could still be executing after we have removed it.
211
    std::this_thread::sleep_for(std::chrono::milliseconds(200));
1✔
212
}
1✔
213

214
void TelemetryImpl::request_home_position_again()
1✔
215
{
216
    {
217
        std::lock_guard<std::mutex> lock(_health_mutex);
1✔
218
        if (_health.is_home_position_ok) {
1✔
219
            _system_impl->remove_call_every(_homepos_cookie);
×
220
            return;
×
221
        }
222

223
        _system_impl->mavlink_request_message().request(
1✔
224
            MAVLINK_MSG_ID_HOME_POSITION, MAV_COMP_ID_AUTOPILOT1, nullptr);
225
    }
1✔
226
}
227

228
Telemetry::Result TelemetryImpl::set_rate_position_velocity_ned(double rate_hz)
×
229
{
230
    return telemetry_result_from_command_result(
×
231
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_LOCAL_POSITION_NED, rate_hz));
×
232
}
233

234
Telemetry::Result TelemetryImpl::set_rate_position(double rate_hz)
×
235
{
236
    _position_rate_hz = rate_hz;
×
237
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
238

239
    return telemetry_result_from_command_result(
×
240
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, max_rate_hz));
×
241
}
242

243
Telemetry::Result TelemetryImpl::set_rate_home(double rate_hz)
×
244
{
245
    return telemetry_result_from_command_result(
×
246
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_HOME_POSITION, rate_hz));
×
247
}
248

249
Telemetry::Result TelemetryImpl::set_rate_in_air(double rate_hz)
×
250
{
251
    return set_rate_landed_state(rate_hz);
×
252
}
253

254
Telemetry::Result TelemetryImpl::set_rate_vtol_state(double rate_hz)
×
255
{
256
    return set_rate_landed_state(rate_hz);
×
257
}
258

259
Telemetry::Result TelemetryImpl::set_rate_landed_state(double rate_hz)
×
260
{
261
    return telemetry_result_from_command_result(
×
262
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_EXTENDED_SYS_STATE, rate_hz));
×
263
}
264

265
Telemetry::Result TelemetryImpl::set_rate_attitude_quaternion(double rate_hz)
×
266
{
267
    return telemetry_result_from_command_result(
×
268
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ATTITUDE_QUATERNION, rate_hz));
×
269
}
270

271
Telemetry::Result TelemetryImpl::set_rate_attitude_euler(double rate_hz)
×
272
{
273
    return telemetry_result_from_command_result(
×
274
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ATTITUDE, rate_hz));
×
275
}
276

277
Telemetry::Result TelemetryImpl::set_rate_velocity_ned(double rate_hz)
×
278
{
279
    _velocity_ned_rate_hz = rate_hz;
×
280
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
281

282
    return telemetry_result_from_command_result(
×
283
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, max_rate_hz));
×
284
}
285

286
Telemetry::Result TelemetryImpl::set_rate_imu(double rate_hz)
×
287
{
288
    return telemetry_result_from_command_result(
×
289
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_HIGHRES_IMU, rate_hz));
×
290
}
291

292
Telemetry::Result TelemetryImpl::set_rate_scaled_imu(double rate_hz)
×
293
{
294
    return telemetry_result_from_command_result(
×
295
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_SCALED_IMU, rate_hz));
×
296
}
297

298
Telemetry::Result TelemetryImpl::set_rate_raw_imu(double rate_hz)
×
299
{
300
    return telemetry_result_from_command_result(
×
301
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_RAW_IMU, rate_hz));
×
302
}
303

304
Telemetry::Result TelemetryImpl::set_rate_fixedwing_metrics(double rate_hz)
×
305
{
306
    return telemetry_result_from_command_result(
×
307
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_VFR_HUD, rate_hz));
×
308
}
309

310
Telemetry::Result TelemetryImpl::set_rate_ground_truth(double rate_hz)
×
311
{
312
    return telemetry_result_from_command_result(
×
313
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_HIL_STATE_QUATERNION, rate_hz));
×
314
}
315

316
Telemetry::Result TelemetryImpl::set_rate_gps_info(double rate_hz)
×
317
{
318
    return telemetry_result_from_command_result(
×
319
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_GPS_RAW_INT, rate_hz));
×
320
}
321

322
Telemetry::Result TelemetryImpl::set_rate_battery(double rate_hz)
×
323
{
324
    return telemetry_result_from_command_result(
×
325
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_BATTERY_STATUS, rate_hz));
×
326
}
327

328
Telemetry::Result TelemetryImpl::set_rate_rc_status(double rate_hz)
×
329
{
330
    UNUSED(rate_hz);
×
331
    LogWarn() << "System status is usually fixed at 1 Hz";
×
332
    return Telemetry::Result::Unsupported;
×
333
}
334

335
Telemetry::Result TelemetryImpl::set_rate_actuator_control_target(double rate_hz)
×
336
{
337
    return telemetry_result_from_command_result(
×
338
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, rate_hz));
×
339
}
340

341
Telemetry::Result TelemetryImpl::set_rate_actuator_output_status(double rate_hz)
×
342
{
343
    return telemetry_result_from_command_result(
×
344
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS, rate_hz));
×
345
}
346

347
Telemetry::Result TelemetryImpl::set_rate_odometry(double rate_hz)
×
348
{
349
    return telemetry_result_from_command_result(
×
350
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ODOMETRY, rate_hz));
×
351
}
352

353
Telemetry::Result TelemetryImpl::set_rate_distance_sensor(double rate_hz)
×
354
{
355
    return telemetry_result_from_command_result(
×
356
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_DISTANCE_SENSOR, rate_hz));
×
357
}
358

359
Telemetry::Result TelemetryImpl::set_rate_scaled_pressure(double rate_hz)
×
360
{
361
    return telemetry_result_from_command_result(
×
362
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_SCALED_PRESSURE, rate_hz));
×
363
}
364

365
Telemetry::Result TelemetryImpl::set_rate_unix_epoch_time(double rate_hz)
×
366
{
367
    return telemetry_result_from_command_result(
×
368
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_SYSTEM_TIME, rate_hz));
×
369
}
370

371
Telemetry::Result TelemetryImpl::set_rate_altitude(double rate_hz)
×
372
{
373
    return telemetry_result_from_command_result(
×
374
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ALTITUDE, rate_hz));
×
375
}
376

377
void TelemetryImpl::set_rate_position_velocity_ned_async(
×
378
    double rate_hz, Telemetry::ResultCallback callback)
379
{
380
    _system_impl->set_msg_rate_async(
×
381
        MAVLINK_MSG_ID_LOCAL_POSITION_NED,
382
        rate_hz,
383
        [callback](MavlinkCommandSender::Result command_result, float) {
×
384
            command_result_callback(command_result, callback);
×
385
        });
×
386
}
×
387

388
void TelemetryImpl::set_rate_position_async(double rate_hz, Telemetry::ResultCallback callback)
×
389
{
390
    _position_rate_hz = rate_hz;
×
391
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
392

393
    _system_impl->set_msg_rate_async(
×
394
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
395
        max_rate_hz,
396
        [callback](MavlinkCommandSender::Result command_result, float) {
×
397
            command_result_callback(command_result, callback);
×
398
        });
×
399
}
×
400

401
void TelemetryImpl::set_rate_home_async(double rate_hz, Telemetry::ResultCallback callback)
×
402
{
403
    _system_impl->set_msg_rate_async(
×
404
        MAVLINK_MSG_ID_HOME_POSITION,
405
        rate_hz,
406
        [callback](MavlinkCommandSender::Result command_result, float) {
×
407
            command_result_callback(command_result, callback);
×
408
        });
×
409
}
×
410

411
void TelemetryImpl::set_rate_in_air_async(double rate_hz, Telemetry::ResultCallback callback)
×
412
{
413
    set_rate_landed_state_async(rate_hz, callback);
×
414
}
×
415

416
void TelemetryImpl::set_rate_vtol_state_async(double rate_hz, Telemetry::ResultCallback callback)
×
417
{
418
    set_rate_landed_state_async(rate_hz, callback);
×
419
}
×
420

421
void TelemetryImpl::set_rate_landed_state_async(double rate_hz, Telemetry::ResultCallback callback)
×
422
{
423
    _system_impl->set_msg_rate_async(
×
424
        MAVLINK_MSG_ID_EXTENDED_SYS_STATE,
425
        rate_hz,
426
        [callback](MavlinkCommandSender::Result command_result, float) {
×
427
            command_result_callback(command_result, callback);
×
428
        });
×
429
}
×
430

431
void TelemetryImpl::set_rate_altitude_async(double rate_hz, Telemetry::ResultCallback callback)
×
432
{
433
    _system_impl->set_msg_rate_async(
×
434
        MAVLINK_MSG_ID_ALTITUDE,
435
        rate_hz,
436
        [callback](MavlinkCommandSender::Result command_result, float) {
×
437
            command_result_callback(command_result, callback);
×
438
        });
×
439
}
×
440

441
void TelemetryImpl::set_rate_attitude_quaternion_async(
×
442
    double rate_hz, Telemetry::ResultCallback callback)
443
{
444
    _system_impl->set_msg_rate_async(
×
445
        MAVLINK_MSG_ID_ATTITUDE_QUATERNION,
446
        rate_hz,
447
        [callback](MavlinkCommandSender::Result command_result, float) {
×
448
            command_result_callback(command_result, callback);
×
449
        });
×
450
}
×
451

452
void TelemetryImpl::set_rate_attitude_euler_async(
×
453
    double rate_hz, Telemetry::ResultCallback callback)
454
{
455
    _system_impl->set_msg_rate_async(
×
456
        MAVLINK_MSG_ID_ATTITUDE,
457
        rate_hz,
458
        [callback](MavlinkCommandSender::Result command_result, float) {
×
459
            command_result_callback(command_result, callback);
×
460
        });
×
461
}
×
462

463
void TelemetryImpl::set_rate_velocity_ned_async(double rate_hz, Telemetry::ResultCallback callback)
×
464
{
465
    _velocity_ned_rate_hz = rate_hz;
×
466
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
467

468
    _system_impl->set_msg_rate_async(
×
469
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
470
        max_rate_hz,
471
        [callback](MavlinkCommandSender::Result command_result, float) {
×
472
            command_result_callback(command_result, callback);
×
473
        });
×
474
}
×
475

476
void TelemetryImpl::set_rate_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
477
{
478
    _system_impl->set_msg_rate_async(
×
479
        MAVLINK_MSG_ID_HIGHRES_IMU,
480
        rate_hz,
481
        [callback](MavlinkCommandSender::Result command_result, float) {
×
482
            command_result_callback(command_result, callback);
×
483
        });
×
484
}
×
485

486
void TelemetryImpl::set_rate_scaled_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
487
{
488
    _system_impl->set_msg_rate_async(
×
489
        MAVLINK_MSG_ID_SCALED_IMU,
490
        rate_hz,
491
        [callback](MavlinkCommandSender::Result command_result, float) {
×
492
            command_result_callback(command_result, callback);
×
493
        });
×
494
}
×
495

496
void TelemetryImpl::set_rate_raw_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
497
{
498
    _system_impl->set_msg_rate_async(
×
499
        MAVLINK_MSG_ID_RAW_IMU,
500
        rate_hz,
501
        [callback](MavlinkCommandSender::Result command_result, float) {
×
502
            command_result_callback(command_result, callback);
×
503
        });
×
504
}
×
505

506
void TelemetryImpl::set_rate_fixedwing_metrics_async(
×
507
    double rate_hz, Telemetry::ResultCallback callback)
508
{
509
    _system_impl->set_msg_rate_async(
×
510
        MAVLINK_MSG_ID_VFR_HUD,
511
        rate_hz,
512
        [callback](MavlinkCommandSender::Result command_result, float) {
×
513
            command_result_callback(command_result, callback);
×
514
        });
×
515
}
×
516

517
void TelemetryImpl::set_rate_ground_truth_async(double rate_hz, Telemetry::ResultCallback callback)
×
518
{
519
    _system_impl->set_msg_rate_async(
×
520
        MAVLINK_MSG_ID_HIL_STATE_QUATERNION,
521
        rate_hz,
522
        [callback](MavlinkCommandSender::Result command_result, float) {
×
523
            command_result_callback(command_result, callback);
×
524
        });
×
525
}
×
526

527
void TelemetryImpl::set_rate_gps_info_async(double rate_hz, Telemetry::ResultCallback callback)
×
528
{
529
    _system_impl->set_msg_rate_async(
×
530
        MAVLINK_MSG_ID_GPS_RAW_INT,
531
        rate_hz,
532
        [callback](MavlinkCommandSender::Result command_result, float) {
×
533
            command_result_callback(command_result, callback);
×
534
        });
×
535
}
×
536

537
void TelemetryImpl::set_rate_battery_async(double rate_hz, Telemetry::ResultCallback callback)
×
538
{
539
    _system_impl->set_msg_rate_async(
×
540
        MAVLINK_MSG_ID_BATTERY_STATUS,
541
        rate_hz,
542
        [callback](MavlinkCommandSender::Result command_result, float) {
×
543
            command_result_callback(command_result, callback);
×
544
        });
×
545
}
×
546

547
void TelemetryImpl::set_rate_rc_status_async(double rate_hz, Telemetry::ResultCallback callback)
×
548
{
549
    UNUSED(rate_hz);
×
550
    LogWarn() << "System status is usually fixed at 1 Hz";
×
551
    _system_impl->call_user_callback([callback]() { callback(Telemetry::Result::Unsupported); });
×
552
}
×
553

554
void TelemetryImpl::set_rate_unix_epoch_time_async(
×
555
    double rate_hz, Telemetry::ResultCallback callback)
556
{
557
    _system_impl->set_msg_rate_async(
×
558
        MAVLINK_MSG_ID_UTM_GLOBAL_POSITION,
559
        rate_hz,
560
        [callback](MavlinkCommandSender::Result command_result, float) {
×
561
            command_result_callback(command_result, callback);
×
562
        });
×
563
}
×
564

565
void TelemetryImpl::set_rate_actuator_control_target_async(
×
566
    double rate_hz, Telemetry::ResultCallback callback)
567
{
568
    _system_impl->set_msg_rate_async(
×
569
        MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET,
570
        rate_hz,
571
        [callback](MavlinkCommandSender::Result command_result, float) {
×
572
            command_result_callback(command_result, callback);
×
573
        });
×
574
}
×
575

576
void TelemetryImpl::set_rate_actuator_output_status_async(
×
577
    double rate_hz, Telemetry::ResultCallback callback)
578
{
579
    _system_impl->set_msg_rate_async(
×
580
        MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS,
581
        rate_hz,
582
        [callback](MavlinkCommandSender::Result command_result, float) {
×
583
            command_result_callback(command_result, callback);
×
584
        });
×
585
}
×
586

587
void TelemetryImpl::set_rate_odometry_async(double rate_hz, Telemetry::ResultCallback callback)
×
588
{
589
    _system_impl->set_msg_rate_async(
×
590
        MAVLINK_MSG_ID_ODOMETRY,
591
        rate_hz,
592
        [callback](MavlinkCommandSender::Result command_result, float) {
×
593
            command_result_callback(command_result, callback);
×
594
        });
×
595
}
×
596

597
void TelemetryImpl::set_rate_distance_sensor_async(
×
598
    double rate_hz, Telemetry::ResultCallback callback)
599
{
600
    _system_impl->set_msg_rate_async(
×
601
        MAVLINK_MSG_ID_DISTANCE_SENSOR,
602
        rate_hz,
603
        [callback](MavlinkCommandSender::Result command_result, float) {
×
604
            command_result_callback(command_result, callback);
×
605
        });
×
606
}
×
607

608
void TelemetryImpl::set_rate_scaled_pressure_async(
×
609
    double rate_hz, Telemetry::ResultCallback callback)
610
{
611
    _system_impl->set_msg_rate_async(
×
612
        MAVLINK_MSG_ID_SCALED_PRESSURE,
613
        rate_hz,
614
        [callback](MavlinkCommandSender::Result command_result, float) {
×
615
            command_result_callback(command_result, callback);
×
616
        });
×
617
}
×
618

619
Telemetry::Result
620
TelemetryImpl::telemetry_result_from_command_result(MavlinkCommandSender::Result command_result)
×
621
{
622
    switch (command_result) {
×
623
        case MavlinkCommandSender::Result::Success:
×
624
            return Telemetry::Result::Success;
×
625
        case MavlinkCommandSender::Result::NoSystem:
×
626
            return Telemetry::Result::NoSystem;
×
627
        case MavlinkCommandSender::Result::ConnectionError:
×
628
            return Telemetry::Result::ConnectionError;
×
629
        case MavlinkCommandSender::Result::Busy:
×
630
            return Telemetry::Result::Busy;
×
631
        case MavlinkCommandSender::Result::Denied:
×
632
            // FALLTHROUGH
633
        case MavlinkCommandSender::Result::TemporarilyRejected:
634
            return Telemetry::Result::CommandDenied;
×
635
        case MavlinkCommandSender::Result::Timeout:
×
636
            return Telemetry::Result::Timeout;
×
637
        case MavlinkCommandSender::Result::Unsupported:
×
638
            return Telemetry::Result::Unsupported;
×
639
        default:
×
640
            return Telemetry::Result::Unknown;
×
641
    }
642
}
643

644
void TelemetryImpl::command_result_callback(
×
645
    MavlinkCommandSender::Result command_result, const Telemetry::ResultCallback& callback)
646
{
647
    Telemetry::Result action_result = telemetry_result_from_command_result(command_result);
×
648

649
    callback(action_result);
×
650
}
×
651

652
void TelemetryImpl::process_position_velocity_ned(const mavlink_message_t& message)
×
653
{
654
    mavlink_local_position_ned_t local_position;
×
655
    mavlink_msg_local_position_ned_decode(&message, &local_position);
×
656

657
    Telemetry::PositionVelocityNed position_velocity;
×
658
    position_velocity.position.north_m = local_position.x;
×
659
    position_velocity.position.east_m = local_position.y;
×
660
    position_velocity.position.down_m = local_position.z;
×
661
    position_velocity.velocity.north_m_s = local_position.vx;
×
662
    position_velocity.velocity.east_m_s = local_position.vy;
×
663
    position_velocity.velocity.down_m_s = local_position.vz;
×
664

665
    set_position_velocity_ned(position_velocity);
×
666

667
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
668
    _position_velocity_ned_subscriptions.queue(position_velocity_ned(), [this](const auto& func) {
×
669
        _system_impl->call_user_callback(func);
×
670
    });
×
671

672
    set_health_local_position(true);
×
673
}
×
674

675
void TelemetryImpl::process_global_position_int(const mavlink_message_t& message)
×
676
{
677
    mavlink_global_position_int_t global_position_int;
×
678
    mavlink_msg_global_position_int_decode(&message, &global_position_int);
×
679

680
    {
681
        Telemetry::Position position;
×
682
        position.latitude_deg = global_position_int.lat * 1e-7;
×
683
        position.longitude_deg = global_position_int.lon * 1e-7;
×
684
        position.absolute_altitude_m = global_position_int.alt * 1e-3f;
×
685
        position.relative_altitude_m = global_position_int.relative_alt * 1e-3f;
×
686
        set_position(position);
×
687
    }
688

689
    {
690
        Telemetry::VelocityNed velocity;
×
691
        velocity.north_m_s = global_position_int.vx * 1e-2f;
×
692
        velocity.east_m_s = global_position_int.vy * 1e-2f;
×
693
        velocity.down_m_s = global_position_int.vz * 1e-2f;
×
694
        set_velocity_ned(velocity);
×
695
    }
696

697
    {
698
        Telemetry::Heading heading;
×
699
        heading.heading_deg = (global_position_int.hdg != std::numeric_limits<uint16_t>::max()) ?
×
700
                                  static_cast<double>(global_position_int.hdg) * 1e-2 :
×
701
                                  static_cast<double>(NAN);
702
        set_heading(heading);
×
703
    }
704

705
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
706
    _position_subscriptions.queue(
×
707
        position(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
708

709
    _velocity_ned_subscriptions.queue(
×
710
        velocity_ned(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
711

712
    _heading_subscriptions.queue(
×
713
        heading(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
714
}
×
715

716
void TelemetryImpl::process_home_position(const mavlink_message_t& message)
×
717
{
718
    mavlink_home_position_t home_position;
×
719
    mavlink_msg_home_position_decode(&message, &home_position);
×
720
    Telemetry::Position new_pos;
×
721
    new_pos.latitude_deg = home_position.latitude * 1e-7;
×
722
    new_pos.longitude_deg = home_position.longitude * 1e-7;
×
723
    new_pos.absolute_altitude_m = home_position.altitude * 1e-3f;
×
724
    new_pos.relative_altitude_m = 0.0f; // 0 by definition.
×
725

726
    set_home_position(new_pos);
×
727

728
    set_health_home_position(true);
×
729

730
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
731
    _home_position_subscriptions.queue(
×
732
        home(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
733
}
×
734

735
void TelemetryImpl::process_attitude(const mavlink_message_t& message)
×
736
{
737
    mavlink_attitude_t attitude;
×
738
    mavlink_msg_attitude_decode(&message, &attitude);
×
739

740
    Telemetry::EulerAngle euler_angle;
×
741
    euler_angle.roll_deg = to_deg_from_rad(attitude.roll);
×
742
    euler_angle.pitch_deg = to_deg_from_rad(attitude.pitch);
×
743
    euler_angle.yaw_deg = to_deg_from_rad(attitude.yaw);
×
744
    euler_angle.timestamp_us = static_cast<uint64_t>(attitude.time_boot_ms) * 1000;
×
745
    set_attitude_euler(euler_angle);
×
746

747
    Telemetry::AngularVelocityBody angular_velocity_body;
×
748
    angular_velocity_body.roll_rad_s = attitude.rollspeed;
×
749
    angular_velocity_body.pitch_rad_s = attitude.pitchspeed;
×
750
    angular_velocity_body.yaw_rad_s = attitude.yawspeed;
×
751
    set_attitude_angular_velocity_body(angular_velocity_body);
×
752

753
    _attitude_euler_angle_subscriptions.queue(
×
754
        attitude_euler(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
755

756
    _attitude_angular_velocity_body_subscriptions.queue(
×
757
        attitude_angular_velocity_body(),
758
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
759
}
×
760

761
void TelemetryImpl::process_attitude_quaternion(const mavlink_message_t& message)
×
762
{
763
    mavlink_attitude_quaternion_t mavlink_attitude_quaternion;
×
764
    mavlink_msg_attitude_quaternion_decode(&message, &mavlink_attitude_quaternion);
×
765

766
    Telemetry::Quaternion quaternion;
×
767
    quaternion.w = mavlink_attitude_quaternion.q1;
×
768
    quaternion.x = mavlink_attitude_quaternion.q2;
×
769
    quaternion.y = mavlink_attitude_quaternion.q3;
×
770
    quaternion.z = mavlink_attitude_quaternion.q4;
×
771
    quaternion.timestamp_us =
×
772
        static_cast<uint64_t>(mavlink_attitude_quaternion.time_boot_ms) * 1000;
×
773

774
    Telemetry::AngularVelocityBody angular_velocity_body;
×
775
    angular_velocity_body.roll_rad_s = mavlink_attitude_quaternion.rollspeed;
×
776
    angular_velocity_body.pitch_rad_s = mavlink_attitude_quaternion.pitchspeed;
×
777
    angular_velocity_body.yaw_rad_s = mavlink_attitude_quaternion.yawspeed;
×
778

779
    set_attitude_quaternion(quaternion);
×
780

781
    set_attitude_angular_velocity_body(angular_velocity_body);
×
782

783
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
784
    _attitude_quaternion_angle_subscriptions.queue(attitude_quaternion(), [this](const auto& func) {
×
785
        _system_impl->call_user_callback(func);
×
786
    });
×
787

788
    _attitude_angular_velocity_body_subscriptions.queue(
×
789
        attitude_angular_velocity_body(),
790
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
791
}
×
792

793
void TelemetryImpl::process_altitude(const mavlink_message_t& message)
×
794
{
795
    mavlink_altitude_t mavlink_altitude;
×
796
    mavlink_msg_altitude_decode(&message, &mavlink_altitude);
×
797

798
    Telemetry::Altitude new_altitude;
×
799
    new_altitude.altitude_monotonic_m = mavlink_altitude.altitude_monotonic;
×
800
    new_altitude.altitude_amsl_m = mavlink_altitude.altitude_amsl;
×
801
    new_altitude.altitude_local_m = mavlink_altitude.altitude_local;
×
802
    new_altitude.altitude_relative_m = mavlink_altitude.altitude_relative;
×
803
    new_altitude.altitude_terrain_m = mavlink_altitude.altitude_terrain;
×
804
    new_altitude.bottom_clearance_m = mavlink_altitude.bottom_clearance;
×
805

806
    set_altitude(new_altitude);
×
807

808
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
809
    _altitude_subscriptions.queue(
×
810
        altitude(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
811
}
×
812

813
void TelemetryImpl::process_wind(const mavlink_message_t& message)
×
814
{
815
    __mavlink_wind_cov_t mavlink_wind_cov;
×
816
    mavlink_msg_wind_cov_decode(&message, &mavlink_wind_cov);
×
817

818
    Telemetry::Wind new_wind;
×
819
    new_wind.wind_x_ned_m_s = mavlink_wind_cov.wind_x;
×
820
    new_wind.wind_y_ned_m_s = mavlink_wind_cov.wind_y;
×
821
    new_wind.wind_z_ned_m_s = mavlink_wind_cov.wind_z;
×
822
    new_wind.horizontal_variability_stddev_m_s = mavlink_wind_cov.var_horiz;
×
823
    new_wind.vertical_variability_stddev_m_s = mavlink_wind_cov.var_vert;
×
824
    new_wind.wind_altitude_msl_m = mavlink_wind_cov.wind_alt;
×
825
    new_wind.horizontal_wind_speed_accuracy_m_s = mavlink_wind_cov.horiz_accuracy;
×
826
    new_wind.vertical_wind_speed_accuracy_m_s = mavlink_wind_cov.vert_accuracy;
×
827

828
    set_wind(new_wind);
×
829

830
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
831
    _wind_subscriptions.queue(
×
832
        wind(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
833
}
×
834

835
void TelemetryImpl::process_imu_reading_ned(const mavlink_message_t& message)
×
836
{
837
    mavlink_highres_imu_t highres_imu;
×
838
    mavlink_msg_highres_imu_decode(&message, &highres_imu);
×
839
    Telemetry::Imu new_imu;
×
840
    new_imu.acceleration_frd.forward_m_s2 = highres_imu.xacc;
×
841
    new_imu.acceleration_frd.right_m_s2 = highres_imu.yacc;
×
842
    new_imu.acceleration_frd.down_m_s2 = highres_imu.zacc;
×
843
    new_imu.angular_velocity_frd.forward_rad_s = highres_imu.xgyro;
×
844
    new_imu.angular_velocity_frd.right_rad_s = highres_imu.ygyro;
×
845
    new_imu.angular_velocity_frd.down_rad_s = highres_imu.zgyro;
×
846
    new_imu.magnetic_field_frd.forward_gauss = highres_imu.xmag;
×
847
    new_imu.magnetic_field_frd.right_gauss = highres_imu.ymag;
×
848
    new_imu.magnetic_field_frd.down_gauss = highres_imu.zmag;
×
849
    new_imu.temperature_degc = highres_imu.temperature;
×
850
    new_imu.timestamp_us = highres_imu.time_usec;
×
851

852
    set_imu_reading_ned(new_imu);
×
853

854
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
855
    _imu_reading_ned_subscriptions.queue(
×
856
        imu(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
857
}
×
858

859
void TelemetryImpl::process_scaled_imu(const mavlink_message_t& message)
×
860
{
861
    mavlink_scaled_imu_t scaled_imu_reading;
×
862
    mavlink_msg_scaled_imu_decode(&message, &scaled_imu_reading);
×
863
    Telemetry::Imu new_imu;
×
864
    new_imu.acceleration_frd.forward_m_s2 = scaled_imu_reading.xacc;
×
865
    new_imu.acceleration_frd.right_m_s2 = scaled_imu_reading.yacc;
×
866
    new_imu.acceleration_frd.down_m_s2 = scaled_imu_reading.zacc;
×
867
    new_imu.angular_velocity_frd.forward_rad_s = scaled_imu_reading.xgyro;
×
868
    new_imu.angular_velocity_frd.right_rad_s = scaled_imu_reading.ygyro;
×
869
    new_imu.angular_velocity_frd.down_rad_s = scaled_imu_reading.zgyro;
×
870
    new_imu.magnetic_field_frd.forward_gauss = scaled_imu_reading.xmag;
×
871
    new_imu.magnetic_field_frd.right_gauss = scaled_imu_reading.ymag;
×
872
    new_imu.magnetic_field_frd.down_gauss = scaled_imu_reading.zmag;
×
873
    new_imu.temperature_degc = static_cast<float>(scaled_imu_reading.temperature) * 1e-2f;
×
874
    new_imu.timestamp_us = static_cast<uint64_t>(scaled_imu_reading.time_boot_ms) * 1000;
×
875

876
    set_scaled_imu(new_imu);
×
877

878
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
879
    _scaled_imu_subscriptions.queue(
×
880
        scaled_imu(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
881
}
×
882

883
void TelemetryImpl::process_raw_imu(const mavlink_message_t& message)
×
884
{
885
    mavlink_raw_imu_t raw_imu_reading;
×
886
    mavlink_msg_raw_imu_decode(&message, &raw_imu_reading);
×
887
    Telemetry::Imu new_imu;
×
888
    new_imu.acceleration_frd.forward_m_s2 = raw_imu_reading.xacc;
×
889
    new_imu.acceleration_frd.right_m_s2 = raw_imu_reading.yacc;
×
890
    new_imu.acceleration_frd.down_m_s2 = raw_imu_reading.zacc;
×
891
    new_imu.angular_velocity_frd.forward_rad_s = raw_imu_reading.xgyro;
×
892
    new_imu.angular_velocity_frd.right_rad_s = raw_imu_reading.ygyro;
×
893
    new_imu.angular_velocity_frd.down_rad_s = raw_imu_reading.zgyro;
×
894
    new_imu.magnetic_field_frd.forward_gauss = raw_imu_reading.xmag;
×
895
    new_imu.magnetic_field_frd.right_gauss = raw_imu_reading.ymag;
×
896
    new_imu.magnetic_field_frd.down_gauss = raw_imu_reading.zmag;
×
897
    new_imu.temperature_degc = static_cast<float>(raw_imu_reading.temperature) * 1e-2f;
×
898
    new_imu.timestamp_us = raw_imu_reading.time_usec;
×
899

900
    set_raw_imu(new_imu);
×
901

902
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
903
    _raw_imu_subscriptions.queue(
×
904
        raw_imu(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
905
}
×
906

907
void TelemetryImpl::process_gps_raw_int(const mavlink_message_t& message)
×
908
{
909
    mavlink_gps_raw_int_t gps_raw_int;
×
910
    mavlink_msg_gps_raw_int_decode(&message, &gps_raw_int);
×
911

912
    Telemetry::FixType fix_type;
913
    switch (gps_raw_int.fix_type) {
×
914
        case 0:
×
915
            fix_type = Telemetry::FixType::NoGps;
×
916
            break;
×
917
        case 1:
×
918
            fix_type = Telemetry::FixType::NoFix;
×
919
            break;
×
920
        case 2:
×
921
            fix_type = Telemetry::FixType::Fix2D;
×
922
            break;
×
923
        case 3:
×
924
            fix_type = Telemetry::FixType::Fix3D;
×
925
            break;
×
926
        case 4:
×
927
            fix_type = Telemetry::FixType::FixDgps;
×
928
            break;
×
929
        case 5:
×
930
            fix_type = Telemetry::FixType::RtkFloat;
×
931
            break;
×
932
        case 6:
×
933
            fix_type = Telemetry::FixType::RtkFixed;
×
934
            break;
×
935

936
        default:
×
937
            LogErr() << "Received unknown GPS fix type!";
×
938
            fix_type = Telemetry::FixType::NoGps;
×
939
            break;
×
940
    }
941

942
    Telemetry::GpsInfo new_gps_info;
×
943
    new_gps_info.num_satellites = gps_raw_int.satellites_visible;
×
944
    new_gps_info.fix_type = fix_type;
×
945
    set_gps_info(new_gps_info);
×
946

947
    Telemetry::RawGps raw_gps_info;
×
948
    raw_gps_info.timestamp_us = gps_raw_int.time_usec;
×
949
    raw_gps_info.latitude_deg = gps_raw_int.lat * 1e-7;
×
950
    raw_gps_info.longitude_deg = gps_raw_int.lon * 1e-7;
×
951
    raw_gps_info.absolute_altitude_m = gps_raw_int.alt * 1e-3f;
×
952
    raw_gps_info.hdop = static_cast<float>(gps_raw_int.eph) * 1e-2f;
×
953
    raw_gps_info.vdop = static_cast<float>(gps_raw_int.epv) * 1e-2f;
×
954
    raw_gps_info.velocity_m_s = static_cast<float>(gps_raw_int.vel) * 1e-2f;
×
955
    raw_gps_info.cog_deg = static_cast<float>(gps_raw_int.cog) * 1e-2f;
×
956
    raw_gps_info.altitude_ellipsoid_m = static_cast<float>(gps_raw_int.alt_ellipsoid) * 1e-3f;
×
957
    raw_gps_info.horizontal_uncertainty_m = static_cast<float>(gps_raw_int.h_acc) * 1e-3f;
×
958
    raw_gps_info.vertical_uncertainty_m = static_cast<float>(gps_raw_int.v_acc) * 1e-3f;
×
959
    raw_gps_info.velocity_uncertainty_m_s = static_cast<float>(gps_raw_int.vel_acc) * 1e-3f;
×
960
    raw_gps_info.heading_uncertainty_deg = static_cast<float>(gps_raw_int.hdg_acc) * 1e-5f;
×
961
    raw_gps_info.yaw_deg = static_cast<float>(gps_raw_int.yaw) * 1e-2f;
×
962
    set_raw_gps(raw_gps_info);
×
963

964
    {
965
        std::lock_guard<std::mutex> lock(_subscription_mutex);
×
966
        _gps_info_subscriptions.queue(
×
967
            gps_info(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
968
        _raw_gps_subscriptions.queue(
×
969
            raw_gps(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
970
    }
×
971
}
×
972

973
void TelemetryImpl::process_ground_truth(const mavlink_message_t& message)
×
974
{
975
    mavlink_hil_state_quaternion_t hil_state_quaternion;
×
976
    mavlink_msg_hil_state_quaternion_decode(&message, &hil_state_quaternion);
×
977

978
    Telemetry::GroundTruth new_ground_truth;
×
979
    new_ground_truth.latitude_deg = hil_state_quaternion.lat * 1e-7;
×
980
    new_ground_truth.longitude_deg = hil_state_quaternion.lon * 1e-7;
×
981
    new_ground_truth.absolute_altitude_m = hil_state_quaternion.alt * 1e-3f;
×
982

983
    set_ground_truth(new_ground_truth);
×
984

985
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
986
    _ground_truth_subscriptions.queue(
×
987
        ground_truth(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
988
}
×
989

990
void TelemetryImpl::process_extended_sys_state(const mavlink_message_t& message)
×
991
{
992
    mavlink_extended_sys_state_t extended_sys_state;
×
993
    mavlink_msg_extended_sys_state_decode(&message, &extended_sys_state);
×
994

995
    {
996
        Telemetry::LandedState landed_state = to_landed_state(extended_sys_state);
×
997
        set_landed_state(landed_state);
×
998

999
        Telemetry::VtolState vtol_state = to_vtol_state(extended_sys_state);
×
1000
        set_vtol_state(vtol_state);
×
1001
    }
1002

1003
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1004
    _landed_state_subscriptions.queue(
×
1005
        landed_state(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1006

1007
    _vtol_state_subscriptions.queue(
×
1008
        vtol_state(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1009

1010
    if (extended_sys_state.landed_state == MAV_LANDED_STATE_IN_AIR ||
×
1011
        extended_sys_state.landed_state == MAV_LANDED_STATE_TAKEOFF ||
×
1012
        extended_sys_state.landed_state == MAV_LANDED_STATE_LANDING) {
×
1013
        set_in_air(true);
×
1014
    } else if (extended_sys_state.landed_state == MAV_LANDED_STATE_ON_GROUND) {
×
1015
        set_in_air(false);
×
1016
    }
1017
    // If landed_state is undefined, we use what we have received last.
1018

1019
    _in_air_subscriptions.queue(
×
1020
        in_air(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1021
}
×
1022
void TelemetryImpl::process_fixedwing_metrics(const mavlink_message_t& message)
×
1023
{
1024
    mavlink_vfr_hud_t vfr_hud;
×
1025
    mavlink_msg_vfr_hud_decode(&message, &vfr_hud);
×
1026

1027
    Telemetry::FixedwingMetrics new_fixedwing_metrics;
×
1028
    new_fixedwing_metrics.airspeed_m_s = vfr_hud.airspeed;
×
1029
    new_fixedwing_metrics.groundspeed_m_s = vfr_hud.groundspeed;
×
1030
    new_fixedwing_metrics.heading_deg = vfr_hud.heading;
×
1031
    new_fixedwing_metrics.throttle_percentage = vfr_hud.throttle * 1e-2f;
×
1032
    new_fixedwing_metrics.absolute_altitude_m = vfr_hud.alt;
×
1033
    new_fixedwing_metrics.climb_rate_m_s = vfr_hud.climb;
×
1034

1035
    set_fixedwing_metrics(new_fixedwing_metrics);
×
1036

1037
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1038
    _fixedwing_metrics_subscriptions.queue(
×
1039
        fixedwing_metrics(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1040
}
×
1041

1042
void TelemetryImpl::process_sys_status(const mavlink_message_t& message)
×
1043
{
1044
    mavlink_sys_status_t sys_status;
×
1045
    mavlink_msg_sys_status_decode(&message, &sys_status);
×
1046

1047
    if (!_has_bat_status) {
×
1048
        Telemetry::Battery new_battery;
×
1049
        new_battery.voltage_v = sys_status.voltage_battery * 1e-3f;
×
1050
        new_battery.remaining_percent = sys_status.battery_remaining;
×
1051

1052
        set_battery(new_battery);
×
1053

1054
        {
1055
            std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1056
            _battery_subscriptions.queue(
×
1057
                battery(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1058
        }
×
1059
    }
1060

1061
    const bool rc_ok =
×
1062
        sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
×
1063

1064
    set_rc_status({rc_ok}, std::nullopt);
×
1065

1066
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_GYRO) {
×
1067
        set_health_gyrometer_calibration(
×
1068
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_GYRO);
×
1069
    }
1070

1071
    // PX4 v1.15.3 and previous has the bug that it doesn't set 3D_ACCEL present.
1072
    // Therefore, we ignore that and look at the health flag only.
1073
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_ACCEL ||
×
1074
        _system_impl->autopilot() == Autopilot::Px4) {
×
1075
        set_health_accelerometer_calibration(
×
1076
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_ACCEL);
×
1077
    }
1078

1079
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_MAG) {
×
1080
        set_health_magnetometer_calibration(
×
1081
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_MAG);
×
1082
    }
1083

1084
    const bool global_position_ok =
1085
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_GPS);
×
1086

1087
    // FIXME: There is nothing really set in PX4 for local position from what I can tell,
1088
    //        so the best we can do for now is to set it based on GPS as a fallback.
1089

1090
    const bool local_position_ok =
1091
        global_position_ok ||
×
1092
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW) ||
×
1093
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_VISION_POSITION);
×
1094

1095
    set_health_local_position(local_position_ok);
×
1096
    set_health_global_position(global_position_ok);
×
1097

1098
    set_rc_status({rc_ok}, std::nullopt);
×
1099

1100
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1101
    _rc_status_subscriptions.queue(
×
1102
        rc_status(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1103

1104
    const bool armable = sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_PREARM_CHECK;
×
1105
    set_health_armable(armable);
×
1106
    _health_all_ok_subscriptions.queue(
×
1107
        health_all_ok(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1108
}
×
1109

1110
bool TelemetryImpl::sys_status_present_enabled_health(
×
1111
    const mavlink_sys_status_t& sys_status, MAV_SYS_STATUS_SENSOR flag)
1112
{
1113
    // FIXME: it doesn't look like PX4 sets enabled for GPS
1114
    return (sys_status.onboard_control_sensors_present & flag) != 0 &&
×
1115
           // (sys_status.onboard_control_sensors_enabled & flag) != 0 &&
1116
           (sys_status.onboard_control_sensors_health & flag) != 0;
×
1117
}
1118

1119
void TelemetryImpl::process_battery_status(const mavlink_message_t& message)
×
1120
{
1121
    mavlink_battery_status_t bat_status;
×
1122
    mavlink_msg_battery_status_decode(&message, &bat_status);
×
1123

1124
    _has_bat_status = true;
×
1125

1126
    Telemetry::Battery new_battery;
×
1127
    new_battery.id = bat_status.id;
×
1128
    new_battery.temperature_degc = (bat_status.temperature == std::numeric_limits<int16_t>::max()) ?
×
1129
                                       static_cast<float>(NAN) :
1130
                                       bat_status.temperature * 1e-2f; // cdegC to degC
×
1131
    new_battery.voltage_v = 0.0f;
×
1132
    for (int i = 0; i < 10; ++i) {
×
1133
        if (bat_status.voltages[i] == std::numeric_limits<uint16_t>::max()) {
×
1134
            break;
×
1135
        }
1136
        new_battery.voltage_v += static_cast<float>(bat_status.voltages[i]) * 1e-3f;
×
1137
    }
1138

1139
    for (int i = 0; i < 4; ++i) {
×
1140
        if (bat_status.voltages_ext[i] == std::numeric_limits<uint16_t>::max()) {
×
1141
            // Some implementations out there set it to UINT16_MAX to signal invalid.
1142
            // That's not up to the spec but we can ignore it nevertheless to be backwards
1143
            // compatible.
1144
            break;
×
1145
        } else if (bat_status.voltages_ext[i] > 1) {
×
1146
            // A value of 1 means 0 mV.
1147
            new_battery.voltage_v += static_cast<float>(bat_status.voltages_ext[i]) * 1e-3f;
×
1148
        }
1149
    }
1150

1151
    new_battery.remaining_percent = bat_status.battery_remaining;
×
1152
    new_battery.current_battery_a = (bat_status.current_battery == -1) ?
×
1153
                                        static_cast<float>(NAN) :
1154
                                        bat_status.current_battery * 1e-2f; // cA to A
×
1155
    new_battery.capacity_consumed_ah = (bat_status.current_consumed == -1) ?
×
1156
                                           static_cast<float>(NAN) :
1157
                                           bat_status.current_consumed * 1e-3f; // mAh to Ah
×
1158
    new_battery.time_remaining_s =
×
1159
        (bat_status.time_remaining == 0 ? static_cast<float>(NAN) : bat_status.time_remaining);
×
1160

1161
    Telemetry::BatteryFunction battery_function;
1162
    switch (bat_status.battery_function) {
×
1163
        case MAV_BATTERY_FUNCTION_ALL:
×
1164
            battery_function = Telemetry::BatteryFunction::All;
×
1165
            break;
×
1166
        case MAV_BATTERY_FUNCTION_PROPULSION:
×
1167
            battery_function = Telemetry::BatteryFunction::Propulsion;
×
1168
            break;
×
1169
        case MAV_BATTERY_FUNCTION_AVIONICS:
×
1170
            battery_function = Telemetry::BatteryFunction::Avionics;
×
1171
            break;
×
1172
        case MAV_BATTERY_FUNCTION_PAYLOAD:
×
1173
            battery_function = Telemetry::BatteryFunction::Payload;
×
1174
            break;
×
1175
        case MAV_BATTERY_FUNCTION_UNKNOWN:
×
1176
        // Fallthrough
1177
        default:
1178
            battery_function = Telemetry::BatteryFunction::Unknown;
×
1179
            break;
×
1180
    }
1181
    new_battery.battery_function = battery_function;
×
1182
    set_battery(new_battery);
×
1183

1184
    {
1185
        std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1186
        _battery_subscriptions.queue(
×
1187
            battery(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1188
    }
×
1189
}
×
1190

UNCOV
1191
void TelemetryImpl::process_heartbeat(const mavlink_message_t& message)
×
1192
{
UNCOV
1193
    if (message.compid != MAV_COMP_ID_AUTOPILOT1) {
×
1194
        return;
×
1195
    }
1196

UNCOV
1197
    mavlink_heartbeat_t heartbeat;
×
UNCOV
1198
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
×
1199

UNCOV
1200
    set_armed(((heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) ? true : false));
×
1201

UNCOV
1202
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
UNCOV
1203
    _armed_subscriptions.queue(
×
UNCOV
1204
        armed(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1205

UNCOV
1206
    _flight_mode_subscriptions.queue(
×
UNCOV
1207
        telemetry_flight_mode_from_flight_mode(_system_impl->get_flight_mode()),
×
1208
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1209

UNCOV
1210
    _health_subscriptions.queue(
×
1211
        health(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1212

UNCOV
1213
    _health_all_ok_subscriptions.queue(
×
UNCOV
1214
        health_all_ok(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
UNCOV
1215
}
×
1216

1217
void TelemetryImpl::receive_statustext(const MavlinkStatustextHandler::Statustext& statustext)
3✔
1218
{
1219
    Telemetry::StatusText new_status_text;
3✔
1220

1221
    switch (statustext.severity) {
3✔
1222
        case MAV_SEVERITY_EMERGENCY:
×
1223
            new_status_text.type = Telemetry::StatusTextType::Emergency;
×
1224
            break;
×
1225
        case MAV_SEVERITY_ALERT:
×
1226
            new_status_text.type = Telemetry::StatusTextType::Alert;
×
1227
            break;
×
1228
        case MAV_SEVERITY_CRITICAL:
×
1229
            new_status_text.type = Telemetry::StatusTextType::Critical;
×
1230
            break;
×
1231
        case MAV_SEVERITY_ERROR:
×
1232
            new_status_text.type = Telemetry::StatusTextType::Error;
×
1233
            break;
×
1234
        case MAV_SEVERITY_WARNING:
×
1235
            new_status_text.type = Telemetry::StatusTextType::Warning;
×
1236
            break;
×
1237
        case MAV_SEVERITY_NOTICE:
×
1238
            new_status_text.type = Telemetry::StatusTextType::Notice;
×
1239
            break;
×
1240
        case MAV_SEVERITY_INFO:
3✔
1241
            new_status_text.type = Telemetry::StatusTextType::Info;
3✔
1242
            break;
3✔
1243
        case MAV_SEVERITY_DEBUG:
×
1244
            new_status_text.type = Telemetry::StatusTextType::Debug;
×
1245
            break;
×
1246
        default:
×
1247
            LogWarn() << "Unknown StatusText severity";
×
1248
            new_status_text.type = Telemetry::StatusTextType::Info;
×
1249
            break;
×
1250
    }
1251

1252
    new_status_text.text = statustext.text;
3✔
1253

1254
    set_status_text(new_status_text);
3✔
1255

1256
    std::lock_guard<std::mutex> lock(_subscription_mutex);
6✔
1257
    _status_text_subscriptions.queue(
9✔
1258
        status_text(), [this](const auto& func) { _system_impl->call_user_callback(func); });
11✔
1259
}
3✔
1260

1261
void TelemetryImpl::process_rc_channels(const mavlink_message_t& message)
×
1262
{
1263
    mavlink_rc_channels_t rc_channels;
×
1264
    mavlink_msg_rc_channels_decode(&message, &rc_channels);
×
1265

1266
    if (rc_channels.rssi != std::numeric_limits<uint8_t>::max()) {
×
1267
        set_rc_status(std::nullopt, {rc_channels.rssi});
×
1268
    }
1269

1270
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1271
    _rc_status_subscriptions.queue(
×
1272
        rc_status(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1273
}
×
1274

1275
void TelemetryImpl::process_unix_epoch_time(const mavlink_message_t& message)
×
1276
{
1277
    mavlink_system_time_t system_time;
×
1278
    mavlink_msg_system_time_decode(&message, &system_time);
×
1279

1280
    set_unix_epoch_time_us(system_time.time_unix_usec);
×
1281

1282
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1283
    _unix_epoch_time_subscriptions.queue(
×
1284
        unix_epoch_time(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1285
}
×
1286

1287
void TelemetryImpl::process_actuator_control_target(const mavlink_message_t& message)
×
1288
{
1289
    mavlink_set_actuator_control_target_t target;
×
1290
    mavlink_msg_set_actuator_control_target_decode(&message, &target);
×
1291

1292
    uint32_t group = target.group_mlx;
×
1293
    std::vector<float> controls;
×
1294

1295
    const unsigned control_size = sizeof(target.controls) / sizeof(target.controls[0]);
×
1296
    // Can't use std::copy because target is packed.
1297
    for (std::size_t i = 0; i < control_size; ++i) {
×
1298
        controls.push_back(target.controls[i]);
×
1299
    }
1300

1301
    set_actuator_control_target(group, controls);
×
1302

1303
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1304
    _actuator_control_target_subscriptions.queue(
×
1305
        actuator_control_target(),
×
1306
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1307
}
×
1308

1309
void TelemetryImpl::process_actuator_output_status(const mavlink_message_t& message)
×
1310
{
1311
    mavlink_actuator_output_status_t status;
×
1312
    mavlink_msg_actuator_output_status_decode(&message, &status);
×
1313

1314
    uint32_t active = status.active;
×
1315
    std::vector<float> actuators;
×
1316

1317
    const unsigned actuators_size = sizeof(status.actuator) / sizeof(status.actuator[0]);
×
1318
    // Can't use std::copy because status is packed.
1319
    for (std::size_t i = 0; i < actuators_size; ++i) {
×
1320
        actuators.push_back(status.actuator[i]);
×
1321
    }
1322

1323
    set_actuator_output_status(active, actuators);
×
1324

1325
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1326
    _actuator_output_status_subscriptions.queue(actuator_output_status(), [this](const auto& func) {
×
1327
        _system_impl->call_user_callback(func);
×
1328
    });
×
1329
}
×
1330

1331
void TelemetryImpl::process_odometry(const mavlink_message_t& message)
×
1332
{
1333
    mavlink_odometry_t odometry_msg;
×
1334
    mavlink_msg_odometry_decode(&message, &odometry_msg);
×
1335

1336
    Telemetry::Odometry odometry_struct{};
×
1337

1338
    odometry_struct.time_usec = odometry_msg.time_usec;
×
1339
    odometry_struct.frame_id = static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.frame_id);
×
1340
    odometry_struct.child_frame_id =
×
1341
        static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.child_frame_id);
×
1342

1343
    odometry_struct.position_body.x_m = odometry_msg.x;
×
1344
    odometry_struct.position_body.y_m = odometry_msg.y;
×
1345
    odometry_struct.position_body.z_m = odometry_msg.z;
×
1346

1347
    odometry_struct.q.w = odometry_msg.q[0];
×
1348
    odometry_struct.q.x = odometry_msg.q[1];
×
1349
    odometry_struct.q.y = odometry_msg.q[2];
×
1350
    odometry_struct.q.z = odometry_msg.q[3];
×
1351

1352
    odometry_struct.velocity_body.x_m_s = odometry_msg.vx;
×
1353
    odometry_struct.velocity_body.y_m_s = odometry_msg.vy;
×
1354
    odometry_struct.velocity_body.z_m_s = odometry_msg.vz;
×
1355

1356
    odometry_struct.angular_velocity_body.roll_rad_s = odometry_msg.rollspeed;
×
1357
    odometry_struct.angular_velocity_body.pitch_rad_s = odometry_msg.pitchspeed;
×
1358
    odometry_struct.angular_velocity_body.yaw_rad_s = odometry_msg.yawspeed;
×
1359

1360
    const std::size_t len_pose_covariance =
×
1361
        sizeof(odometry_msg.pose_covariance) / sizeof(odometry_msg.pose_covariance[0]);
1362
    for (std::size_t i = 0; i < len_pose_covariance; ++i) {
×
1363
        odometry_struct.pose_covariance.covariance_matrix.push_back(
×
1364
            odometry_msg.pose_covariance[i]);
×
1365
    }
1366

1367
    const std::size_t len_velocity_covariance =
×
1368
        sizeof(odometry_msg.velocity_covariance) / sizeof(odometry_msg.velocity_covariance[0]);
1369
    for (std::size_t i = 0; i < len_velocity_covariance; ++i) {
×
1370
        odometry_struct.velocity_covariance.covariance_matrix.push_back(
×
1371
            odometry_msg.velocity_covariance[i]);
×
1372
    }
1373

1374
    set_odometry(odometry_struct);
×
1375

1376
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1377
    _odometry_subscriptions.queue(
×
1378
        odometry(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1379
}
×
1380

1381
void TelemetryImpl::process_distance_sensor(const mavlink_message_t& message)
×
1382
{
1383
    mavlink_distance_sensor_t distance_sensor_msg;
×
1384
    mavlink_msg_distance_sensor_decode(&message, &distance_sensor_msg);
×
1385

1386
    Telemetry::DistanceSensor distance_sensor_struct{};
×
1387

1388
    distance_sensor_struct.minimum_distance_m =
×
1389
        static_cast<float>(distance_sensor_msg.min_distance) * 1e-2f; // cm to m
×
1390
    distance_sensor_struct.maximum_distance_m =
×
1391
        static_cast<float>(distance_sensor_msg.max_distance) * 1e-2f; // cm to m
×
1392
    distance_sensor_struct.current_distance_m =
×
1393
        static_cast<float>(distance_sensor_msg.current_distance) * 1e-2f; // cm to m
×
1394
    distance_sensor_struct.orientation = extractOrientation(distance_sensor_msg);
×
1395

1396
    set_distance_sensor(distance_sensor_struct);
×
1397

1398
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1399
    _distance_sensor_subscriptions.queue(
×
1400
        distance_sensor(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1401
}
×
1402

1403
Telemetry::EulerAngle
1404
TelemetryImpl::extractOrientation(mavlink_distance_sensor_t distance_sensor_msg)
×
1405
{
1406
    MavSensorOrientation orientation =
×
1407
        static_cast<MavSensorOrientation>(distance_sensor_msg.orientation);
×
1408

1409
    Telemetry::EulerAngle euler_angle;
×
1410
    euler_angle.roll_deg = 0;
×
1411
    euler_angle.pitch_deg = 0;
×
1412
    euler_angle.yaw_deg = 0;
×
1413

1414
    switch (orientation) {
×
1415
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_45: {
×
1416
            euler_angle.yaw_deg = 45;
×
1417
            break;
×
1418
        }
1419
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_90: {
×
1420
            euler_angle.yaw_deg = 90;
×
1421
            break;
×
1422
        }
1423
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_135: {
×
1424
            euler_angle.yaw_deg = 135;
×
1425
            break;
×
1426
        }
1427
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_180: {
×
1428
            euler_angle.yaw_deg = 180;
×
1429
            break;
×
1430
        }
1431
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_225: {
×
1432
            euler_angle.yaw_deg = 225;
×
1433
            break;
×
1434
        }
1435
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_270: {
×
1436
            euler_angle.yaw_deg = 270;
×
1437
            break;
×
1438
        }
1439
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_315: {
×
1440
            euler_angle.yaw_deg = 315;
×
1441
            break;
×
1442
        }
1443
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180: {
×
1444
            euler_angle.roll_deg = 180;
×
1445
            break;
×
1446
        }
1447
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_45: {
×
1448
            euler_angle.roll_deg = 180;
×
1449
            euler_angle.yaw_deg = 45;
×
1450
            break;
×
1451
        }
1452
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_90: {
×
1453
            euler_angle.roll_deg = 180;
×
1454
            euler_angle.yaw_deg = 90;
×
1455
            break;
×
1456
        }
1457
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_135: {
×
1458
            euler_angle.roll_deg = 180;
×
1459
            euler_angle.yaw_deg = 135;
×
1460
            break;
×
1461
        }
1462
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_180: {
×
1463
            euler_angle.pitch_deg = 180;
×
1464
            break;
×
1465
        }
1466
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_225: {
×
1467
            euler_angle.roll_deg = 180;
×
1468
            euler_angle.yaw_deg = 225;
×
1469
            break;
×
1470
        }
1471
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_270: {
×
1472
            euler_angle.roll_deg = 180;
×
1473
            euler_angle.yaw_deg = 270;
×
1474
            break;
×
1475
        }
1476
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_315: {
×
1477
            euler_angle.roll_deg = 180;
×
1478
            euler_angle.yaw_deg = 315;
×
1479
            break;
×
1480
        }
1481
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90: {
×
1482
            euler_angle.roll_deg = 90;
×
1483
            break;
×
1484
        }
1485
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_45: {
×
1486
            euler_angle.roll_deg = 90;
×
1487
            euler_angle.yaw_deg = 45;
×
1488
            break;
×
1489
        }
1490
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_90: {
×
1491
            euler_angle.roll_deg = 90;
×
1492
            euler_angle.yaw_deg = 90;
×
1493
            break;
×
1494
        }
1495
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_135: {
×
1496
            euler_angle.roll_deg = 90;
×
1497
            euler_angle.yaw_deg = 135;
×
1498
            break;
×
1499
        }
1500
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270: {
×
1501
            euler_angle.roll_deg = 270;
×
1502
            break;
×
1503
        }
1504
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_YAW_45: {
×
1505
            euler_angle.roll_deg = 270;
×
1506
            euler_angle.yaw_deg = 45;
×
1507
            break;
×
1508
        }
1509
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_YAW_90: {
×
1510
            euler_angle.roll_deg = 270;
×
1511
            euler_angle.yaw_deg = 90;
×
1512
            break;
×
1513
        }
1514
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_YAW_135: {
×
1515
            euler_angle.roll_deg = 270;
×
1516
            euler_angle.yaw_deg = 135;
×
1517
            break;
×
1518
        }
1519
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_90: {
×
1520
            euler_angle.pitch_deg = 90;
×
1521
            break;
×
1522
        }
1523
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_270: {
×
1524
            euler_angle.pitch_deg = 270;
×
1525
            break;
×
1526
        }
1527
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_180_YAW_90: {
×
1528
            euler_angle.pitch_deg = 180;
×
1529
            euler_angle.yaw_deg = 90;
×
1530
            break;
×
1531
        }
1532
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_180_YAW_270: {
×
1533
            euler_angle.pitch_deg = 180;
×
1534
            euler_angle.yaw_deg = 270;
×
1535
            break;
×
1536
        }
1537
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_90: {
×
1538
            euler_angle.roll_deg = 90;
×
1539
            euler_angle.pitch_deg = 90;
×
1540
            break;
×
1541
        }
1542
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_PITCH_90: {
×
1543
            euler_angle.roll_deg = 180;
×
1544
            euler_angle.pitch_deg = 90;
×
1545
            break;
×
1546
        }
1547
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_PITCH_90: {
×
1548
            euler_angle.roll_deg = 270;
×
1549
            euler_angle.pitch_deg = 90;
×
1550
            break;
×
1551
        }
1552
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_180: {
×
1553
            euler_angle.roll_deg = 90;
×
1554
            euler_angle.pitch_deg = 180;
×
1555
            break;
×
1556
        }
1557
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_PITCH_180: {
×
1558
            euler_angle.roll_deg = 270;
×
1559
            euler_angle.pitch_deg = 180;
×
1560
            break;
×
1561
        }
1562
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_270: {
×
1563
            euler_angle.roll_deg = 90;
×
1564
            euler_angle.pitch_deg = 270;
×
1565
            break;
×
1566
        }
1567
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_PITCH_270: {
×
1568
            euler_angle.roll_deg = 180;
×
1569
            euler_angle.pitch_deg = 270;
×
1570
            break;
×
1571
        }
1572
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_PITCH_270: {
×
1573
            euler_angle.roll_deg = 270;
×
1574
            euler_angle.pitch_deg = 270;
×
1575
            break;
×
1576
        }
1577
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90: {
×
1578
            euler_angle.roll_deg = 90;
×
1579
            euler_angle.pitch_deg = 180;
×
1580
            euler_angle.yaw_deg = 90;
×
1581
            break;
×
1582
        }
1583
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_270: {
×
1584
            euler_angle.roll_deg = 90;
×
1585
            euler_angle.yaw_deg = 270;
×
1586
            break;
×
1587
        }
1588
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_68_YAW_293: {
×
1589
            euler_angle.roll_deg = 90;
×
1590
            euler_angle.pitch_deg = 68;
×
1591
            euler_angle.yaw_deg = 293;
×
1592
            break;
×
1593
        }
1594
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_315: {
×
1595
            euler_angle.pitch_deg = 315;
×
1596
            break;
×
1597
        }
1598
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_315: {
×
1599
            euler_angle.roll_deg = 90;
×
1600
            euler_angle.pitch_deg = 315;
×
1601
            break;
×
1602
        }
1603
        default: {
×
1604
            euler_angle.roll_deg = 0;
×
1605
            euler_angle.pitch_deg = 0;
×
1606
            euler_angle.yaw_deg = 0;
×
1607
        }
1608
    }
1609

1610
    return euler_angle;
×
1611
}
1612

1613
void TelemetryImpl::process_scaled_pressure(const mavlink_message_t& message)
×
1614
{
1615
    mavlink_scaled_pressure_t scaled_pressure_msg;
×
1616
    mavlink_msg_scaled_pressure_decode(&message, &scaled_pressure_msg);
×
1617

1618
    Telemetry::ScaledPressure scaled_pressure_struct{};
×
1619

1620
    scaled_pressure_struct.timestamp_us =
×
1621
        static_cast<uint64_t>(scaled_pressure_msg.time_boot_ms) * 1000;
×
1622
    scaled_pressure_struct.absolute_pressure_hpa = scaled_pressure_msg.press_abs;
×
1623
    scaled_pressure_struct.differential_pressure_hpa = scaled_pressure_msg.press_diff;
×
1624
    scaled_pressure_struct.temperature_deg =
×
1625
        static_cast<float>(scaled_pressure_msg.temperature) * 1e-2f;
×
1626
    scaled_pressure_struct.differential_pressure_temperature_deg =
×
1627
        static_cast<float>(scaled_pressure_msg.temperature_press_diff) * 1e-2f;
×
1628

1629
    set_scaled_pressure(scaled_pressure_struct);
×
1630

1631
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1632
    _scaled_pressure_subscriptions.queue(
×
1633
        scaled_pressure(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1634
}
×
1635

1636
Telemetry::LandedState
1637
TelemetryImpl::to_landed_state(mavlink_extended_sys_state_t extended_sys_state)
×
1638
{
1639
    switch (extended_sys_state.landed_state) {
×
1640
        case MAV_LANDED_STATE_IN_AIR:
×
1641
            return Telemetry::LandedState::InAir;
×
1642
        case MAV_LANDED_STATE_TAKEOFF:
×
1643
            return Telemetry::LandedState::TakingOff;
×
1644
        case MAV_LANDED_STATE_LANDING:
×
1645
            return Telemetry::LandedState::Landing;
×
1646
        case MAV_LANDED_STATE_ON_GROUND:
×
1647
            return Telemetry::LandedState::OnGround;
×
1648
        default:
×
1649
            return Telemetry::LandedState::Unknown;
×
1650
    }
1651
}
1652

1653
Telemetry::VtolState TelemetryImpl::to_vtol_state(mavlink_extended_sys_state_t extended_sys_state)
×
1654
{
1655
    switch (extended_sys_state.vtol_state) {
×
1656
        case MAV_VTOL_STATE::MAV_VTOL_STATE_TRANSITION_TO_FW:
×
1657
            return Telemetry::VtolState::TransitionToFw;
×
1658
        case MAV_VTOL_STATE_TRANSITION_TO_MC:
×
1659
            return Telemetry::VtolState::TransitionToMc;
×
1660
        case MAV_VTOL_STATE_MC:
×
1661
            return Telemetry::VtolState::Mc;
×
1662
        case MAV_VTOL_STATE_FW:
×
1663
            return Telemetry::VtolState::Fw;
×
1664
        default:
×
1665
            return Telemetry::VtolState::Undefined;
×
1666
    }
1667
}
1668

UNCOV
1669
Telemetry::FlightMode TelemetryImpl::telemetry_flight_mode_from_flight_mode(FlightMode flight_mode)
×
1670
{
UNCOV
1671
    switch (flight_mode) {
×
1672
        case FlightMode::Ready:
×
1673
            return Telemetry::FlightMode::Ready;
×
1674
        case FlightMode::Takeoff:
×
1675
            return Telemetry::FlightMode::Takeoff;
×
1676
        case FlightMode::Hold:
×
1677
            return Telemetry::FlightMode::Hold;
×
1678
        case FlightMode::Mission:
×
1679
            return Telemetry::FlightMode::Mission;
×
1680
        case FlightMode::ReturnToLaunch:
×
1681
            return Telemetry::FlightMode::ReturnToLaunch;
×
1682
        case FlightMode::Land:
×
1683
            return Telemetry::FlightMode::Land;
×
1684
        case FlightMode::Offboard:
×
1685
            return Telemetry::FlightMode::Offboard;
×
1686
        case FlightMode::FollowMe:
×
1687
            return Telemetry::FlightMode::FollowMe;
×
1688
        case FlightMode::Manual:
×
1689
            return Telemetry::FlightMode::Manual;
×
1690
        case FlightMode::Posctl:
×
1691
            return Telemetry::FlightMode::Posctl;
×
1692
        case FlightMode::Altctl:
×
1693
            return Telemetry::FlightMode::Altctl;
×
1694
        case FlightMode::Rattitude:
×
1695
            return Telemetry::FlightMode::Rattitude;
×
1696
        case FlightMode::Acro:
×
1697
            return Telemetry::FlightMode::Acro;
×
1698
        case FlightMode::Stabilized:
×
1699
            return Telemetry::FlightMode::Stabilized;
×
UNCOV
1700
        default:
×
UNCOV
1701
            return Telemetry::FlightMode::Unknown;
×
1702
    }
1703
}
1704

1705
Telemetry::PositionVelocityNed TelemetryImpl::position_velocity_ned() const
×
1706
{
1707
    std::lock_guard<std::mutex> lock(_position_velocity_ned_mutex);
×
1708
    return _position_velocity_ned;
×
1709
}
×
1710

1711
void TelemetryImpl::set_position_velocity_ned(Telemetry::PositionVelocityNed position_velocity_ned)
×
1712
{
1713
    std::lock_guard<std::mutex> lock(_position_velocity_ned_mutex);
×
1714
    _position_velocity_ned = position_velocity_ned;
×
1715
}
×
1716

1717
Telemetry::Position TelemetryImpl::position() const
×
1718
{
1719
    std::lock_guard<std::mutex> lock(_position_mutex);
×
1720
    return _position;
×
1721
}
×
1722

1723
void TelemetryImpl::set_position(Telemetry::Position position)
×
1724
{
1725
    std::lock_guard<std::mutex> lock(_position_mutex);
×
1726
    _position = position;
×
1727
}
×
1728

1729
Telemetry::Heading TelemetryImpl::heading() const
×
1730
{
1731
    std::lock_guard<std::mutex> lock(_heading_mutex);
×
1732
    return _heading;
×
1733
}
×
1734

1735
void TelemetryImpl::set_heading(Telemetry::Heading heading)
×
1736
{
1737
    std::lock_guard<std::mutex> lock(_heading_mutex);
×
1738
    _heading = heading;
×
1739
}
×
1740

1741
Telemetry::Altitude TelemetryImpl::altitude() const
×
1742
{
1743
    std::lock_guard<std::mutex> lock(_altitude_mutex);
×
1744
    return _altitude;
×
1745
}
×
1746

1747
void TelemetryImpl::set_altitude(Telemetry::Altitude altitude)
×
1748
{
1749
    std::lock_guard<std::mutex> lock(_altitude_mutex);
×
1750
    _altitude = altitude;
×
1751
}
×
1752

1753
Telemetry::Wind TelemetryImpl::wind() const
×
1754
{
1755
    std::lock_guard<std::mutex> lock(_wind_mutex);
×
1756
    return _wind;
×
1757
}
×
1758

1759
void TelemetryImpl::set_wind(Telemetry::Wind wind)
×
1760
{
1761
    std::lock_guard<std::mutex> lock(_wind_mutex);
×
1762
    _wind = wind;
×
1763
}
×
1764

1765
Telemetry::Position TelemetryImpl::home() const
×
1766
{
1767
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
1768
    return _home_position;
×
1769
}
×
1770

1771
void TelemetryImpl::set_home_position(Telemetry::Position home_position)
×
1772
{
1773
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
1774
    _home_position = home_position;
×
1775
}
×
1776

UNCOV
1777
bool TelemetryImpl::armed() const
×
1778
{
UNCOV
1779
    return _armed;
×
1780
}
1781

1782
bool TelemetryImpl::in_air() const
×
1783
{
1784
    return _in_air;
×
1785
}
1786

1787
void TelemetryImpl::set_in_air(bool in_air_new)
×
1788
{
1789
    _in_air = in_air_new;
×
1790
}
×
1791

1792
void TelemetryImpl::set_status_text(Telemetry::StatusText status_text)
3✔
1793
{
1794
    std::lock_guard<std::mutex> lock(_status_text_mutex);
3✔
1795
    _status_text = status_text;
3✔
1796
}
3✔
1797

1798
Telemetry::StatusText TelemetryImpl::status_text() const
3✔
1799
{
1800
    std::lock_guard<std::mutex> lock(_status_text_mutex);
3✔
1801
    return _status_text;
3✔
1802
}
3✔
1803

UNCOV
1804
void TelemetryImpl::set_armed(bool armed_new)
×
1805
{
UNCOV
1806
    _armed = armed_new;
×
UNCOV
1807
}
×
1808

1809
Telemetry::Quaternion TelemetryImpl::attitude_quaternion() const
×
1810
{
1811
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1812
    return _attitude_quaternion;
×
1813
}
×
1814

1815
Telemetry::AngularVelocityBody TelemetryImpl::attitude_angular_velocity_body() const
×
1816
{
1817
    std::lock_guard<std::mutex> lock(_attitude_angular_velocity_body_mutex);
×
1818
    return _attitude_angular_velocity_body;
×
1819
}
×
1820

1821
Telemetry::GroundTruth TelemetryImpl::ground_truth() const
×
1822
{
1823
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
1824
    return _ground_truth;
×
1825
}
×
1826

1827
Telemetry::FixedwingMetrics TelemetryImpl::fixedwing_metrics() const
×
1828
{
1829
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
1830
    return _fixedwing_metrics;
×
1831
}
×
1832

1833
Telemetry::EulerAngle TelemetryImpl::attitude_euler() const
×
1834
{
1835
    std::lock_guard<std::mutex> lock(_attitude_euler_mutex);
×
1836
    return _attitude_euler;
×
1837
}
×
1838

1839
void TelemetryImpl::set_attitude_quaternion(Telemetry::Quaternion quaternion)
×
1840
{
1841
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1842
    _attitude_quaternion = quaternion;
×
1843
}
×
1844

1845
void TelemetryImpl::set_attitude_euler(Telemetry::EulerAngle euler)
×
1846
{
1847
    std::lock_guard<std::mutex> lock(_attitude_euler_mutex);
×
1848
    _attitude_euler = euler;
×
1849
}
×
1850

1851
void TelemetryImpl::set_attitude_angular_velocity_body(
×
1852
    Telemetry::AngularVelocityBody angular_velocity_body)
1853
{
1854
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1855
    _attitude_angular_velocity_body = angular_velocity_body;
×
1856
}
×
1857

1858
void TelemetryImpl::set_ground_truth(Telemetry::GroundTruth ground_truth)
×
1859
{
1860
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
1861
    _ground_truth = ground_truth;
×
1862
}
×
1863

1864
void TelemetryImpl::set_fixedwing_metrics(Telemetry::FixedwingMetrics fixedwing_metrics)
×
1865
{
1866
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
1867
    _fixedwing_metrics = fixedwing_metrics;
×
1868
}
×
1869

1870
Telemetry::VelocityNed TelemetryImpl::velocity_ned() const
×
1871
{
1872
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
1873
    return _velocity_ned;
×
1874
}
×
1875

1876
void TelemetryImpl::set_velocity_ned(Telemetry::VelocityNed velocity_ned)
×
1877
{
1878
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
1879
    _velocity_ned = velocity_ned;
×
1880
}
×
1881

1882
Telemetry::Imu TelemetryImpl::imu() const
×
1883
{
1884
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
1885
    return _imu_reading_ned;
×
1886
}
×
1887

1888
void TelemetryImpl::set_imu_reading_ned(Telemetry::Imu imu_reading_ned)
×
1889
{
1890
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
1891
    _imu_reading_ned = imu_reading_ned;
×
1892
}
×
1893

1894
Telemetry::Imu TelemetryImpl::scaled_imu() const
×
1895
{
1896
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
1897
    return _scaled_imu;
×
1898
}
×
1899

1900
void TelemetryImpl::set_scaled_imu(Telemetry::Imu scaled_imu)
×
1901
{
1902
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
1903
    _scaled_imu = scaled_imu;
×
1904
}
×
1905

1906
Telemetry::Imu TelemetryImpl::raw_imu() const
×
1907
{
1908
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
1909
    return _raw_imu;
×
1910
}
×
1911

1912
void TelemetryImpl::set_raw_imu(Telemetry::Imu raw_imu)
×
1913
{
1914
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
1915
    _raw_imu = raw_imu;
×
1916
}
×
1917

1918
Telemetry::GpsInfo TelemetryImpl::gps_info() const
×
1919
{
1920
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
×
1921
    return _gps_info;
×
1922
}
×
1923

1924
void TelemetryImpl::set_gps_info(Telemetry::GpsInfo gps_info)
×
1925
{
1926
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
×
1927
    _gps_info = gps_info;
×
1928
}
×
1929

1930
Telemetry::RawGps TelemetryImpl::raw_gps() const
×
1931
{
1932
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
×
1933
    return _raw_gps;
×
1934
}
×
1935

1936
void TelemetryImpl::set_raw_gps(Telemetry::RawGps raw_gps)
×
1937
{
1938
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
×
1939
    _raw_gps = raw_gps;
×
1940
}
×
1941

1942
Telemetry::Battery TelemetryImpl::battery() const
×
1943
{
1944
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
1945
    return _battery;
×
1946
}
×
1947

1948
void TelemetryImpl::set_battery(Telemetry::Battery battery)
×
1949
{
1950
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
1951
    _battery = battery;
×
1952
}
×
1953

1954
Telemetry::FlightMode TelemetryImpl::flight_mode() const
×
1955
{
1956
    return telemetry_flight_mode_from_flight_mode(_system_impl->get_flight_mode());
×
1957
}
1958

UNCOV
1959
Telemetry::Health TelemetryImpl::health() const
×
1960
{
UNCOV
1961
    std::lock_guard<std::mutex> lock(_health_mutex);
×
UNCOV
1962
    return _health;
×
UNCOV
1963
}
×
1964

UNCOV
1965
bool TelemetryImpl::health_all_ok() const
×
1966
{
UNCOV
1967
    std::lock_guard<std::mutex> lock(_health_mutex);
×
UNCOV
1968
    if (_health.is_gyrometer_calibration_ok && _health.is_accelerometer_calibration_ok &&
×
1969
        _health.is_magnetometer_calibration_ok && _health.is_local_position_ok &&
×
1970
        _health.is_global_position_ok && _health.is_home_position_ok) {
×
1971
        return true;
×
1972
    } else {
UNCOV
1973
        return false;
×
1974
    }
UNCOV
1975
}
×
1976

1977
Telemetry::RcStatus TelemetryImpl::rc_status() const
×
1978
{
1979
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
1980
    return _rc_status;
×
1981
}
×
1982

1983
uint64_t TelemetryImpl::unix_epoch_time() const
×
1984
{
1985
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
1986
    return _unix_epoch_time_us;
×
1987
}
×
1988

1989
Telemetry::ActuatorControlTarget TelemetryImpl::actuator_control_target() const
×
1990
{
1991
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
1992
    return _actuator_control_target;
×
1993
}
×
1994

1995
Telemetry::ActuatorOutputStatus TelemetryImpl::actuator_output_status() const
×
1996
{
1997
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
1998
    return _actuator_output_status;
×
1999
}
×
2000

2001
Telemetry::Odometry TelemetryImpl::odometry() const
×
2002
{
2003
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
2004
    return _odometry;
×
2005
}
×
2006

2007
Telemetry::DistanceSensor TelemetryImpl::distance_sensor() const
×
2008
{
2009
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
2010
    return _distance_sensor;
×
2011
}
×
2012

2013
Telemetry::ScaledPressure TelemetryImpl::scaled_pressure() const
×
2014
{
2015
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
2016
    return _scaled_pressure;
×
2017
}
×
2018

2019
void TelemetryImpl::set_health_local_position(bool ok)
×
2020
{
2021
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2022
    _health.is_local_position_ok = ok;
×
2023
}
×
2024

2025
void TelemetryImpl::set_health_global_position(bool ok)
×
2026
{
2027
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2028
    _health.is_global_position_ok = ok;
×
2029
}
×
2030

2031
void TelemetryImpl::set_health_home_position(bool ok)
×
2032
{
2033
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2034
    _health.is_home_position_ok = ok;
×
2035
}
×
2036

2037
void TelemetryImpl::set_health_gyrometer_calibration(bool ok)
×
2038
{
2039
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2040
    _health.is_gyrometer_calibration_ok = ok;
×
2041
}
×
2042

2043
void TelemetryImpl::set_health_accelerometer_calibration(bool ok)
×
2044
{
2045
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2046
    _health.is_accelerometer_calibration_ok = ok;
×
2047
}
×
2048

2049
void TelemetryImpl::set_health_magnetometer_calibration(bool ok)
×
2050
{
2051
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2052
    _health.is_magnetometer_calibration_ok = ok;
×
2053
}
×
2054

2055
void TelemetryImpl::set_health_armable(bool ok)
×
2056
{
2057
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2058
    _health.is_armable = ok;
×
2059
}
×
2060

2061
Telemetry::VtolState TelemetryImpl::vtol_state() const
×
2062
{
2063
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
2064
    return _vtol_state;
×
2065
}
×
2066

2067
void TelemetryImpl::set_vtol_state(Telemetry::VtolState vtol_state)
×
2068
{
2069
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
2070
    _vtol_state = vtol_state;
×
2071
}
×
2072

2073
Telemetry::LandedState TelemetryImpl::landed_state() const
×
2074
{
2075
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2076
    return _landed_state;
×
2077
}
×
2078

2079
void TelemetryImpl::set_landed_state(Telemetry::LandedState landed_state)
×
2080
{
2081
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2082
    _landed_state = landed_state;
×
2083
}
×
2084

2085
void TelemetryImpl::set_rc_status(
×
2086
    std::optional<bool> maybe_available, std::optional<float> maybe_signal_strength_percent)
2087
{
2088
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
2089

2090
    if (maybe_available) {
×
2091
        _rc_status.is_available = maybe_available.value();
×
2092
        if (maybe_available.value()) {
×
2093
            _rc_status.was_available_once = true;
×
2094
        }
2095
    }
2096

2097
    if (maybe_signal_strength_percent) {
×
2098
        _rc_status.signal_strength_percent = maybe_signal_strength_percent.value();
×
2099
    }
2100
}
×
2101

2102
void TelemetryImpl::set_unix_epoch_time_us(uint64_t time_us)
×
2103
{
2104
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
2105
    _unix_epoch_time_us = time_us;
×
2106
}
×
2107

2108
void TelemetryImpl::set_actuator_control_target(uint8_t group, const std::vector<float>& controls)
×
2109
{
2110
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
2111
    _actuator_control_target.group = group;
×
2112
    _actuator_control_target.controls = controls;
×
2113
}
×
2114

2115
void TelemetryImpl::set_actuator_output_status(uint32_t active, const std::vector<float>& actuators)
×
2116
{
2117
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
2118
    _actuator_output_status.active = active;
×
2119
    _actuator_output_status.actuator = actuators;
×
2120
}
×
2121

2122
void TelemetryImpl::set_odometry(Telemetry::Odometry& odometry)
×
2123
{
2124
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
2125
    _odometry = odometry;
×
2126
}
×
2127

2128
void TelemetryImpl::set_distance_sensor(Telemetry::DistanceSensor& distance_sensor)
×
2129
{
2130
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
2131
    _distance_sensor = distance_sensor;
×
2132
}
×
2133

2134
void TelemetryImpl::set_scaled_pressure(Telemetry::ScaledPressure& scaled_pressure)
×
2135
{
2136
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
2137
    _scaled_pressure = scaled_pressure;
×
2138
}
×
2139

2140
Telemetry::PositionVelocityNedHandle TelemetryImpl::subscribe_position_velocity_ned(
×
2141
    const Telemetry::PositionVelocityNedCallback& callback)
2142
{
2143
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2144
    return _position_velocity_ned_subscriptions.subscribe(callback);
×
2145
}
×
2146

2147
void TelemetryImpl::unsubscribe_position_velocity_ned(Telemetry::PositionVelocityNedHandle handle)
×
2148
{
2149
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2150
    _position_velocity_ned_subscriptions.unsubscribe(handle);
×
2151
}
×
2152

2153
Telemetry::PositionHandle
2154
TelemetryImpl::subscribe_position(const Telemetry::PositionCallback& callback)
×
2155
{
2156
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2157
    return _position_subscriptions.subscribe(callback);
×
2158
}
×
2159

2160
void TelemetryImpl::unsubscribe_position(Telemetry::PositionHandle handle)
×
2161
{
2162
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2163
    _position_subscriptions.unsubscribe(handle);
×
2164
}
×
2165

2166
Telemetry::HomeHandle TelemetryImpl::subscribe_home(const Telemetry::PositionCallback& callback)
×
2167
{
2168
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2169
    return _home_position_subscriptions.subscribe(callback);
×
2170
}
×
2171

2172
void TelemetryImpl::unsubscribe_home(Telemetry::HomeHandle handle)
×
2173
{
2174
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2175
    _home_position_subscriptions.unsubscribe(handle);
×
2176
}
×
2177

2178
Telemetry::InAirHandle TelemetryImpl::subscribe_in_air(const Telemetry::InAirCallback& callback)
×
2179
{
2180
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2181
    return _in_air_subscriptions.subscribe(callback);
×
2182
}
×
2183

2184
void TelemetryImpl::unsubscribe_in_air(Telemetry::InAirHandle handle)
×
2185
{
2186
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2187
    return _in_air_subscriptions.unsubscribe(handle);
×
2188
}
×
2189

2190
Telemetry::StatusTextHandle
2191
TelemetryImpl::subscribe_status_text(const Telemetry::StatusTextCallback& callback)
2✔
2192
{
2193
    std::lock_guard<std::mutex> lock(_subscription_mutex);
2✔
2194
    return _status_text_subscriptions.subscribe(callback);
2✔
2195
}
2✔
2196

2197
void TelemetryImpl::unsubscribe_status_text(Handle<Telemetry::StatusText> handle)
1✔
2198
{
2199
    std::lock_guard<std::mutex> lock(_subscription_mutex);
1✔
2200
    _status_text_subscriptions.unsubscribe(handle);
1✔
2201
}
1✔
2202

2203
Telemetry::ArmedHandle TelemetryImpl::subscribe_armed(const Telemetry::ArmedCallback& callback)
×
2204
{
2205
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2206
    return _armed_subscriptions.subscribe(callback);
×
2207
}
×
2208

2209
void TelemetryImpl::unsubscribe_armed(Telemetry::ArmedHandle handle)
×
2210
{
2211
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2212
    _armed_subscriptions.unsubscribe(handle);
×
2213
}
×
2214

2215
Telemetry::AttitudeQuaternionHandle
2216
TelemetryImpl::subscribe_attitude_quaternion(const Telemetry::AttitudeQuaternionCallback& callback)
×
2217
{
2218
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2219
    return _attitude_quaternion_angle_subscriptions.subscribe(callback);
×
2220
}
×
2221

2222
void TelemetryImpl::unsubscribe_attitude_quaternion(Telemetry::AttitudeQuaternionHandle handle)
×
2223
{
2224
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2225
    _attitude_quaternion_angle_subscriptions.unsubscribe(handle);
×
2226
}
×
2227

2228
Telemetry::AttitudeEulerHandle
2229
TelemetryImpl::subscribe_attitude_euler(const Telemetry::AttitudeEulerCallback& callback)
×
2230
{
2231
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2232
    return _attitude_euler_angle_subscriptions.subscribe(callback);
×
2233
}
×
2234

2235
void TelemetryImpl::unsubscribe_attitude_euler(Telemetry::AttitudeEulerHandle handle)
×
2236
{
2237
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2238
    _attitude_euler_angle_subscriptions.unsubscribe(handle);
×
2239
}
×
2240

2241
Telemetry::AttitudeAngularVelocityBodyHandle
2242
TelemetryImpl::subscribe_attitude_angular_velocity_body(
×
2243
    const Telemetry::AttitudeAngularVelocityBodyCallback& callback)
2244
{
2245
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2246
    return _attitude_angular_velocity_body_subscriptions.subscribe(callback);
×
2247
}
×
2248

2249
void TelemetryImpl::unsubscribe_attitude_angular_velocity_body(
×
2250
    Telemetry::AttitudeAngularVelocityBodyHandle handle)
2251
{
2252
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2253
    _attitude_angular_velocity_body_subscriptions.unsubscribe(handle);
×
2254
}
×
2255

2256
Telemetry::FixedwingMetricsHandle
2257
TelemetryImpl::subscribe_fixedwing_metrics(const Telemetry::FixedwingMetricsCallback& callback)
×
2258
{
2259
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2260
    return _fixedwing_metrics_subscriptions.subscribe(callback);
×
2261
}
×
2262

2263
void TelemetryImpl::unsubscribe_fixedwing_metrics(Telemetry::FixedwingMetricsHandle handle)
×
2264
{
2265
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2266
    _fixedwing_metrics_subscriptions.unsubscribe(handle);
×
2267
}
×
2268

2269
Telemetry::GroundTruthHandle
2270
TelemetryImpl::subscribe_ground_truth(const Telemetry::GroundTruthCallback& callback)
×
2271
{
2272
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2273
    return _ground_truth_subscriptions.subscribe(callback);
×
2274
}
×
2275

2276
void TelemetryImpl::unsubscribe_ground_truth(Telemetry::GroundTruthHandle handle)
×
2277
{
2278
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2279
    _ground_truth_subscriptions.unsubscribe(handle);
×
2280
}
×
2281

2282
Telemetry::VelocityNedHandle
2283
TelemetryImpl::subscribe_velocity_ned(const Telemetry::VelocityNedCallback& callback)
×
2284
{
2285
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2286
    return _velocity_ned_subscriptions.subscribe(callback);
×
2287
}
×
2288

2289
void TelemetryImpl::unsubscribe_velocity_ned(Telemetry::VelocityNedHandle handle)
×
2290
{
2291
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2292
    _velocity_ned_subscriptions.unsubscribe(handle);
×
2293
}
×
2294

2295
Telemetry::ImuHandle TelemetryImpl::subscribe_imu(const Telemetry::ImuCallback& callback)
×
2296
{
2297
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2298
    return _imu_reading_ned_subscriptions.subscribe(callback);
×
2299
}
×
2300

2301
void TelemetryImpl::unsubscribe_imu(Telemetry::ImuHandle handle)
×
2302
{
2303
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2304
    return _imu_reading_ned_subscriptions.unsubscribe(handle);
×
2305
}
×
2306

2307
Telemetry::ScaledImuHandle
2308
TelemetryImpl::subscribe_scaled_imu(const Telemetry::ScaledImuCallback& callback)
×
2309
{
2310
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2311
    return _scaled_imu_subscriptions.subscribe(callback);
×
2312
}
×
2313

2314
void TelemetryImpl::unsubscribe_scaled_imu(Telemetry::ScaledImuHandle handle)
×
2315
{
2316
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2317
    _scaled_imu_subscriptions.unsubscribe(handle);
×
2318
}
×
2319

2320
Telemetry::RawImuHandle TelemetryImpl::subscribe_raw_imu(const Telemetry::RawImuCallback& callback)
×
2321
{
2322
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2323
    return _raw_imu_subscriptions.subscribe(callback);
×
2324
}
×
2325

2326
void TelemetryImpl::unsubscribe_raw_imu(Telemetry::RawImuHandle handle)
×
2327
{
2328
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2329
    _raw_imu_subscriptions.unsubscribe(handle);
×
2330
}
×
2331

2332
Telemetry::GpsInfoHandle
2333
TelemetryImpl::subscribe_gps_info(const Telemetry::GpsInfoCallback& callback)
×
2334
{
2335
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2336
    return _gps_info_subscriptions.subscribe(callback);
×
2337
}
×
2338

2339
void TelemetryImpl::unsubscribe_gps_info(Telemetry::GpsInfoHandle handle)
×
2340
{
2341
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2342
    _gps_info_subscriptions.unsubscribe(handle);
×
2343
}
×
2344

2345
Telemetry::RawGpsHandle TelemetryImpl::subscribe_raw_gps(const Telemetry::RawGpsCallback& callback)
×
2346
{
2347
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2348
    return _raw_gps_subscriptions.subscribe(callback);
×
2349
}
×
2350

2351
void TelemetryImpl::unsubscribe_raw_gps(Telemetry::RawGpsHandle handle)
×
2352
{
2353
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2354
    _raw_gps_subscriptions.unsubscribe(handle);
×
2355
}
×
2356

2357
Telemetry::BatteryHandle
2358
TelemetryImpl::subscribe_battery(const Telemetry::BatteryCallback& callback)
×
2359
{
2360
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2361
    return _battery_subscriptions.subscribe(callback);
×
2362
}
×
2363

2364
void TelemetryImpl::unsubscribe_battery(Telemetry::BatteryHandle handle)
×
2365
{
2366
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2367
    _battery_subscriptions.unsubscribe(handle);
×
2368
}
×
2369

2370
Telemetry::FlightModeHandle
2371
TelemetryImpl::subscribe_flight_mode(const Telemetry::FlightModeCallback& callback)
×
2372
{
2373
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2374
    return _flight_mode_subscriptions.subscribe(callback);
×
2375
}
×
2376

2377
void TelemetryImpl::unsubscribe_flight_mode(Telemetry::FlightModeHandle handle)
×
2378
{
2379
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2380
    _flight_mode_subscriptions.unsubscribe(handle);
×
2381
}
×
2382

2383
Telemetry::HealthHandle TelemetryImpl::subscribe_health(const Telemetry::HealthCallback& callback)
×
2384
{
2385
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2386
    return _health_subscriptions.subscribe(callback);
×
2387
}
×
2388

2389
void TelemetryImpl::unsubscribe_health(Telemetry::HealthHandle handle)
×
2390
{
2391
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2392
    _health_subscriptions.unsubscribe(handle);
×
2393
}
×
2394

2395
Telemetry::HealthAllOkHandle
2396
TelemetryImpl::subscribe_health_all_ok(const Telemetry::HealthAllOkCallback& callback)
×
2397
{
2398
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2399
    return _health_all_ok_subscriptions.subscribe(callback);
×
2400
}
×
2401

2402
void TelemetryImpl::unsubscribe_health_all_ok(Telemetry::HealthAllOkHandle handle)
×
2403
{
2404
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2405
    _health_all_ok_subscriptions.unsubscribe(handle);
×
2406
}
×
2407

2408
Telemetry::VtolStateHandle
2409
TelemetryImpl::subscribe_vtol_state(const Telemetry::VtolStateCallback& callback)
×
2410
{
2411
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2412
    return _vtol_state_subscriptions.subscribe(callback);
×
2413
}
×
2414

2415
void TelemetryImpl::unsubscribe_vtol_state(Telemetry::VtolStateHandle handle)
×
2416
{
2417
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2418
    _vtol_state_subscriptions.unsubscribe(handle);
×
2419
}
×
2420

2421
Telemetry::LandedStateHandle
2422
TelemetryImpl::subscribe_landed_state(const Telemetry::LandedStateCallback& callback)
×
2423
{
2424
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2425
    return _landed_state_subscriptions.subscribe(callback);
×
2426
}
×
2427

2428
void TelemetryImpl::unsubscribe_landed_state(Telemetry::LandedStateHandle handle)
×
2429
{
2430
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2431
    _landed_state_subscriptions.unsubscribe(handle);
×
2432
}
×
2433

2434
Telemetry::RcStatusHandle
2435
TelemetryImpl::subscribe_rc_status(const Telemetry::RcStatusCallback& callback)
×
2436
{
2437
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2438
    return _rc_status_subscriptions.subscribe(callback);
×
2439
}
×
2440

2441
void TelemetryImpl::unsubscribe_rc_status(Telemetry::RcStatusHandle handle)
×
2442
{
2443
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2444
    _rc_status_subscriptions.unsubscribe(handle);
×
2445
}
×
2446

2447
Telemetry::UnixEpochTimeHandle
2448
TelemetryImpl::subscribe_unix_epoch_time(const Telemetry::UnixEpochTimeCallback& callback)
×
2449
{
2450
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2451
    return _unix_epoch_time_subscriptions.subscribe(callback);
×
2452
}
×
2453

2454
void TelemetryImpl::unsubscribe_unix_epoch_time(Telemetry::UnixEpochTimeHandle handle)
×
2455
{
2456
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2457
    _unix_epoch_time_subscriptions.unsubscribe(handle);
×
2458
}
×
2459

2460
Telemetry::ActuatorControlTargetHandle TelemetryImpl::subscribe_actuator_control_target(
×
2461
    const Telemetry::ActuatorControlTargetCallback& callback)
2462
{
2463
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2464
    return _actuator_control_target_subscriptions.subscribe(callback);
×
2465
}
×
2466

2467
void TelemetryImpl::unsubscribe_actuator_control_target(
×
2468
    Telemetry::ActuatorControlTargetHandle handle)
2469
{
2470
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2471
    _actuator_control_target_subscriptions.unsubscribe(handle);
×
2472
}
×
2473

2474
Telemetry::ActuatorOutputStatusHandle TelemetryImpl::subscribe_actuator_output_status(
×
2475
    const Telemetry::ActuatorOutputStatusCallback& callback)
2476
{
2477
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2478
    return _actuator_output_status_subscriptions.subscribe(callback);
×
2479
}
×
2480

2481
void TelemetryImpl::unsubscribe_actuator_output_status(Telemetry::ActuatorOutputStatusHandle handle)
×
2482
{
2483
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2484
    _actuator_output_status_subscriptions.unsubscribe(handle);
×
2485
}
×
2486

2487
Telemetry::OdometryHandle
2488
TelemetryImpl::subscribe_odometry(const Telemetry::OdometryCallback& callback)
×
2489
{
2490
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2491
    return _odometry_subscriptions.subscribe(callback);
×
2492
}
×
2493

2494
void TelemetryImpl::unsubscribe_odometry(Telemetry::OdometryHandle handle)
×
2495
{
2496
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2497
    _odometry_subscriptions.unsubscribe(handle);
×
2498
}
×
2499

2500
Telemetry::DistanceSensorHandle
2501
TelemetryImpl::subscribe_distance_sensor(const Telemetry::DistanceSensorCallback& callback)
×
2502
{
2503
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2504
    return _distance_sensor_subscriptions.subscribe(callback);
×
2505
}
×
2506

2507
void TelemetryImpl::unsubscribe_distance_sensor(Telemetry::DistanceSensorHandle handle)
×
2508
{
2509
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2510
    _distance_sensor_subscriptions.unsubscribe(handle);
×
2511
}
×
2512

2513
Telemetry::ScaledPressureHandle
2514
TelemetryImpl::subscribe_scaled_pressure(const Telemetry::ScaledPressureCallback& callback)
×
2515
{
2516
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2517
    return _scaled_pressure_subscriptions.subscribe(callback);
×
2518
}
×
2519

2520
void TelemetryImpl::unsubscribe_scaled_pressure(Telemetry::ScaledPressureHandle handle)
×
2521
{
2522
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2523
    _scaled_pressure_subscriptions.unsubscribe(handle);
×
2524
}
×
2525

2526
Telemetry::HeadingHandle
2527
TelemetryImpl::subscribe_heading(const Telemetry::HeadingCallback& callback)
×
2528
{
2529
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2530
    return _heading_subscriptions.subscribe(callback);
×
2531
}
×
2532

2533
void TelemetryImpl::unsubscribe_heading(Telemetry::HeadingHandle handle)
×
2534
{
2535
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2536
    _heading_subscriptions.unsubscribe(handle);
×
2537
}
×
2538

2539
Telemetry::AltitudeHandle
2540
TelemetryImpl::subscribe_altitude(const Telemetry::AltitudeCallback& callback)
×
2541
{
2542
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2543
    return _altitude_subscriptions.subscribe(callback);
×
2544
}
×
2545

2546
void TelemetryImpl::unsubscribe_altitude(Telemetry::AltitudeHandle handle)
×
2547
{
2548
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2549
    _altitude_subscriptions.unsubscribe(handle);
×
2550
}
×
2551

2552
Telemetry::WindHandle TelemetryImpl::subscribe_wind(const Telemetry::WindCallback& callback)
×
2553
{
2554
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2555
    return _wind_subscriptions.subscribe(callback);
×
2556
}
×
2557

2558
void TelemetryImpl::unsubscribe_wind(Telemetry::WindHandle handle)
×
2559
{
2560
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2561
    _wind_subscriptions.unsubscribe(handle);
×
2562
}
×
2563

2564
void TelemetryImpl::get_gps_global_origin_async(
×
2565
    const Telemetry::GetGpsGlobalOriginCallback callback)
2566
{
2567
    _system_impl->mavlink_request_message().request(
×
2568
        MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN,
2569
        MAV_COMP_ID_AUTOPILOT1,
2570
        [this, callback](MavlinkCommandSender::Result result, const mavlink_message_t& message) {
×
2571
            if (result == MavlinkCommandSender::Result::Success) {
×
2572
                mavlink_gps_global_origin_t mavlink_gps_global_origin;
×
2573
                mavlink_msg_gps_global_origin_decode(&message, &mavlink_gps_global_origin);
×
2574

2575
                Telemetry::GpsGlobalOrigin gps_global_origin;
×
2576
                gps_global_origin.latitude_deg = mavlink_gps_global_origin.latitude * 1e-7;
×
2577
                gps_global_origin.longitude_deg = mavlink_gps_global_origin.longitude * 1e-7;
×
2578
                gps_global_origin.altitude_m = mavlink_gps_global_origin.altitude * 1e-3f;
×
2579
                _system_impl->call_user_callback([callback, gps_global_origin]() {
×
2580
                    callback(Telemetry::Result::Success, gps_global_origin);
2581
                });
2582

2583
            } else {
2584
                _system_impl->call_user_callback([callback, result]() {
×
2585
                    callback(telemetry_result_from_command_result(result), {});
2586
                });
2587
            }
2588
        });
×
2589
}
×
2590

2591
std::pair<Telemetry::Result, Telemetry::GpsGlobalOrigin> TelemetryImpl::get_gps_global_origin()
×
2592
{
2593
    auto prom = std::promise<std::pair<Telemetry::Result, Telemetry::GpsGlobalOrigin>>();
×
2594
    auto fut = prom.get_future();
×
2595

2596
    get_gps_global_origin_async(
×
2597
        [&prom](Telemetry::Result result, Telemetry::GpsGlobalOrigin gps_global_origin) {
×
2598
            prom.set_value(std::make_pair(result, gps_global_origin));
×
2599
        });
×
2600
    return fut.get();
×
2601
}
×
2602

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