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

mavlink / MAVSDK / 11767930807

10 Nov 2024 07:33PM UTC coverage: 38.608% (+0.7%) from 37.921%
11767930807

push

github

web-flow
Merge pull request #2394 from mavlink/pr-consolidate-ci

Consolidate CI

12030 of 31159 relevant lines covered (38.61%)

243.33 hits per line

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

7.17
/src/mavsdk/plugins/telemetry/telemetry_impl.cpp
1
#include "telemetry_impl.h"
2
#include "system.h"
3
#include "math_conversions.h"
4
#include "mavsdk_math.h"
5
#include "callback_list.tpp"
6

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

14
namespace mavsdk {
15

16
template class CallbackList<Telemetry::PositionVelocityNed>;
17
template class CallbackList<Telemetry::Position>;
18
template class CallbackList<bool>;
19
template class CallbackList<Telemetry::StatusText>;
20
template class CallbackList<Telemetry::Quaternion>;
21
template class CallbackList<Telemetry::AngularVelocityBody>;
22
template class CallbackList<Telemetry::GroundTruth>;
23
template class CallbackList<Telemetry::FixedwingMetrics>;
24
template class CallbackList<Telemetry::EulerAngle>;
25
template class CallbackList<Telemetry::VelocityNed>;
26
template class CallbackList<Telemetry::Imu>;
27
template class CallbackList<Telemetry::GpsInfo>;
28
template class CallbackList<Telemetry::RawGps>;
29
template class CallbackList<Telemetry::Battery>;
30
template class CallbackList<Telemetry::FlightMode>;
31
template class CallbackList<Telemetry::Health>;
32
template class CallbackList<Telemetry::VtolState>;
33
template class CallbackList<Telemetry::LandedState>;
34
template class CallbackList<Telemetry::RcStatus>;
35
template class CallbackList<uint64_t>;
36
template class CallbackList<Telemetry::ActuatorControlTarget>;
37
template class CallbackList<Telemetry::ActuatorOutputStatus>;
38
template class CallbackList<Telemetry::Odometry>;
39
template class CallbackList<Telemetry::DistanceSensor>;
40
template class CallbackList<Telemetry::ScaledPressure>;
41
template class CallbackList<Telemetry::Heading>;
42
template class CallbackList<Telemetry::Altitude>;
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,
108
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
1✔
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_statustext_handler(
1✔
177
        [this](const MavlinkStatustextHandler::Statustext& statustext) {
3✔
178
            receive_statustext(statustext);
3✔
179
        },
3✔
180
        this);
181
}
1✔
182

183
void TelemetryImpl::deinit()
1✔
184
{
185
    _system_impl->unregister_statustext_handler(this);
1✔
186
    _system_impl->unregister_all_mavlink_message_handlers(this);
1✔
187
}
1✔
188

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

196
void TelemetryImpl::disable()
1✔
197
{
198
    _system_impl->remove_call_every(_homepos_cookie);
1✔
199
    {
200
        std::lock_guard<std::mutex> lock(_health_mutex);
1✔
201
        _health.is_home_position_ok = false;
1✔
202
    }
1✔
203
}
1✔
204

205
void TelemetryImpl::request_home_position_again()
1✔
206
{
207
    {
208
        std::lock_guard<std::mutex> lock(_health_mutex);
1✔
209
        if (_health.is_home_position_ok) {
1✔
210
            _system_impl->remove_call_every(_homepos_cookie);
×
211
            return;
×
212
        }
213

214
        _system_impl->mavlink_request_message().request(
1✔
215
            MAVLINK_MSG_ID_HOME_POSITION, MAV_COMP_ID_AUTOPILOT1, nullptr);
216
    }
1✔
217
}
218

219
Telemetry::Result TelemetryImpl::set_rate_position_velocity_ned(double rate_hz)
×
220
{
221
    return telemetry_result_from_command_result(
×
222
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_LOCAL_POSITION_NED, rate_hz));
×
223
}
224

225
Telemetry::Result TelemetryImpl::set_rate_position(double rate_hz)
×
226
{
227
    _position_rate_hz = rate_hz;
×
228
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
229

230
    return telemetry_result_from_command_result(
×
231
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, max_rate_hz));
×
232
}
233

234
Telemetry::Result TelemetryImpl::set_rate_home(double rate_hz)
×
235
{
236
    return telemetry_result_from_command_result(
×
237
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_HOME_POSITION, rate_hz));
×
238
}
239

240
Telemetry::Result TelemetryImpl::set_rate_in_air(double rate_hz)
×
241
{
242
    return set_rate_landed_state(rate_hz);
×
243
}
244

245
Telemetry::Result TelemetryImpl::set_rate_vtol_state(double rate_hz)
×
246
{
247
    return set_rate_landed_state(rate_hz);
×
248
}
249

250
Telemetry::Result TelemetryImpl::set_rate_landed_state(double rate_hz)
×
251
{
252
    return telemetry_result_from_command_result(
×
253
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_EXTENDED_SYS_STATE, rate_hz));
×
254
}
255

256
Telemetry::Result TelemetryImpl::set_rate_attitude_quaternion(double rate_hz)
×
257
{
258
    return telemetry_result_from_command_result(
×
259
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ATTITUDE_QUATERNION, rate_hz));
×
260
}
261

262
Telemetry::Result TelemetryImpl::set_rate_attitude_euler(double rate_hz)
×
263
{
264
    return telemetry_result_from_command_result(
×
265
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ATTITUDE, rate_hz));
×
266
}
267

268
Telemetry::Result TelemetryImpl::set_rate_velocity_ned(double rate_hz)
×
269
{
270
    _velocity_ned_rate_hz = rate_hz;
×
271
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
272

273
    return telemetry_result_from_command_result(
×
274
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, max_rate_hz));
×
275
}
276

277
Telemetry::Result TelemetryImpl::set_rate_imu(double rate_hz)
×
278
{
279
    return telemetry_result_from_command_result(
×
280
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_HIGHRES_IMU, rate_hz));
×
281
}
282

283
Telemetry::Result TelemetryImpl::set_rate_scaled_imu(double rate_hz)
×
284
{
285
    return telemetry_result_from_command_result(
×
286
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_SCALED_IMU, rate_hz));
×
287
}
288

289
Telemetry::Result TelemetryImpl::set_rate_raw_imu(double rate_hz)
×
290
{
291
    return telemetry_result_from_command_result(
×
292
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_RAW_IMU, rate_hz));
×
293
}
294

295
Telemetry::Result TelemetryImpl::set_rate_fixedwing_metrics(double rate_hz)
×
296
{
297
    return telemetry_result_from_command_result(
×
298
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_VFR_HUD, rate_hz));
×
299
}
300

301
Telemetry::Result TelemetryImpl::set_rate_ground_truth(double rate_hz)
×
302
{
303
    return telemetry_result_from_command_result(
×
304
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_HIL_STATE_QUATERNION, rate_hz));
×
305
}
306

307
Telemetry::Result TelemetryImpl::set_rate_gps_info(double rate_hz)
×
308
{
309
    return telemetry_result_from_command_result(
×
310
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_GPS_RAW_INT, rate_hz));
×
311
}
312

313
Telemetry::Result TelemetryImpl::set_rate_battery(double rate_hz)
×
314
{
315
    return telemetry_result_from_command_result(
×
316
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_BATTERY_STATUS, rate_hz));
×
317
}
318

319
Telemetry::Result TelemetryImpl::set_rate_rc_status(double rate_hz)
×
320
{
321
    UNUSED(rate_hz);
×
322
    LogWarn() << "System status is usually fixed at 1 Hz";
×
323
    return Telemetry::Result::Unsupported;
×
324
}
325

326
Telemetry::Result TelemetryImpl::set_rate_actuator_control_target(double rate_hz)
×
327
{
328
    return telemetry_result_from_command_result(
×
329
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, rate_hz));
×
330
}
331

332
Telemetry::Result TelemetryImpl::set_rate_actuator_output_status(double rate_hz)
×
333
{
334
    return telemetry_result_from_command_result(
×
335
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS, rate_hz));
×
336
}
337

338
Telemetry::Result TelemetryImpl::set_rate_odometry(double rate_hz)
×
339
{
340
    return telemetry_result_from_command_result(
×
341
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ODOMETRY, rate_hz));
×
342
}
343

344
Telemetry::Result TelemetryImpl::set_rate_distance_sensor(double rate_hz)
×
345
{
346
    return telemetry_result_from_command_result(
×
347
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_DISTANCE_SENSOR, rate_hz));
×
348
}
349

350
Telemetry::Result TelemetryImpl::set_rate_scaled_pressure(double rate_hz)
×
351
{
352
    return telemetry_result_from_command_result(
×
353
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_SCALED_PRESSURE, rate_hz));
×
354
}
355

356
Telemetry::Result TelemetryImpl::set_rate_unix_epoch_time(double rate_hz)
×
357
{
358
    return telemetry_result_from_command_result(
×
359
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_SYSTEM_TIME, rate_hz));
×
360
}
361

362
Telemetry::Result TelemetryImpl::set_rate_altitude(double rate_hz)
×
363
{
364
    return telemetry_result_from_command_result(
×
365
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ALTITUDE, rate_hz));
×
366
}
367

368
void TelemetryImpl::set_rate_position_velocity_ned_async(
×
369
    double rate_hz, Telemetry::ResultCallback callback)
370
{
371
    _system_impl->set_msg_rate_async(
×
372
        MAVLINK_MSG_ID_LOCAL_POSITION_NED,
373
        rate_hz,
374
        [callback](MavlinkCommandSender::Result command_result, float) {
×
375
            command_result_callback(command_result, callback);
×
376
        });
×
377
}
×
378

379
void TelemetryImpl::set_rate_position_async(double rate_hz, Telemetry::ResultCallback callback)
×
380
{
381
    _position_rate_hz = rate_hz;
×
382
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
383

384
    _system_impl->set_msg_rate_async(
×
385
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
386
        max_rate_hz,
387
        [callback](MavlinkCommandSender::Result command_result, float) {
×
388
            command_result_callback(command_result, callback);
×
389
        });
×
390
}
×
391

392
void TelemetryImpl::set_rate_home_async(double rate_hz, Telemetry::ResultCallback callback)
×
393
{
394
    _system_impl->set_msg_rate_async(
×
395
        MAVLINK_MSG_ID_HOME_POSITION,
396
        rate_hz,
397
        [callback](MavlinkCommandSender::Result command_result, float) {
×
398
            command_result_callback(command_result, callback);
×
399
        });
×
400
}
×
401

402
void TelemetryImpl::set_rate_in_air_async(double rate_hz, Telemetry::ResultCallback callback)
×
403
{
404
    set_rate_landed_state_async(rate_hz, callback);
×
405
}
×
406

407
void TelemetryImpl::set_rate_vtol_state_async(double rate_hz, Telemetry::ResultCallback callback)
×
408
{
409
    set_rate_landed_state_async(rate_hz, callback);
×
410
}
×
411

412
void TelemetryImpl::set_rate_landed_state_async(double rate_hz, Telemetry::ResultCallback callback)
×
413
{
414
    _system_impl->set_msg_rate_async(
×
415
        MAVLINK_MSG_ID_EXTENDED_SYS_STATE,
416
        rate_hz,
417
        [callback](MavlinkCommandSender::Result command_result, float) {
×
418
            command_result_callback(command_result, callback);
×
419
        });
×
420
}
×
421

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

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

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

454
void TelemetryImpl::set_rate_velocity_ned_async(double rate_hz, Telemetry::ResultCallback callback)
×
455
{
456
    _velocity_ned_rate_hz = rate_hz;
×
457
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
458

459
    _system_impl->set_msg_rate_async(
×
460
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
461
        max_rate_hz,
462
        [callback](MavlinkCommandSender::Result command_result, float) {
×
463
            command_result_callback(command_result, callback);
×
464
        });
×
465
}
×
466

467
void TelemetryImpl::set_rate_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
468
{
469
    _system_impl->set_msg_rate_async(
×
470
        MAVLINK_MSG_ID_HIGHRES_IMU,
471
        rate_hz,
472
        [callback](MavlinkCommandSender::Result command_result, float) {
×
473
            command_result_callback(command_result, callback);
×
474
        });
×
475
}
×
476

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

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

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

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

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

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

538
void TelemetryImpl::set_rate_rc_status_async(double rate_hz, Telemetry::ResultCallback callback)
×
539
{
540
    UNUSED(rate_hz);
×
541
    LogWarn() << "System status is usually fixed at 1 Hz";
×
542
    _system_impl->call_user_callback([callback]() { callback(Telemetry::Result::Unsupported); });
×
543
}
×
544

545
void TelemetryImpl::set_rate_unix_epoch_time_async(
×
546
    double rate_hz, Telemetry::ResultCallback callback)
547
{
548
    _system_impl->set_msg_rate_async(
×
549
        MAVLINK_MSG_ID_UTM_GLOBAL_POSITION,
550
        rate_hz,
551
        [callback](MavlinkCommandSender::Result command_result, float) {
×
552
            command_result_callback(command_result, callback);
×
553
        });
×
554
}
×
555

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

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

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

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

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

610
Telemetry::Result
611
TelemetryImpl::telemetry_result_from_command_result(MavlinkCommandSender::Result command_result)
×
612
{
613
    switch (command_result) {
×
614
        case MavlinkCommandSender::Result::Success:
×
615
            return Telemetry::Result::Success;
×
616
        case MavlinkCommandSender::Result::NoSystem:
×
617
            return Telemetry::Result::NoSystem;
×
618
        case MavlinkCommandSender::Result::ConnectionError:
×
619
            return Telemetry::Result::ConnectionError;
×
620
        case MavlinkCommandSender::Result::Busy:
×
621
            return Telemetry::Result::Busy;
×
622
        case MavlinkCommandSender::Result::Denied:
×
623
            // FALLTHROUGH
624
        case MavlinkCommandSender::Result::TemporarilyRejected:
625
            return Telemetry::Result::CommandDenied;
×
626
        case MavlinkCommandSender::Result::Timeout:
×
627
            return Telemetry::Result::Timeout;
×
628
        case MavlinkCommandSender::Result::Unsupported:
×
629
            return Telemetry::Result::Unsupported;
×
630
        default:
×
631
            return Telemetry::Result::Unknown;
×
632
    }
633
}
634

635
void TelemetryImpl::command_result_callback(
×
636
    MavlinkCommandSender::Result command_result, const Telemetry::ResultCallback& callback)
637
{
638
    Telemetry::Result action_result = telemetry_result_from_command_result(command_result);
×
639

640
    callback(action_result);
×
641
}
×
642

643
void TelemetryImpl::process_position_velocity_ned(const mavlink_message_t& message)
×
644
{
645
    mavlink_local_position_ned_t local_position;
×
646
    mavlink_msg_local_position_ned_decode(&message, &local_position);
×
647

648
    Telemetry::PositionVelocityNed position_velocity;
×
649
    position_velocity.position.north_m = local_position.x;
×
650
    position_velocity.position.east_m = local_position.y;
×
651
    position_velocity.position.down_m = local_position.z;
×
652
    position_velocity.velocity.north_m_s = local_position.vx;
×
653
    position_velocity.velocity.east_m_s = local_position.vy;
×
654
    position_velocity.velocity.down_m_s = local_position.vz;
×
655

656
    set_position_velocity_ned(position_velocity);
×
657

658
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
659
    _position_velocity_ned_subscriptions.queue(position_velocity_ned(), [this](const auto& func) {
×
660
        _system_impl->call_user_callback(func);
×
661
    });
×
662

663
    set_health_local_position(true);
×
664
}
×
665

666
void TelemetryImpl::process_global_position_int(const mavlink_message_t& message)
×
667
{
668
    mavlink_global_position_int_t global_position_int;
×
669
    mavlink_msg_global_position_int_decode(&message, &global_position_int);
×
670

671
    {
672
        Telemetry::Position position;
×
673
        position.latitude_deg = global_position_int.lat * 1e-7;
×
674
        position.longitude_deg = global_position_int.lon * 1e-7;
×
675
        position.absolute_altitude_m = global_position_int.alt * 1e-3f;
×
676
        position.relative_altitude_m = global_position_int.relative_alt * 1e-3f;
×
677
        set_position(position);
×
678
    }
679

680
    {
681
        Telemetry::VelocityNed velocity;
×
682
        velocity.north_m_s = global_position_int.vx * 1e-2f;
×
683
        velocity.east_m_s = global_position_int.vy * 1e-2f;
×
684
        velocity.down_m_s = global_position_int.vz * 1e-2f;
×
685
        set_velocity_ned(velocity);
×
686
    }
687

688
    {
689
        Telemetry::Heading heading;
×
690
        heading.heading_deg = (global_position_int.hdg != std::numeric_limits<uint16_t>::max()) ?
×
691
                                  static_cast<double>(global_position_int.hdg) * 1e-2 :
×
692
                                  static_cast<double>(NAN);
693
        set_heading(heading);
×
694
    }
695

696
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
697
    _position_subscriptions.queue(
×
698
        position(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
699

700
    _velocity_ned_subscriptions.queue(
×
701
        velocity_ned(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
702

703
    _heading_subscriptions.queue(
×
704
        heading(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
705
}
×
706

707
void TelemetryImpl::process_home_position(const mavlink_message_t& message)
×
708
{
709
    mavlink_home_position_t home_position;
×
710
    mavlink_msg_home_position_decode(&message, &home_position);
×
711
    Telemetry::Position new_pos;
×
712
    new_pos.latitude_deg = home_position.latitude * 1e-7;
×
713
    new_pos.longitude_deg = home_position.longitude * 1e-7;
×
714
    new_pos.absolute_altitude_m = home_position.altitude * 1e-3f;
×
715
    new_pos.relative_altitude_m = 0.0f; // 0 by definition.
×
716

717
    set_home_position(new_pos);
×
718

719
    set_health_home_position(true);
×
720

721
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
722
    _home_position_subscriptions.queue(
×
723
        home(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
724
}
×
725

726
void TelemetryImpl::process_attitude(const mavlink_message_t& message)
×
727
{
728
    mavlink_attitude_t attitude;
×
729
    mavlink_msg_attitude_decode(&message, &attitude);
×
730

731
    Telemetry::EulerAngle euler_angle;
×
732
    euler_angle.roll_deg = to_deg_from_rad(attitude.roll);
×
733
    euler_angle.pitch_deg = to_deg_from_rad(attitude.pitch);
×
734
    euler_angle.yaw_deg = to_deg_from_rad(attitude.yaw);
×
735
    euler_angle.timestamp_us = static_cast<uint64_t>(attitude.time_boot_ms) * 1000;
×
736
    set_attitude_euler(euler_angle);
×
737

738
    Telemetry::AngularVelocityBody angular_velocity_body;
×
739
    angular_velocity_body.roll_rad_s = attitude.rollspeed;
×
740
    angular_velocity_body.pitch_rad_s = attitude.pitchspeed;
×
741
    angular_velocity_body.yaw_rad_s = attitude.yawspeed;
×
742
    set_attitude_angular_velocity_body(angular_velocity_body);
×
743

744
    _attitude_euler_angle_subscriptions.queue(
×
745
        attitude_euler(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
746

747
    _attitude_angular_velocity_body_subscriptions.queue(
×
748
        attitude_angular_velocity_body(),
749
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
750
}
×
751

752
void TelemetryImpl::process_attitude_quaternion(const mavlink_message_t& message)
×
753
{
754
    mavlink_attitude_quaternion_t mavlink_attitude_quaternion;
×
755
    mavlink_msg_attitude_quaternion_decode(&message, &mavlink_attitude_quaternion);
×
756

757
    Telemetry::Quaternion quaternion;
×
758
    quaternion.w = mavlink_attitude_quaternion.q1;
×
759
    quaternion.x = mavlink_attitude_quaternion.q2;
×
760
    quaternion.y = mavlink_attitude_quaternion.q3;
×
761
    quaternion.z = mavlink_attitude_quaternion.q4;
×
762
    quaternion.timestamp_us =
×
763
        static_cast<uint64_t>(mavlink_attitude_quaternion.time_boot_ms) * 1000;
×
764

765
    Telemetry::AngularVelocityBody angular_velocity_body;
×
766
    angular_velocity_body.roll_rad_s = mavlink_attitude_quaternion.rollspeed;
×
767
    angular_velocity_body.pitch_rad_s = mavlink_attitude_quaternion.pitchspeed;
×
768
    angular_velocity_body.yaw_rad_s = mavlink_attitude_quaternion.yawspeed;
×
769

770
    set_attitude_quaternion(quaternion);
×
771

772
    set_attitude_angular_velocity_body(angular_velocity_body);
×
773

774
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
775
    _attitude_quaternion_angle_subscriptions.queue(attitude_quaternion(), [this](const auto& func) {
×
776
        _system_impl->call_user_callback(func);
×
777
    });
×
778

779
    _attitude_angular_velocity_body_subscriptions.queue(
×
780
        attitude_angular_velocity_body(),
781
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
782
}
×
783

784
void TelemetryImpl::process_altitude(const mavlink_message_t& message)
×
785
{
786
    mavlink_altitude_t mavlink_altitude;
×
787
    mavlink_msg_altitude_decode(&message, &mavlink_altitude);
×
788

789
    Telemetry::Altitude new_altitude;
×
790
    new_altitude.altitude_monotonic_m = mavlink_altitude.altitude_monotonic;
×
791
    new_altitude.altitude_amsl_m = mavlink_altitude.altitude_amsl;
×
792
    new_altitude.altitude_local_m = mavlink_altitude.altitude_local;
×
793
    new_altitude.altitude_relative_m = mavlink_altitude.altitude_relative;
×
794
    new_altitude.altitude_terrain_m = mavlink_altitude.altitude_terrain;
×
795
    new_altitude.bottom_clearance_m = mavlink_altitude.bottom_clearance;
×
796

797
    set_altitude(new_altitude);
×
798

799
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
800
    _altitude_subscriptions.queue(
×
801
        altitude(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
802
}
×
803

804
void TelemetryImpl::process_imu_reading_ned(const mavlink_message_t& message)
×
805
{
806
    mavlink_highres_imu_t highres_imu;
×
807
    mavlink_msg_highres_imu_decode(&message, &highres_imu);
×
808
    Telemetry::Imu new_imu;
×
809
    new_imu.acceleration_frd.forward_m_s2 = highres_imu.xacc;
×
810
    new_imu.acceleration_frd.right_m_s2 = highres_imu.yacc;
×
811
    new_imu.acceleration_frd.down_m_s2 = highres_imu.zacc;
×
812
    new_imu.angular_velocity_frd.forward_rad_s = highres_imu.xgyro;
×
813
    new_imu.angular_velocity_frd.right_rad_s = highres_imu.ygyro;
×
814
    new_imu.angular_velocity_frd.down_rad_s = highres_imu.zgyro;
×
815
    new_imu.magnetic_field_frd.forward_gauss = highres_imu.xmag;
×
816
    new_imu.magnetic_field_frd.right_gauss = highres_imu.ymag;
×
817
    new_imu.magnetic_field_frd.down_gauss = highres_imu.zmag;
×
818
    new_imu.temperature_degc = highres_imu.temperature;
×
819
    new_imu.timestamp_us = highres_imu.time_usec;
×
820

821
    set_imu_reading_ned(new_imu);
×
822

823
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
824
    _imu_reading_ned_subscriptions.queue(
×
825
        imu(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
826
}
×
827

828
void TelemetryImpl::process_scaled_imu(const mavlink_message_t& message)
×
829
{
830
    mavlink_scaled_imu_t scaled_imu_reading;
×
831
    mavlink_msg_scaled_imu_decode(&message, &scaled_imu_reading);
×
832
    Telemetry::Imu new_imu;
×
833
    new_imu.acceleration_frd.forward_m_s2 = scaled_imu_reading.xacc;
×
834
    new_imu.acceleration_frd.right_m_s2 = scaled_imu_reading.yacc;
×
835
    new_imu.acceleration_frd.down_m_s2 = scaled_imu_reading.zacc;
×
836
    new_imu.angular_velocity_frd.forward_rad_s = scaled_imu_reading.xgyro;
×
837
    new_imu.angular_velocity_frd.right_rad_s = scaled_imu_reading.ygyro;
×
838
    new_imu.angular_velocity_frd.down_rad_s = scaled_imu_reading.zgyro;
×
839
    new_imu.magnetic_field_frd.forward_gauss = scaled_imu_reading.xmag;
×
840
    new_imu.magnetic_field_frd.right_gauss = scaled_imu_reading.ymag;
×
841
    new_imu.magnetic_field_frd.down_gauss = scaled_imu_reading.zmag;
×
842
    new_imu.temperature_degc = static_cast<float>(scaled_imu_reading.temperature) * 1e-2f;
×
843
    new_imu.timestamp_us = static_cast<uint64_t>(scaled_imu_reading.time_boot_ms) * 1000;
×
844

845
    set_scaled_imu(new_imu);
×
846

847
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
848
    _scaled_imu_subscriptions.queue(
×
849
        scaled_imu(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
850
}
×
851

852
void TelemetryImpl::process_raw_imu(const mavlink_message_t& message)
×
853
{
854
    mavlink_raw_imu_t raw_imu_reading;
×
855
    mavlink_msg_raw_imu_decode(&message, &raw_imu_reading);
×
856
    Telemetry::Imu new_imu;
×
857
    new_imu.acceleration_frd.forward_m_s2 = raw_imu_reading.xacc;
×
858
    new_imu.acceleration_frd.right_m_s2 = raw_imu_reading.yacc;
×
859
    new_imu.acceleration_frd.down_m_s2 = raw_imu_reading.zacc;
×
860
    new_imu.angular_velocity_frd.forward_rad_s = raw_imu_reading.xgyro;
×
861
    new_imu.angular_velocity_frd.right_rad_s = raw_imu_reading.ygyro;
×
862
    new_imu.angular_velocity_frd.down_rad_s = raw_imu_reading.zgyro;
×
863
    new_imu.magnetic_field_frd.forward_gauss = raw_imu_reading.xmag;
×
864
    new_imu.magnetic_field_frd.right_gauss = raw_imu_reading.ymag;
×
865
    new_imu.magnetic_field_frd.down_gauss = raw_imu_reading.zmag;
×
866
    new_imu.temperature_degc = static_cast<float>(raw_imu_reading.temperature) * 1e-2f;
×
867
    new_imu.timestamp_us = raw_imu_reading.time_usec;
×
868

869
    set_raw_imu(new_imu);
×
870

871
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
872
    _raw_imu_subscriptions.queue(
×
873
        raw_imu(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
874
}
×
875

876
void TelemetryImpl::process_gps_raw_int(const mavlink_message_t& message)
×
877
{
878
    mavlink_gps_raw_int_t gps_raw_int;
×
879
    mavlink_msg_gps_raw_int_decode(&message, &gps_raw_int);
×
880

881
    Telemetry::FixType fix_type;
882
    switch (gps_raw_int.fix_type) {
×
883
        case 0:
×
884
            fix_type = Telemetry::FixType::NoGps;
×
885
            break;
×
886
        case 1:
×
887
            fix_type = Telemetry::FixType::NoFix;
×
888
            break;
×
889
        case 2:
×
890
            fix_type = Telemetry::FixType::Fix2D;
×
891
            break;
×
892
        case 3:
×
893
            fix_type = Telemetry::FixType::Fix3D;
×
894
            break;
×
895
        case 4:
×
896
            fix_type = Telemetry::FixType::FixDgps;
×
897
            break;
×
898
        case 5:
×
899
            fix_type = Telemetry::FixType::RtkFloat;
×
900
            break;
×
901
        case 6:
×
902
            fix_type = Telemetry::FixType::RtkFixed;
×
903
            break;
×
904

905
        default:
×
906
            LogErr() << "Received unknown GPS fix type!";
×
907
            fix_type = Telemetry::FixType::NoGps;
×
908
            break;
×
909
    }
910

911
    Telemetry::GpsInfo new_gps_info;
×
912
    new_gps_info.num_satellites = gps_raw_int.satellites_visible;
×
913
    new_gps_info.fix_type = fix_type;
×
914
    set_gps_info(new_gps_info);
×
915

916
    Telemetry::RawGps raw_gps_info;
×
917
    raw_gps_info.timestamp_us = gps_raw_int.time_usec;
×
918
    raw_gps_info.latitude_deg = gps_raw_int.lat * 1e-7;
×
919
    raw_gps_info.longitude_deg = gps_raw_int.lon * 1e-7;
×
920
    raw_gps_info.absolute_altitude_m = gps_raw_int.alt * 1e-3f;
×
921
    raw_gps_info.hdop = static_cast<float>(gps_raw_int.eph) * 1e-2f;
×
922
    raw_gps_info.vdop = static_cast<float>(gps_raw_int.epv) * 1e-2f;
×
923
    raw_gps_info.velocity_m_s = static_cast<float>(gps_raw_int.vel) * 1e-2f;
×
924
    raw_gps_info.cog_deg = static_cast<float>(gps_raw_int.cog) * 1e-2f;
×
925
    raw_gps_info.altitude_ellipsoid_m = static_cast<float>(gps_raw_int.alt_ellipsoid) * 1e-3f;
×
926
    raw_gps_info.horizontal_uncertainty_m = static_cast<float>(gps_raw_int.h_acc) * 1e-3f;
×
927
    raw_gps_info.vertical_uncertainty_m = static_cast<float>(gps_raw_int.v_acc) * 1e-3f;
×
928
    raw_gps_info.velocity_uncertainty_m_s = static_cast<float>(gps_raw_int.vel_acc) * 1e-3f;
×
929
    raw_gps_info.heading_uncertainty_deg = static_cast<float>(gps_raw_int.hdg_acc) * 1e-5f;
×
930
    raw_gps_info.yaw_deg = static_cast<float>(gps_raw_int.yaw) * 1e-2f;
×
931
    set_raw_gps(raw_gps_info);
×
932

933
    {
934
        std::lock_guard<std::mutex> lock(_subscription_mutex);
×
935
        _gps_info_subscriptions.queue(
×
936
            gps_info(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
937
        _raw_gps_subscriptions.queue(
×
938
            raw_gps(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
939
    }
×
940
}
×
941

942
void TelemetryImpl::process_ground_truth(const mavlink_message_t& message)
×
943
{
944
    mavlink_hil_state_quaternion_t hil_state_quaternion;
×
945
    mavlink_msg_hil_state_quaternion_decode(&message, &hil_state_quaternion);
×
946

947
    Telemetry::GroundTruth new_ground_truth;
×
948
    new_ground_truth.latitude_deg = hil_state_quaternion.lat * 1e-7;
×
949
    new_ground_truth.longitude_deg = hil_state_quaternion.lon * 1e-7;
×
950
    new_ground_truth.absolute_altitude_m = hil_state_quaternion.alt * 1e-3f;
×
951

952
    set_ground_truth(new_ground_truth);
×
953

954
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
955
    _ground_truth_subscriptions.queue(
×
956
        ground_truth(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
957
}
×
958

959
void TelemetryImpl::process_extended_sys_state(const mavlink_message_t& message)
×
960
{
961
    mavlink_extended_sys_state_t extended_sys_state;
×
962
    mavlink_msg_extended_sys_state_decode(&message, &extended_sys_state);
×
963

964
    {
965
        Telemetry::LandedState landed_state = to_landed_state(extended_sys_state);
×
966
        set_landed_state(landed_state);
×
967

968
        Telemetry::VtolState vtol_state = to_vtol_state(extended_sys_state);
×
969
        set_vtol_state(vtol_state);
×
970
    }
971

972
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
973
    _landed_state_subscriptions.queue(
×
974
        landed_state(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
975

976
    _vtol_state_subscriptions.queue(
×
977
        vtol_state(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
978

979
    if (extended_sys_state.landed_state == MAV_LANDED_STATE_IN_AIR ||
×
980
        extended_sys_state.landed_state == MAV_LANDED_STATE_TAKEOFF ||
×
981
        extended_sys_state.landed_state == MAV_LANDED_STATE_LANDING) {
×
982
        set_in_air(true);
×
983
    } else if (extended_sys_state.landed_state == MAV_LANDED_STATE_ON_GROUND) {
×
984
        set_in_air(false);
×
985
    }
986
    // If landed_state is undefined, we use what we have received last.
987

988
    _in_air_subscriptions.queue(
×
989
        in_air(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
990
}
×
991
void TelemetryImpl::process_fixedwing_metrics(const mavlink_message_t& message)
×
992
{
993
    mavlink_vfr_hud_t vfr_hud;
×
994
    mavlink_msg_vfr_hud_decode(&message, &vfr_hud);
×
995

996
    Telemetry::FixedwingMetrics new_fixedwing_metrics;
×
997
    new_fixedwing_metrics.airspeed_m_s = vfr_hud.airspeed;
×
998
    new_fixedwing_metrics.throttle_percentage = vfr_hud.throttle * 1e-2f;
×
999
    new_fixedwing_metrics.climb_rate_m_s = vfr_hud.climb;
×
1000

1001
    set_fixedwing_metrics(new_fixedwing_metrics);
×
1002

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

1008
void TelemetryImpl::process_sys_status(const mavlink_message_t& message)
×
1009
{
1010
    mavlink_sys_status_t sys_status;
×
1011
    mavlink_msg_sys_status_decode(&message, &sys_status);
×
1012

1013
    if (!_has_bat_status) {
×
1014
        Telemetry::Battery new_battery;
×
1015
        new_battery.voltage_v = sys_status.voltage_battery * 1e-3f;
×
1016
        new_battery.remaining_percent = sys_status.battery_remaining;
×
1017

1018
        set_battery(new_battery);
×
1019

1020
        {
1021
            std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1022
            _battery_subscriptions.queue(
×
1023
                battery(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1024
        }
×
1025
    }
1026

1027
    const bool rc_ok =
×
1028
        sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
×
1029

1030
    set_rc_status({rc_ok}, std::nullopt);
×
1031

1032
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_GYRO) {
×
1033
        set_health_gyrometer_calibration(
×
1034
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_GYRO);
×
1035
    }
1036

1037
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_ACCEL) {
×
1038
        set_health_accelerometer_calibration(
×
1039
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_ACCEL);
×
1040
    }
1041

1042
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_MAG) {
×
1043
        set_health_magnetometer_calibration(
×
1044
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_MAG);
×
1045
    }
1046

1047
    const bool global_position_ok =
1048
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_GPS);
×
1049

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

1053
    const bool local_position_ok =
1054
        global_position_ok ||
×
1055
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW) ||
×
1056
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_VISION_POSITION);
×
1057

1058
    set_health_local_position(local_position_ok);
×
1059
    set_health_global_position(global_position_ok);
×
1060

1061
    set_rc_status({rc_ok}, std::nullopt);
×
1062

1063
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1064
    _rc_status_subscriptions.queue(
×
1065
        rc_status(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1066

1067
    const bool armable = sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_PREARM_CHECK;
×
1068
    set_health_armable(armable);
×
1069
    _health_all_ok_subscriptions.queue(
×
1070
        health_all_ok(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1071
}
×
1072

1073
bool TelemetryImpl::sys_status_present_enabled_health(
×
1074
    const mavlink_sys_status_t& sys_status, MAV_SYS_STATUS_SENSOR flag)
1075
{
1076
    // FIXME: it doesn't look like PX4 sets enabled for GPS
1077
    return (sys_status.onboard_control_sensors_present & flag) != 0 &&
×
1078
           // (sys_status.onboard_control_sensors_enabled & flag) != 0 &&
1079
           (sys_status.onboard_control_sensors_health & flag) != 0;
×
1080
}
1081

1082
void TelemetryImpl::process_battery_status(const mavlink_message_t& message)
×
1083
{
1084
    mavlink_battery_status_t bat_status;
×
1085
    mavlink_msg_battery_status_decode(&message, &bat_status);
×
1086

1087
    _has_bat_status = true;
×
1088

1089
    Telemetry::Battery new_battery;
×
1090
    new_battery.id = bat_status.id;
×
1091
    new_battery.temperature_degc = (bat_status.temperature == std::numeric_limits<int16_t>::max()) ?
×
1092
                                       static_cast<float>(NAN) :
1093
                                       bat_status.temperature * 1e-2f; // cdegC to degC
×
1094
    new_battery.voltage_v = 0.0f;
×
1095
    for (int i = 0; i < 10; ++i) {
×
1096
        if (bat_status.voltages[i] == std::numeric_limits<uint16_t>::max()) {
×
1097
            break;
×
1098
        }
1099
        new_battery.voltage_v += static_cast<float>(bat_status.voltages[i]) * 1e-3f;
×
1100
    }
1101

1102
    for (int i = 0; i < 4; ++i) {
×
1103
        if (bat_status.voltages_ext[i] == std::numeric_limits<uint16_t>::max()) {
×
1104
            // Some implementations out there set it to UINT16_MAX to signal invalid.
1105
            // That's not up to the spec but we can ignore it nevertheless to be backwards
1106
            // compatible.
1107
            break;
×
1108
        } else if (bat_status.voltages_ext[i] > 1) {
×
1109
            // A value of 1 means 0 mV.
1110
            new_battery.voltage_v += static_cast<float>(bat_status.voltages_ext[i]) * 1e-3f;
×
1111
        }
1112
    }
1113

1114
    new_battery.remaining_percent = bat_status.battery_remaining;
×
1115
    new_battery.current_battery_a = (bat_status.current_battery == -1) ?
×
1116
                                        static_cast<float>(NAN) :
1117
                                        bat_status.current_battery * 1e-2f; // cA to A
×
1118
    new_battery.capacity_consumed_ah = (bat_status.current_consumed == -1) ?
×
1119
                                           static_cast<float>(NAN) :
1120
                                           bat_status.current_consumed * 1e-3f; // mAh to Ah
×
1121

1122
    set_battery(new_battery);
×
1123

1124
    {
1125
        std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1126
        _battery_subscriptions.queue(
×
1127
            battery(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1128
    }
×
1129
}
×
1130

1131
void TelemetryImpl::process_heartbeat(const mavlink_message_t& message)
1✔
1132
{
1133
    if (message.compid != MAV_COMP_ID_AUTOPILOT1) {
1✔
1134
        return;
×
1135
    }
1136

1137
    mavlink_heartbeat_t heartbeat;
1✔
1138
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
1✔
1139

1140
    set_armed(((heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) ? true : false));
1✔
1141

1142
    std::lock_guard<std::mutex> lock(_subscription_mutex);
1✔
1143
    _armed_subscriptions.queue(
2✔
1144
        armed(), [this](const auto& func) { _system_impl->call_user_callback(func); });
1✔
1145

1146
    _flight_mode_subscriptions.queue(
2✔
1147
        telemetry_flight_mode_from_flight_mode(_system_impl->get_flight_mode()),
1✔
1148
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1149

1150
    _health_subscriptions.queue(
1✔
1151
        health(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1152

1153
    _health_all_ok_subscriptions.queue(
2✔
1154
        health_all_ok(), [this](const auto& func) { _system_impl->call_user_callback(func); });
1✔
1155
}
1✔
1156

1157
void TelemetryImpl::receive_statustext(const MavlinkStatustextHandler::Statustext& statustext)
3✔
1158
{
1159
    Telemetry::StatusText new_status_text;
3✔
1160

1161
    switch (statustext.severity) {
3✔
1162
        case MAV_SEVERITY_EMERGENCY:
×
1163
            new_status_text.type = Telemetry::StatusTextType::Emergency;
×
1164
            break;
×
1165
        case MAV_SEVERITY_ALERT:
×
1166
            new_status_text.type = Telemetry::StatusTextType::Alert;
×
1167
            break;
×
1168
        case MAV_SEVERITY_CRITICAL:
×
1169
            new_status_text.type = Telemetry::StatusTextType::Critical;
×
1170
            break;
×
1171
        case MAV_SEVERITY_ERROR:
×
1172
            new_status_text.type = Telemetry::StatusTextType::Error;
×
1173
            break;
×
1174
        case MAV_SEVERITY_WARNING:
×
1175
            new_status_text.type = Telemetry::StatusTextType::Warning;
×
1176
            break;
×
1177
        case MAV_SEVERITY_NOTICE:
×
1178
            new_status_text.type = Telemetry::StatusTextType::Notice;
×
1179
            break;
×
1180
        case MAV_SEVERITY_INFO:
3✔
1181
            new_status_text.type = Telemetry::StatusTextType::Info;
3✔
1182
            break;
3✔
1183
        case MAV_SEVERITY_DEBUG:
×
1184
            new_status_text.type = Telemetry::StatusTextType::Debug;
×
1185
            break;
×
1186
        default:
×
1187
            LogWarn() << "Unknown StatusText severity";
×
1188
            new_status_text.type = Telemetry::StatusTextType::Info;
×
1189
            break;
×
1190
    }
1191

1192
    new_status_text.text = statustext.text;
3✔
1193

1194
    set_status_text(new_status_text);
3✔
1195

1196
    std::lock_guard<std::mutex> lock(_subscription_mutex);
6✔
1197
    _status_text_subscriptions.queue(
9✔
1198
        status_text(), [this](const auto& func) { _system_impl->call_user_callback(func); });
11✔
1199
}
3✔
1200

1201
void TelemetryImpl::process_rc_channels(const mavlink_message_t& message)
×
1202
{
1203
    mavlink_rc_channels_t rc_channels;
×
1204
    mavlink_msg_rc_channels_decode(&message, &rc_channels);
×
1205

1206
    if (rc_channels.rssi != std::numeric_limits<uint8_t>::max()) {
×
1207
        set_rc_status(std::nullopt, {rc_channels.rssi});
×
1208
    }
1209

1210
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1211
    _rc_status_subscriptions.queue(
×
1212
        rc_status(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1213
}
×
1214

1215
void TelemetryImpl::process_unix_epoch_time(const mavlink_message_t& message)
×
1216
{
1217
    mavlink_system_time_t system_time;
×
1218
    mavlink_msg_system_time_decode(&message, &system_time);
×
1219

1220
    set_unix_epoch_time_us(system_time.time_unix_usec);
×
1221

1222
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1223
    _unix_epoch_time_subscriptions.queue(
×
1224
        unix_epoch_time(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1225
}
×
1226

1227
void TelemetryImpl::process_actuator_control_target(const mavlink_message_t& message)
×
1228
{
1229
    mavlink_set_actuator_control_target_t target;
×
1230
    mavlink_msg_set_actuator_control_target_decode(&message, &target);
×
1231

1232
    uint32_t group = target.group_mlx;
×
1233
    std::vector<float> controls;
×
1234

1235
    const unsigned control_size = sizeof(target.controls) / sizeof(target.controls[0]);
×
1236
    // Can't use std::copy because target is packed.
1237
    for (std::size_t i = 0; i < control_size; ++i) {
×
1238
        controls.push_back(target.controls[i]);
×
1239
    }
1240

1241
    set_actuator_control_target(group, controls);
×
1242

1243
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1244
    _actuator_control_target_subscriptions.queue(
×
1245
        actuator_control_target(),
×
1246
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1247
}
×
1248

1249
void TelemetryImpl::process_actuator_output_status(const mavlink_message_t& message)
×
1250
{
1251
    mavlink_actuator_output_status_t status;
×
1252
    mavlink_msg_actuator_output_status_decode(&message, &status);
×
1253

1254
    uint32_t active = status.active;
×
1255
    std::vector<float> actuators;
×
1256

1257
    const unsigned actuators_size = sizeof(status.actuator) / sizeof(status.actuator[0]);
×
1258
    // Can't use std::copy because status is packed.
1259
    for (std::size_t i = 0; i < actuators_size; ++i) {
×
1260
        actuators.push_back(status.actuator[i]);
×
1261
    }
1262

1263
    set_actuator_output_status(active, actuators);
×
1264

1265
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1266
    _actuator_output_status_subscriptions.queue(actuator_output_status(), [this](const auto& func) {
×
1267
        _system_impl->call_user_callback(func);
×
1268
    });
×
1269
}
×
1270

1271
void TelemetryImpl::process_odometry(const mavlink_message_t& message)
×
1272
{
1273
    mavlink_odometry_t odometry_msg;
×
1274
    mavlink_msg_odometry_decode(&message, &odometry_msg);
×
1275

1276
    Telemetry::Odometry odometry_struct{};
×
1277

1278
    odometry_struct.time_usec = odometry_msg.time_usec;
×
1279
    odometry_struct.frame_id = static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.frame_id);
×
1280
    odometry_struct.child_frame_id =
×
1281
        static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.child_frame_id);
×
1282

1283
    odometry_struct.position_body.x_m = odometry_msg.x;
×
1284
    odometry_struct.position_body.y_m = odometry_msg.y;
×
1285
    odometry_struct.position_body.z_m = odometry_msg.z;
×
1286

1287
    odometry_struct.q.w = odometry_msg.q[0];
×
1288
    odometry_struct.q.x = odometry_msg.q[1];
×
1289
    odometry_struct.q.y = odometry_msg.q[2];
×
1290
    odometry_struct.q.z = odometry_msg.q[3];
×
1291

1292
    odometry_struct.velocity_body.x_m_s = odometry_msg.vx;
×
1293
    odometry_struct.velocity_body.y_m_s = odometry_msg.vy;
×
1294
    odometry_struct.velocity_body.z_m_s = odometry_msg.vz;
×
1295

1296
    odometry_struct.angular_velocity_body.roll_rad_s = odometry_msg.rollspeed;
×
1297
    odometry_struct.angular_velocity_body.pitch_rad_s = odometry_msg.pitchspeed;
×
1298
    odometry_struct.angular_velocity_body.yaw_rad_s = odometry_msg.yawspeed;
×
1299

1300
    const std::size_t len_pose_covariance =
×
1301
        sizeof(odometry_msg.pose_covariance) / sizeof(odometry_msg.pose_covariance[0]);
1302
    for (std::size_t i = 0; i < len_pose_covariance; ++i) {
×
1303
        odometry_struct.pose_covariance.covariance_matrix.push_back(
×
1304
            odometry_msg.pose_covariance[i]);
×
1305
    }
1306

1307
    const std::size_t len_velocity_covariance =
×
1308
        sizeof(odometry_msg.velocity_covariance) / sizeof(odometry_msg.velocity_covariance[0]);
1309
    for (std::size_t i = 0; i < len_velocity_covariance; ++i) {
×
1310
        odometry_struct.velocity_covariance.covariance_matrix.push_back(
×
1311
            odometry_msg.velocity_covariance[i]);
×
1312
    }
1313

1314
    set_odometry(odometry_struct);
×
1315

1316
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1317
    _odometry_subscriptions.queue(
×
1318
        odometry(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1319
}
×
1320

1321
void TelemetryImpl::process_distance_sensor(const mavlink_message_t& message)
×
1322
{
1323
    mavlink_distance_sensor_t distance_sensor_msg;
×
1324
    mavlink_msg_distance_sensor_decode(&message, &distance_sensor_msg);
×
1325

1326
    Telemetry::DistanceSensor distance_sensor_struct{};
×
1327

1328
    distance_sensor_struct.minimum_distance_m =
×
1329
        static_cast<float>(distance_sensor_msg.min_distance) * 1e-2f; // cm to m
×
1330
    distance_sensor_struct.maximum_distance_m =
×
1331
        static_cast<float>(distance_sensor_msg.max_distance) * 1e-2f; // cm to m
×
1332
    distance_sensor_struct.current_distance_m =
×
1333
        static_cast<float>(distance_sensor_msg.current_distance) * 1e-2f; // cm to m
×
1334
    distance_sensor_struct.orientation = extractOrientation(distance_sensor_msg);
×
1335

1336
    set_distance_sensor(distance_sensor_struct);
×
1337

1338
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1339
    _distance_sensor_subscriptions.queue(
×
1340
        distance_sensor(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1341
}
×
1342

1343
Telemetry::EulerAngle
1344
TelemetryImpl::extractOrientation(mavlink_distance_sensor_t distance_sensor_msg)
×
1345
{
1346
    MavSensorOrientation orientation =
×
1347
        static_cast<MavSensorOrientation>(distance_sensor_msg.orientation);
×
1348

1349
    Telemetry::EulerAngle euler_angle;
×
1350
    euler_angle.roll_deg = 0;
×
1351
    euler_angle.pitch_deg = 0;
×
1352
    euler_angle.yaw_deg = 0;
×
1353

1354
    switch (orientation) {
×
1355
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_45: {
×
1356
            euler_angle.yaw_deg = 45;
×
1357
            break;
×
1358
        }
1359
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_90: {
×
1360
            euler_angle.yaw_deg = 90;
×
1361
            break;
×
1362
        }
1363
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_135: {
×
1364
            euler_angle.yaw_deg = 135;
×
1365
            break;
×
1366
        }
1367
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_180: {
×
1368
            euler_angle.yaw_deg = 180;
×
1369
            break;
×
1370
        }
1371
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_225: {
×
1372
            euler_angle.yaw_deg = 225;
×
1373
            break;
×
1374
        }
1375
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_270: {
×
1376
            euler_angle.yaw_deg = 270;
×
1377
            break;
×
1378
        }
1379
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_315: {
×
1380
            euler_angle.yaw_deg = 315;
×
1381
            break;
×
1382
        }
1383
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180: {
×
1384
            euler_angle.roll_deg = 180;
×
1385
            break;
×
1386
        }
1387
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_45: {
×
1388
            euler_angle.roll_deg = 180;
×
1389
            euler_angle.yaw_deg = 45;
×
1390
            break;
×
1391
        }
1392
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_90: {
×
1393
            euler_angle.roll_deg = 180;
×
1394
            euler_angle.yaw_deg = 90;
×
1395
            break;
×
1396
        }
1397
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_135: {
×
1398
            euler_angle.roll_deg = 180;
×
1399
            euler_angle.yaw_deg = 135;
×
1400
            break;
×
1401
        }
1402
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_180: {
×
1403
            euler_angle.pitch_deg = 180;
×
1404
            break;
×
1405
        }
1406
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_225: {
×
1407
            euler_angle.roll_deg = 180;
×
1408
            euler_angle.yaw_deg = 225;
×
1409
            break;
×
1410
        }
1411
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_270: {
×
1412
            euler_angle.roll_deg = 180;
×
1413
            euler_angle.yaw_deg = 270;
×
1414
            break;
×
1415
        }
1416
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_315: {
×
1417
            euler_angle.roll_deg = 180;
×
1418
            euler_angle.yaw_deg = 315;
×
1419
            break;
×
1420
        }
1421
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90: {
×
1422
            euler_angle.roll_deg = 90;
×
1423
            break;
×
1424
        }
1425
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_45: {
×
1426
            euler_angle.roll_deg = 90;
×
1427
            euler_angle.yaw_deg = 45;
×
1428
            break;
×
1429
        }
1430
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_90: {
×
1431
            euler_angle.roll_deg = 90;
×
1432
            euler_angle.yaw_deg = 90;
×
1433
            break;
×
1434
        }
1435
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_135: {
×
1436
            euler_angle.roll_deg = 90;
×
1437
            euler_angle.yaw_deg = 135;
×
1438
            break;
×
1439
        }
1440
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270: {
×
1441
            euler_angle.roll_deg = 270;
×
1442
            break;
×
1443
        }
1444
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_YAW_45: {
×
1445
            euler_angle.roll_deg = 270;
×
1446
            euler_angle.yaw_deg = 45;
×
1447
            break;
×
1448
        }
1449
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_YAW_90: {
×
1450
            euler_angle.roll_deg = 270;
×
1451
            euler_angle.yaw_deg = 90;
×
1452
            break;
×
1453
        }
1454
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_YAW_135: {
×
1455
            euler_angle.roll_deg = 270;
×
1456
            euler_angle.yaw_deg = 135;
×
1457
            break;
×
1458
        }
1459
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_90: {
×
1460
            euler_angle.pitch_deg = 90;
×
1461
            break;
×
1462
        }
1463
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_270: {
×
1464
            euler_angle.pitch_deg = 270;
×
1465
            break;
×
1466
        }
1467
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_180_YAW_90: {
×
1468
            euler_angle.pitch_deg = 180;
×
1469
            euler_angle.yaw_deg = 90;
×
1470
            break;
×
1471
        }
1472
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_180_YAW_270: {
×
1473
            euler_angle.pitch_deg = 180;
×
1474
            euler_angle.yaw_deg = 270;
×
1475
            break;
×
1476
        }
1477
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_90: {
×
1478
            euler_angle.roll_deg = 90;
×
1479
            euler_angle.pitch_deg = 90;
×
1480
            break;
×
1481
        }
1482
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_PITCH_90: {
×
1483
            euler_angle.roll_deg = 180;
×
1484
            euler_angle.pitch_deg = 90;
×
1485
            break;
×
1486
        }
1487
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_PITCH_90: {
×
1488
            euler_angle.roll_deg = 270;
×
1489
            euler_angle.pitch_deg = 90;
×
1490
            break;
×
1491
        }
1492
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_180: {
×
1493
            euler_angle.roll_deg = 90;
×
1494
            euler_angle.pitch_deg = 180;
×
1495
            break;
×
1496
        }
1497
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_PITCH_180: {
×
1498
            euler_angle.roll_deg = 270;
×
1499
            euler_angle.pitch_deg = 180;
×
1500
            break;
×
1501
        }
1502
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_270: {
×
1503
            euler_angle.roll_deg = 90;
×
1504
            euler_angle.pitch_deg = 270;
×
1505
            break;
×
1506
        }
1507
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_PITCH_270: {
×
1508
            euler_angle.roll_deg = 180;
×
1509
            euler_angle.pitch_deg = 270;
×
1510
            break;
×
1511
        }
1512
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_PITCH_270: {
×
1513
            euler_angle.roll_deg = 270;
×
1514
            euler_angle.pitch_deg = 270;
×
1515
            break;
×
1516
        }
1517
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90: {
×
1518
            euler_angle.roll_deg = 90;
×
1519
            euler_angle.pitch_deg = 180;
×
1520
            euler_angle.yaw_deg = 90;
×
1521
            break;
×
1522
        }
1523
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_270: {
×
1524
            euler_angle.roll_deg = 90;
×
1525
            euler_angle.yaw_deg = 270;
×
1526
            break;
×
1527
        }
1528
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_68_YAW_293: {
×
1529
            euler_angle.roll_deg = 90;
×
1530
            euler_angle.pitch_deg = 68;
×
1531
            euler_angle.yaw_deg = 293;
×
1532
            break;
×
1533
        }
1534
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_315: {
×
1535
            euler_angle.pitch_deg = 315;
×
1536
            break;
×
1537
        }
1538
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_315: {
×
1539
            euler_angle.roll_deg = 90;
×
1540
            euler_angle.pitch_deg = 315;
×
1541
            break;
×
1542
        }
1543
        default: {
×
1544
            euler_angle.roll_deg = 0;
×
1545
            euler_angle.pitch_deg = 0;
×
1546
            euler_angle.yaw_deg = 0;
×
1547
        }
1548
    }
1549

1550
    return euler_angle;
×
1551
}
1552

1553
void TelemetryImpl::process_scaled_pressure(const mavlink_message_t& message)
×
1554
{
1555
    mavlink_scaled_pressure_t scaled_pressure_msg;
×
1556
    mavlink_msg_scaled_pressure_decode(&message, &scaled_pressure_msg);
×
1557

1558
    Telemetry::ScaledPressure scaled_pressure_struct{};
×
1559

1560
    scaled_pressure_struct.timestamp_us =
×
1561
        static_cast<uint64_t>(scaled_pressure_msg.time_boot_ms) * 1000;
×
1562
    scaled_pressure_struct.absolute_pressure_hpa = scaled_pressure_msg.press_abs;
×
1563
    scaled_pressure_struct.differential_pressure_hpa = scaled_pressure_msg.press_diff;
×
1564
    scaled_pressure_struct.temperature_deg =
×
1565
        static_cast<float>(scaled_pressure_msg.temperature) * 1e-2f;
×
1566
    scaled_pressure_struct.differential_pressure_temperature_deg =
×
1567
        static_cast<float>(scaled_pressure_msg.temperature_press_diff) * 1e-2f;
×
1568

1569
    set_scaled_pressure(scaled_pressure_struct);
×
1570

1571
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1572
    _scaled_pressure_subscriptions.queue(
×
1573
        scaled_pressure(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1574
}
×
1575

1576
Telemetry::LandedState
1577
TelemetryImpl::to_landed_state(mavlink_extended_sys_state_t extended_sys_state)
×
1578
{
1579
    switch (extended_sys_state.landed_state) {
×
1580
        case MAV_LANDED_STATE_IN_AIR:
×
1581
            return Telemetry::LandedState::InAir;
×
1582
        case MAV_LANDED_STATE_TAKEOFF:
×
1583
            return Telemetry::LandedState::TakingOff;
×
1584
        case MAV_LANDED_STATE_LANDING:
×
1585
            return Telemetry::LandedState::Landing;
×
1586
        case MAV_LANDED_STATE_ON_GROUND:
×
1587
            return Telemetry::LandedState::OnGround;
×
1588
        default:
×
1589
            return Telemetry::LandedState::Unknown;
×
1590
    }
1591
}
1592

1593
Telemetry::VtolState TelemetryImpl::to_vtol_state(mavlink_extended_sys_state_t extended_sys_state)
×
1594
{
1595
    switch (extended_sys_state.vtol_state) {
×
1596
        case MAV_VTOL_STATE::MAV_VTOL_STATE_TRANSITION_TO_FW:
×
1597
            return Telemetry::VtolState::TransitionToFw;
×
1598
        case MAV_VTOL_STATE_TRANSITION_TO_MC:
×
1599
            return Telemetry::VtolState::TransitionToMc;
×
1600
        case MAV_VTOL_STATE_MC:
×
1601
            return Telemetry::VtolState::Mc;
×
1602
        case MAV_VTOL_STATE_FW:
×
1603
            return Telemetry::VtolState::Fw;
×
1604
        default:
×
1605
            return Telemetry::VtolState::Undefined;
×
1606
    }
1607
}
1608

1609
Telemetry::FlightMode TelemetryImpl::telemetry_flight_mode_from_flight_mode(FlightMode flight_mode)
1✔
1610
{
1611
    switch (flight_mode) {
1✔
1612
        case FlightMode::Ready:
×
1613
            return Telemetry::FlightMode::Ready;
×
1614
        case FlightMode::Takeoff:
×
1615
            return Telemetry::FlightMode::Takeoff;
×
1616
        case FlightMode::Hold:
×
1617
            return Telemetry::FlightMode::Hold;
×
1618
        case FlightMode::Mission:
×
1619
            return Telemetry::FlightMode::Mission;
×
1620
        case FlightMode::ReturnToLaunch:
×
1621
            return Telemetry::FlightMode::ReturnToLaunch;
×
1622
        case FlightMode::Land:
×
1623
            return Telemetry::FlightMode::Land;
×
1624
        case FlightMode::Offboard:
×
1625
            return Telemetry::FlightMode::Offboard;
×
1626
        case FlightMode::FollowMe:
×
1627
            return Telemetry::FlightMode::FollowMe;
×
1628
        case FlightMode::Manual:
×
1629
            return Telemetry::FlightMode::Manual;
×
1630
        case FlightMode::Posctl:
×
1631
            return Telemetry::FlightMode::Posctl;
×
1632
        case FlightMode::Altctl:
×
1633
            return Telemetry::FlightMode::Altctl;
×
1634
        case FlightMode::Rattitude:
×
1635
            return Telemetry::FlightMode::Rattitude;
×
1636
        case FlightMode::Acro:
×
1637
            return Telemetry::FlightMode::Acro;
×
1638
        case FlightMode::Stabilized:
×
1639
            return Telemetry::FlightMode::Stabilized;
×
1640
        default:
1✔
1641
            return Telemetry::FlightMode::Unknown;
1✔
1642
    }
1643
}
1644

1645
Telemetry::PositionVelocityNed TelemetryImpl::position_velocity_ned() const
×
1646
{
1647
    std::lock_guard<std::mutex> lock(_position_velocity_ned_mutex);
×
1648
    return _position_velocity_ned;
×
1649
}
×
1650

1651
void TelemetryImpl::set_position_velocity_ned(Telemetry::PositionVelocityNed position_velocity_ned)
×
1652
{
1653
    std::lock_guard<std::mutex> lock(_position_velocity_ned_mutex);
×
1654
    _position_velocity_ned = position_velocity_ned;
×
1655
}
×
1656

1657
Telemetry::Position TelemetryImpl::position() const
×
1658
{
1659
    std::lock_guard<std::mutex> lock(_position_mutex);
×
1660
    return _position;
×
1661
}
×
1662

1663
void TelemetryImpl::set_position(Telemetry::Position position)
×
1664
{
1665
    std::lock_guard<std::mutex> lock(_position_mutex);
×
1666
    _position = position;
×
1667
}
×
1668

1669
Telemetry::Heading TelemetryImpl::heading() const
×
1670
{
1671
    std::lock_guard<std::mutex> lock(_heading_mutex);
×
1672
    return _heading;
×
1673
}
×
1674

1675
void TelemetryImpl::set_heading(Telemetry::Heading heading)
×
1676
{
1677
    std::lock_guard<std::mutex> lock(_heading_mutex);
×
1678
    _heading = heading;
×
1679
}
×
1680

1681
Telemetry::Altitude TelemetryImpl::altitude() const
×
1682
{
1683
    std::lock_guard<std::mutex> lock(_altitude_mutex);
×
1684
    return _altitude;
×
1685
}
×
1686

1687
void TelemetryImpl::set_altitude(Telemetry::Altitude altitude)
×
1688
{
1689
    std::lock_guard<std::mutex> lock(_altitude_mutex);
×
1690
    _altitude = altitude;
×
1691
}
×
1692

1693
Telemetry::Position TelemetryImpl::home() const
×
1694
{
1695
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
1696
    return _home_position;
×
1697
}
×
1698

1699
void TelemetryImpl::set_home_position(Telemetry::Position home_position)
×
1700
{
1701
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
1702
    _home_position = home_position;
×
1703
}
×
1704

1705
bool TelemetryImpl::armed() const
1✔
1706
{
1707
    return _armed;
1✔
1708
}
1709

1710
bool TelemetryImpl::in_air() const
×
1711
{
1712
    return _in_air;
×
1713
}
1714

1715
void TelemetryImpl::set_in_air(bool in_air_new)
×
1716
{
1717
    _in_air = in_air_new;
×
1718
}
×
1719

1720
void TelemetryImpl::set_status_text(Telemetry::StatusText status_text)
3✔
1721
{
1722
    std::lock_guard<std::mutex> lock(_status_text_mutex);
3✔
1723
    _status_text = status_text;
3✔
1724
}
3✔
1725

1726
Telemetry::StatusText TelemetryImpl::status_text() const
3✔
1727
{
1728
    std::lock_guard<std::mutex> lock(_status_text_mutex);
3✔
1729
    return _status_text;
3✔
1730
}
3✔
1731

1732
void TelemetryImpl::set_armed(bool armed_new)
1✔
1733
{
1734
    _armed = armed_new;
1✔
1735
}
1✔
1736

1737
Telemetry::Quaternion TelemetryImpl::attitude_quaternion() const
×
1738
{
1739
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1740
    return _attitude_quaternion;
×
1741
}
×
1742

1743
Telemetry::AngularVelocityBody TelemetryImpl::attitude_angular_velocity_body() const
×
1744
{
1745
    std::lock_guard<std::mutex> lock(_attitude_angular_velocity_body_mutex);
×
1746
    return _attitude_angular_velocity_body;
×
1747
}
×
1748

1749
Telemetry::GroundTruth TelemetryImpl::ground_truth() const
×
1750
{
1751
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
1752
    return _ground_truth;
×
1753
}
×
1754

1755
Telemetry::FixedwingMetrics TelemetryImpl::fixedwing_metrics() const
×
1756
{
1757
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
1758
    return _fixedwing_metrics;
×
1759
}
×
1760

1761
Telemetry::EulerAngle TelemetryImpl::attitude_euler() const
×
1762
{
1763
    std::lock_guard<std::mutex> lock(_attitude_euler_mutex);
×
1764
    return _attitude_euler;
×
1765
}
×
1766

1767
void TelemetryImpl::set_attitude_quaternion(Telemetry::Quaternion quaternion)
×
1768
{
1769
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1770
    _attitude_quaternion = quaternion;
×
1771
}
×
1772

1773
void TelemetryImpl::set_attitude_euler(Telemetry::EulerAngle euler)
×
1774
{
1775
    std::lock_guard<std::mutex> lock(_attitude_euler_mutex);
×
1776
    _attitude_euler = euler;
×
1777
}
×
1778

1779
void TelemetryImpl::set_attitude_angular_velocity_body(
×
1780
    Telemetry::AngularVelocityBody angular_velocity_body)
1781
{
1782
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1783
    _attitude_angular_velocity_body = angular_velocity_body;
×
1784
}
×
1785

1786
void TelemetryImpl::set_ground_truth(Telemetry::GroundTruth ground_truth)
×
1787
{
1788
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
1789
    _ground_truth = ground_truth;
×
1790
}
×
1791

1792
void TelemetryImpl::set_fixedwing_metrics(Telemetry::FixedwingMetrics fixedwing_metrics)
×
1793
{
1794
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
1795
    _fixedwing_metrics = fixedwing_metrics;
×
1796
}
×
1797

1798
Telemetry::VelocityNed TelemetryImpl::velocity_ned() const
×
1799
{
1800
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
1801
    return _velocity_ned;
×
1802
}
×
1803

1804
void TelemetryImpl::set_velocity_ned(Telemetry::VelocityNed velocity_ned)
×
1805
{
1806
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
1807
    _velocity_ned = velocity_ned;
×
1808
}
×
1809

1810
Telemetry::Imu TelemetryImpl::imu() const
×
1811
{
1812
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
1813
    return _imu_reading_ned;
×
1814
}
×
1815

1816
void TelemetryImpl::set_imu_reading_ned(Telemetry::Imu imu_reading_ned)
×
1817
{
1818
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
1819
    _imu_reading_ned = imu_reading_ned;
×
1820
}
×
1821

1822
Telemetry::Imu TelemetryImpl::scaled_imu() const
×
1823
{
1824
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
1825
    return _scaled_imu;
×
1826
}
×
1827

1828
void TelemetryImpl::set_scaled_imu(Telemetry::Imu scaled_imu)
×
1829
{
1830
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
1831
    _scaled_imu = scaled_imu;
×
1832
}
×
1833

1834
Telemetry::Imu TelemetryImpl::raw_imu() const
×
1835
{
1836
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
1837
    return _raw_imu;
×
1838
}
×
1839

1840
void TelemetryImpl::set_raw_imu(Telemetry::Imu raw_imu)
×
1841
{
1842
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
1843
    _raw_imu = raw_imu;
×
1844
}
×
1845

1846
Telemetry::GpsInfo TelemetryImpl::gps_info() const
×
1847
{
1848
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
×
1849
    return _gps_info;
×
1850
}
×
1851

1852
void TelemetryImpl::set_gps_info(Telemetry::GpsInfo gps_info)
×
1853
{
1854
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
×
1855
    _gps_info = gps_info;
×
1856
}
×
1857

1858
Telemetry::RawGps TelemetryImpl::raw_gps() const
×
1859
{
1860
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
×
1861
    return _raw_gps;
×
1862
}
×
1863

1864
void TelemetryImpl::set_raw_gps(Telemetry::RawGps raw_gps)
×
1865
{
1866
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
×
1867
    _raw_gps = raw_gps;
×
1868
}
×
1869

1870
Telemetry::Battery TelemetryImpl::battery() const
×
1871
{
1872
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
1873
    return _battery;
×
1874
}
×
1875

1876
void TelemetryImpl::set_battery(Telemetry::Battery battery)
×
1877
{
1878
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
1879
    _battery = battery;
×
1880
}
×
1881

1882
Telemetry::FlightMode TelemetryImpl::flight_mode() const
×
1883
{
1884
    return telemetry_flight_mode_from_flight_mode(_system_impl->get_flight_mode());
×
1885
}
1886

1887
Telemetry::Health TelemetryImpl::health() const
1✔
1888
{
1889
    std::lock_guard<std::mutex> lock(_health_mutex);
1✔
1890
    return _health;
2✔
1891
}
1✔
1892

1893
bool TelemetryImpl::health_all_ok() const
1✔
1894
{
1895
    std::lock_guard<std::mutex> lock(_health_mutex);
1✔
1896
    if (_health.is_gyrometer_calibration_ok && _health.is_accelerometer_calibration_ok &&
1✔
1897
        _health.is_magnetometer_calibration_ok && _health.is_local_position_ok &&
×
1898
        _health.is_global_position_ok && _health.is_home_position_ok) {
×
1899
        return true;
×
1900
    } else {
1901
        return false;
1✔
1902
    }
1903
}
1✔
1904

1905
Telemetry::RcStatus TelemetryImpl::rc_status() const
×
1906
{
1907
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
1908
    return _rc_status;
×
1909
}
×
1910

1911
uint64_t TelemetryImpl::unix_epoch_time() const
×
1912
{
1913
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
1914
    return _unix_epoch_time_us;
×
1915
}
×
1916

1917
Telemetry::ActuatorControlTarget TelemetryImpl::actuator_control_target() const
×
1918
{
1919
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
1920
    return _actuator_control_target;
×
1921
}
×
1922

1923
Telemetry::ActuatorOutputStatus TelemetryImpl::actuator_output_status() const
×
1924
{
1925
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
1926
    return _actuator_output_status;
×
1927
}
×
1928

1929
Telemetry::Odometry TelemetryImpl::odometry() const
×
1930
{
1931
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
1932
    return _odometry;
×
1933
}
×
1934

1935
Telemetry::DistanceSensor TelemetryImpl::distance_sensor() const
×
1936
{
1937
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
1938
    return _distance_sensor;
×
1939
}
×
1940

1941
Telemetry::ScaledPressure TelemetryImpl::scaled_pressure() const
×
1942
{
1943
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
1944
    return _scaled_pressure;
×
1945
}
×
1946

1947
void TelemetryImpl::set_health_local_position(bool ok)
×
1948
{
1949
    std::lock_guard<std::mutex> lock(_health_mutex);
×
1950
    _health.is_local_position_ok = ok;
×
1951
}
×
1952

1953
void TelemetryImpl::set_health_global_position(bool ok)
×
1954
{
1955
    std::lock_guard<std::mutex> lock(_health_mutex);
×
1956
    _health.is_global_position_ok = ok;
×
1957
}
×
1958

1959
void TelemetryImpl::set_health_home_position(bool ok)
×
1960
{
1961
    std::lock_guard<std::mutex> lock(_health_mutex);
×
1962
    _health.is_home_position_ok = ok;
×
1963
}
×
1964

1965
void TelemetryImpl::set_health_gyrometer_calibration(bool ok)
×
1966
{
1967
    std::lock_guard<std::mutex> lock(_health_mutex);
×
1968
    _health.is_gyrometer_calibration_ok = ok;
×
1969
}
×
1970

1971
void TelemetryImpl::set_health_accelerometer_calibration(bool ok)
×
1972
{
1973
    std::lock_guard<std::mutex> lock(_health_mutex);
×
1974
    _health.is_accelerometer_calibration_ok = ok;
×
1975
}
×
1976

1977
void TelemetryImpl::set_health_magnetometer_calibration(bool ok)
×
1978
{
1979
    std::lock_guard<std::mutex> lock(_health_mutex);
×
1980
    _health.is_magnetometer_calibration_ok = ok;
×
1981
}
×
1982

1983
void TelemetryImpl::set_health_armable(bool ok)
×
1984
{
1985
    std::lock_guard<std::mutex> lock(_health_mutex);
×
1986
    _health.is_armable = ok;
×
1987
}
×
1988

1989
Telemetry::VtolState TelemetryImpl::vtol_state() const
×
1990
{
1991
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
1992
    return _vtol_state;
×
1993
}
×
1994

1995
void TelemetryImpl::set_vtol_state(Telemetry::VtolState vtol_state)
×
1996
{
1997
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
1998
    _vtol_state = vtol_state;
×
1999
}
×
2000

2001
Telemetry::LandedState TelemetryImpl::landed_state() const
×
2002
{
2003
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2004
    return _landed_state;
×
2005
}
×
2006

2007
void TelemetryImpl::set_landed_state(Telemetry::LandedState landed_state)
×
2008
{
2009
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2010
    _landed_state = landed_state;
×
2011
}
×
2012

2013
void TelemetryImpl::set_rc_status(
×
2014
    std::optional<bool> maybe_available, std::optional<float> maybe_signal_strength_percent)
2015
{
2016
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
2017

2018
    if (maybe_available) {
×
2019
        _rc_status.is_available = maybe_available.value();
×
2020
        if (maybe_available.value()) {
×
2021
            _rc_status.was_available_once = true;
×
2022
        }
2023
    }
2024

2025
    if (maybe_signal_strength_percent) {
×
2026
        _rc_status.signal_strength_percent = maybe_signal_strength_percent.value();
×
2027
    }
2028
}
×
2029

2030
void TelemetryImpl::set_unix_epoch_time_us(uint64_t time_us)
×
2031
{
2032
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
2033
    _unix_epoch_time_us = time_us;
×
2034
}
×
2035

2036
void TelemetryImpl::set_actuator_control_target(uint8_t group, const std::vector<float>& controls)
×
2037
{
2038
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
2039
    _actuator_control_target.group = group;
×
2040
    _actuator_control_target.controls = controls;
×
2041
}
×
2042

2043
void TelemetryImpl::set_actuator_output_status(uint32_t active, const std::vector<float>& actuators)
×
2044
{
2045
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
2046
    _actuator_output_status.active = active;
×
2047
    _actuator_output_status.actuator = actuators;
×
2048
}
×
2049

2050
void TelemetryImpl::set_odometry(Telemetry::Odometry& odometry)
×
2051
{
2052
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
2053
    _odometry = odometry;
×
2054
}
×
2055

2056
void TelemetryImpl::set_distance_sensor(Telemetry::DistanceSensor& distance_sensor)
×
2057
{
2058
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
2059
    _distance_sensor = distance_sensor;
×
2060
}
×
2061

2062
void TelemetryImpl::set_scaled_pressure(Telemetry::ScaledPressure& scaled_pressure)
×
2063
{
2064
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
2065
    _scaled_pressure = scaled_pressure;
×
2066
}
×
2067

2068
Telemetry::PositionVelocityNedHandle TelemetryImpl::subscribe_position_velocity_ned(
×
2069
    const Telemetry::PositionVelocityNedCallback& callback)
2070
{
2071
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2072
    return _position_velocity_ned_subscriptions.subscribe(callback);
×
2073
}
×
2074

2075
void TelemetryImpl::unsubscribe_position_velocity_ned(Telemetry::PositionVelocityNedHandle handle)
×
2076
{
2077
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2078
    _position_velocity_ned_subscriptions.unsubscribe(handle);
×
2079
}
×
2080

2081
Telemetry::PositionHandle
2082
TelemetryImpl::subscribe_position(const Telemetry::PositionCallback& callback)
×
2083
{
2084
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2085
    return _position_subscriptions.subscribe(callback);
×
2086
}
×
2087

2088
void TelemetryImpl::unsubscribe_position(Telemetry::PositionHandle handle)
×
2089
{
2090
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2091
    _position_subscriptions.unsubscribe(handle);
×
2092
}
×
2093

2094
Telemetry::HomeHandle TelemetryImpl::subscribe_home(const Telemetry::PositionCallback& callback)
×
2095
{
2096
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2097
    return _home_position_subscriptions.subscribe(callback);
×
2098
}
×
2099

2100
void TelemetryImpl::unsubscribe_home(Telemetry::HomeHandle handle)
×
2101
{
2102
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2103
    _home_position_subscriptions.unsubscribe(handle);
×
2104
}
×
2105

2106
Telemetry::InAirHandle TelemetryImpl::subscribe_in_air(const Telemetry::InAirCallback& callback)
×
2107
{
2108
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2109
    return _in_air_subscriptions.subscribe(callback);
×
2110
}
×
2111

2112
void TelemetryImpl::unsubscribe_in_air(Telemetry::InAirHandle handle)
×
2113
{
2114
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2115
    return _in_air_subscriptions.unsubscribe(handle);
×
2116
}
×
2117

2118
Telemetry::StatusTextHandle
2119
TelemetryImpl::subscribe_status_text(const Telemetry::StatusTextCallback& callback)
2✔
2120
{
2121
    std::lock_guard<std::mutex> lock(_subscription_mutex);
2✔
2122
    return _status_text_subscriptions.subscribe(callback);
2✔
2123
}
2✔
2124

2125
void TelemetryImpl::unsubscribe_status_text(Handle<Telemetry::StatusText> handle)
1✔
2126
{
2127
    std::lock_guard<std::mutex> lock(_subscription_mutex);
1✔
2128
    _status_text_subscriptions.unsubscribe(handle);
1✔
2129
}
1✔
2130

2131
Telemetry::ArmedHandle TelemetryImpl::subscribe_armed(const Telemetry::ArmedCallback& callback)
×
2132
{
2133
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2134
    return _armed_subscriptions.subscribe(callback);
×
2135
}
×
2136

2137
void TelemetryImpl::unsubscribe_armed(Telemetry::ArmedHandle handle)
×
2138
{
2139
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2140
    _armed_subscriptions.unsubscribe(handle);
×
2141
}
×
2142

2143
Telemetry::AttitudeQuaternionHandle
2144
TelemetryImpl::subscribe_attitude_quaternion(const Telemetry::AttitudeQuaternionCallback& callback)
×
2145
{
2146
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2147
    return _attitude_quaternion_angle_subscriptions.subscribe(callback);
×
2148
}
×
2149

2150
void TelemetryImpl::unsubscribe_attitude_quaternion(Telemetry::AttitudeQuaternionHandle handle)
×
2151
{
2152
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2153
    _attitude_quaternion_angle_subscriptions.unsubscribe(handle);
×
2154
}
×
2155

2156
Telemetry::AttitudeEulerHandle
2157
TelemetryImpl::subscribe_attitude_euler(const Telemetry::AttitudeEulerCallback& callback)
×
2158
{
2159
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2160
    return _attitude_euler_angle_subscriptions.subscribe(callback);
×
2161
}
×
2162

2163
void TelemetryImpl::unsubscribe_attitude_euler(Telemetry::AttitudeEulerHandle handle)
×
2164
{
2165
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2166
    _attitude_euler_angle_subscriptions.unsubscribe(handle);
×
2167
}
×
2168

2169
Telemetry::AttitudeAngularVelocityBodyHandle
2170
TelemetryImpl::subscribe_attitude_angular_velocity_body(
×
2171
    const Telemetry::AttitudeAngularVelocityBodyCallback& callback)
2172
{
2173
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2174
    return _attitude_angular_velocity_body_subscriptions.subscribe(callback);
×
2175
}
×
2176

2177
void TelemetryImpl::unsubscribe_attitude_angular_velocity_body(
×
2178
    Telemetry::AttitudeAngularVelocityBodyHandle handle)
2179
{
2180
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2181
    _attitude_angular_velocity_body_subscriptions.unsubscribe(handle);
×
2182
}
×
2183

2184
Telemetry::FixedwingMetricsHandle
2185
TelemetryImpl::subscribe_fixedwing_metrics(const Telemetry::FixedwingMetricsCallback& callback)
×
2186
{
2187
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2188
    return _fixedwing_metrics_subscriptions.subscribe(callback);
×
2189
}
×
2190

2191
void TelemetryImpl::unsubscribe_fixedwing_metrics(Telemetry::FixedwingMetricsHandle handle)
×
2192
{
2193
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2194
    _fixedwing_metrics_subscriptions.unsubscribe(handle);
×
2195
}
×
2196

2197
Telemetry::GroundTruthHandle
2198
TelemetryImpl::subscribe_ground_truth(const Telemetry::GroundTruthCallback& callback)
×
2199
{
2200
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2201
    return _ground_truth_subscriptions.subscribe(callback);
×
2202
}
×
2203

2204
void TelemetryImpl::unsubscribe_ground_truth(Telemetry::GroundTruthHandle handle)
×
2205
{
2206
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2207
    _ground_truth_subscriptions.unsubscribe(handle);
×
2208
}
×
2209

2210
Telemetry::VelocityNedHandle
2211
TelemetryImpl::subscribe_velocity_ned(const Telemetry::VelocityNedCallback& callback)
×
2212
{
2213
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2214
    return _velocity_ned_subscriptions.subscribe(callback);
×
2215
}
×
2216

2217
void TelemetryImpl::unsubscribe_velocity_ned(Telemetry::VelocityNedHandle handle)
×
2218
{
2219
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2220
    _velocity_ned_subscriptions.unsubscribe(handle);
×
2221
}
×
2222

2223
Telemetry::ImuHandle TelemetryImpl::subscribe_imu(const Telemetry::ImuCallback& callback)
×
2224
{
2225
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2226
    return _imu_reading_ned_subscriptions.subscribe(callback);
×
2227
}
×
2228

2229
void TelemetryImpl::unsubscribe_imu(Telemetry::ImuHandle handle)
×
2230
{
2231
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2232
    return _imu_reading_ned_subscriptions.unsubscribe(handle);
×
2233
}
×
2234

2235
Telemetry::ScaledImuHandle
2236
TelemetryImpl::subscribe_scaled_imu(const Telemetry::ScaledImuCallback& callback)
×
2237
{
2238
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2239
    return _scaled_imu_subscriptions.subscribe(callback);
×
2240
}
×
2241

2242
void TelemetryImpl::unsubscribe_scaled_imu(Telemetry::ScaledImuHandle handle)
×
2243
{
2244
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2245
    _scaled_imu_subscriptions.unsubscribe(handle);
×
2246
}
×
2247

2248
Telemetry::RawImuHandle TelemetryImpl::subscribe_raw_imu(const Telemetry::RawImuCallback& callback)
×
2249
{
2250
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2251
    return _raw_imu_subscriptions.subscribe(callback);
×
2252
}
×
2253

2254
void TelemetryImpl::unsubscribe_raw_imu(Telemetry::RawImuHandle handle)
×
2255
{
2256
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2257
    _raw_imu_subscriptions.unsubscribe(handle);
×
2258
}
×
2259

2260
Telemetry::GpsInfoHandle
2261
TelemetryImpl::subscribe_gps_info(const Telemetry::GpsInfoCallback& callback)
×
2262
{
2263
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2264
    return _gps_info_subscriptions.subscribe(callback);
×
2265
}
×
2266

2267
void TelemetryImpl::unsubscribe_gps_info(Telemetry::GpsInfoHandle handle)
×
2268
{
2269
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2270
    _gps_info_subscriptions.unsubscribe(handle);
×
2271
}
×
2272

2273
Telemetry::RawGpsHandle TelemetryImpl::subscribe_raw_gps(const Telemetry::RawGpsCallback& callback)
×
2274
{
2275
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2276
    return _raw_gps_subscriptions.subscribe(callback);
×
2277
}
×
2278

2279
void TelemetryImpl::unsubscribe_raw_gps(Telemetry::RawGpsHandle handle)
×
2280
{
2281
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2282
    _raw_gps_subscriptions.unsubscribe(handle);
×
2283
}
×
2284

2285
Telemetry::BatteryHandle
2286
TelemetryImpl::subscribe_battery(const Telemetry::BatteryCallback& callback)
×
2287
{
2288
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2289
    return _battery_subscriptions.subscribe(callback);
×
2290
}
×
2291

2292
void TelemetryImpl::unsubscribe_battery(Telemetry::BatteryHandle handle)
×
2293
{
2294
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2295
    _battery_subscriptions.unsubscribe(handle);
×
2296
}
×
2297

2298
Telemetry::FlightModeHandle
2299
TelemetryImpl::subscribe_flight_mode(const Telemetry::FlightModeCallback& callback)
×
2300
{
2301
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2302
    return _flight_mode_subscriptions.subscribe(callback);
×
2303
}
×
2304

2305
void TelemetryImpl::unsubscribe_flight_mode(Telemetry::FlightModeHandle handle)
×
2306
{
2307
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2308
    _flight_mode_subscriptions.unsubscribe(handle);
×
2309
}
×
2310

2311
Telemetry::HealthHandle TelemetryImpl::subscribe_health(const Telemetry::HealthCallback& callback)
×
2312
{
2313
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2314
    return _health_subscriptions.subscribe(callback);
×
2315
}
×
2316

2317
void TelemetryImpl::unsubscribe_health(Telemetry::HealthHandle handle)
×
2318
{
2319
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2320
    _health_subscriptions.unsubscribe(handle);
×
2321
}
×
2322

2323
Telemetry::HealthAllOkHandle
2324
TelemetryImpl::subscribe_health_all_ok(const Telemetry::HealthAllOkCallback& callback)
×
2325
{
2326
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2327
    return _health_all_ok_subscriptions.subscribe(callback);
×
2328
}
×
2329

2330
void TelemetryImpl::unsubscribe_health_all_ok(Telemetry::HealthAllOkHandle handle)
×
2331
{
2332
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2333
    _health_all_ok_subscriptions.unsubscribe(handle);
×
2334
}
×
2335

2336
Telemetry::VtolStateHandle
2337
TelemetryImpl::subscribe_vtol_state(const Telemetry::VtolStateCallback& callback)
×
2338
{
2339
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2340
    return _vtol_state_subscriptions.subscribe(callback);
×
2341
}
×
2342

2343
void TelemetryImpl::unsubscribe_vtol_state(Telemetry::VtolStateHandle handle)
×
2344
{
2345
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2346
    _vtol_state_subscriptions.unsubscribe(handle);
×
2347
}
×
2348

2349
Telemetry::LandedStateHandle
2350
TelemetryImpl::subscribe_landed_state(const Telemetry::LandedStateCallback& callback)
×
2351
{
2352
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2353
    return _landed_state_subscriptions.subscribe(callback);
×
2354
}
×
2355

2356
void TelemetryImpl::unsubscribe_landed_state(Telemetry::LandedStateHandle handle)
×
2357
{
2358
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2359
    _landed_state_subscriptions.unsubscribe(handle);
×
2360
}
×
2361

2362
Telemetry::RcStatusHandle
2363
TelemetryImpl::subscribe_rc_status(const Telemetry::RcStatusCallback& callback)
×
2364
{
2365
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2366
    return _rc_status_subscriptions.subscribe(callback);
×
2367
}
×
2368

2369
void TelemetryImpl::unsubscribe_rc_status(Telemetry::RcStatusHandle handle)
×
2370
{
2371
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2372
    _rc_status_subscriptions.unsubscribe(handle);
×
2373
}
×
2374

2375
Telemetry::UnixEpochTimeHandle
2376
TelemetryImpl::subscribe_unix_epoch_time(const Telemetry::UnixEpochTimeCallback& callback)
×
2377
{
2378
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2379
    return _unix_epoch_time_subscriptions.subscribe(callback);
×
2380
}
×
2381

2382
void TelemetryImpl::unsubscribe_unix_epoch_time(Telemetry::UnixEpochTimeHandle handle)
×
2383
{
2384
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2385
    _unix_epoch_time_subscriptions.unsubscribe(handle);
×
2386
}
×
2387

2388
Telemetry::ActuatorControlTargetHandle TelemetryImpl::subscribe_actuator_control_target(
×
2389
    const Telemetry::ActuatorControlTargetCallback& callback)
2390
{
2391
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2392
    return _actuator_control_target_subscriptions.subscribe(callback);
×
2393
}
×
2394

2395
void TelemetryImpl::unsubscribe_actuator_control_target(
×
2396
    Telemetry::ActuatorControlTargetHandle handle)
2397
{
2398
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2399
    _actuator_control_target_subscriptions.unsubscribe(handle);
×
2400
}
×
2401

2402
Telemetry::ActuatorOutputStatusHandle TelemetryImpl::subscribe_actuator_output_status(
×
2403
    const Telemetry::ActuatorOutputStatusCallback& callback)
2404
{
2405
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2406
    return _actuator_output_status_subscriptions.subscribe(callback);
×
2407
}
×
2408

2409
void TelemetryImpl::unsubscribe_actuator_output_status(Telemetry::ActuatorOutputStatusHandle handle)
×
2410
{
2411
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2412
    _actuator_output_status_subscriptions.unsubscribe(handle);
×
2413
}
×
2414

2415
Telemetry::OdometryHandle
2416
TelemetryImpl::subscribe_odometry(const Telemetry::OdometryCallback& callback)
×
2417
{
2418
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2419
    return _odometry_subscriptions.subscribe(callback);
×
2420
}
×
2421

2422
void TelemetryImpl::unsubscribe_odometry(Telemetry::OdometryHandle handle)
×
2423
{
2424
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2425
    _odometry_subscriptions.unsubscribe(handle);
×
2426
}
×
2427

2428
Telemetry::DistanceSensorHandle
2429
TelemetryImpl::subscribe_distance_sensor(const Telemetry::DistanceSensorCallback& callback)
×
2430
{
2431
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2432
    return _distance_sensor_subscriptions.subscribe(callback);
×
2433
}
×
2434

2435
void TelemetryImpl::unsubscribe_distance_sensor(Telemetry::DistanceSensorHandle handle)
×
2436
{
2437
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2438
    _distance_sensor_subscriptions.unsubscribe(handle);
×
2439
}
×
2440

2441
Telemetry::ScaledPressureHandle
2442
TelemetryImpl::subscribe_scaled_pressure(const Telemetry::ScaledPressureCallback& callback)
×
2443
{
2444
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2445
    return _scaled_pressure_subscriptions.subscribe(callback);
×
2446
}
×
2447

2448
void TelemetryImpl::unsubscribe_scaled_pressure(Telemetry::ScaledPressureHandle handle)
×
2449
{
2450
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2451
    _scaled_pressure_subscriptions.unsubscribe(handle);
×
2452
}
×
2453

2454
Telemetry::HeadingHandle
2455
TelemetryImpl::subscribe_heading(const Telemetry::HeadingCallback& callback)
×
2456
{
2457
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2458
    return _heading_subscriptions.subscribe(callback);
×
2459
}
×
2460

2461
void TelemetryImpl::unsubscribe_heading(Telemetry::HeadingHandle handle)
×
2462
{
2463
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2464
    _heading_subscriptions.unsubscribe(handle);
×
2465
}
×
2466

2467
Telemetry::AltitudeHandle
2468
TelemetryImpl::subscribe_altitude(const Telemetry::AltitudeCallback& callback)
×
2469
{
2470
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2471
    return _altitude_subscriptions.subscribe(callback);
×
2472
}
×
2473

2474
void TelemetryImpl::unsubscribe_altitude(Telemetry::AltitudeHandle handle)
×
2475
{
2476
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2477
    _altitude_subscriptions.unsubscribe(handle);
×
2478
}
×
2479

2480
void TelemetryImpl::get_gps_global_origin_async(
×
2481
    const Telemetry::GetGpsGlobalOriginCallback callback)
2482
{
2483
    _system_impl->mavlink_request_message().request(
×
2484
        MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN,
2485
        MAV_COMP_ID_AUTOPILOT1,
2486
        [this, callback](MavlinkCommandSender::Result result, const mavlink_message_t& message) {
×
2487
            if (result == MavlinkCommandSender::Result::Success) {
×
2488
                mavlink_gps_global_origin_t mavlink_gps_global_origin;
×
2489
                mavlink_msg_gps_global_origin_decode(&message, &mavlink_gps_global_origin);
×
2490

2491
                Telemetry::GpsGlobalOrigin gps_global_origin;
×
2492
                gps_global_origin.latitude_deg = mavlink_gps_global_origin.latitude * 1e-7;
×
2493
                gps_global_origin.longitude_deg = mavlink_gps_global_origin.longitude * 1e-7;
×
2494
                gps_global_origin.altitude_m = mavlink_gps_global_origin.altitude * 1e-3f;
×
2495
                _system_impl->call_user_callback([callback, gps_global_origin]() {
×
2496
                    callback(Telemetry::Result::Success, gps_global_origin);
2497
                });
2498

2499
            } else {
2500
                _system_impl->call_user_callback([callback, result]() {
×
2501
                    callback(telemetry_result_from_command_result(result), {});
2502
                });
2503
            }
2504
        });
×
2505
}
×
2506

2507
std::pair<Telemetry::Result, Telemetry::GpsGlobalOrigin> TelemetryImpl::get_gps_global_origin()
×
2508
{
2509
    auto prom = std::promise<std::pair<Telemetry::Result, Telemetry::GpsGlobalOrigin>>();
×
2510
    auto fut = prom.get_future();
×
2511

2512
    get_gps_global_origin_async(
×
2513
        [&prom](Telemetry::Result result, Telemetry::GpsGlobalOrigin gps_global_origin) {
×
2514
            prom.set_value(std::make_pair(result, gps_global_origin));
×
2515
        });
×
2516
    return fut.get();
×
2517
}
×
2518

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