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

mavlink / MAVSDK / 14141487007

29 Mar 2025 02:55AM UTC coverage: 44.301% (-0.04%) from 44.344%
14141487007

Pull #2530

github

web-flow
Merge e3b31e283 into c4a070f97
Pull Request #2530: telem: remove periodic request HOME_POSITION

1 of 2 new or added lines in 1 file covered. (50.0%)

12 existing lines in 2 files now uncovered.

14580 of 32911 relevant lines covered (44.3%)

283.07 hits per line

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

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

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

13
namespace mavsdk {
14

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

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

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

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

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

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

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

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

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

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

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

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

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

106
    _system_impl->register_mavlink_message_handler(
1✔
107
        MAVLINK_MSG_ID_HEARTBEAT,
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_mavlink_message_handler(
1✔
177
        MAVLINK_MSG_ID_WIND_COV,
178
        [this](const mavlink_message_t& message) { process_wind(message); },
×
179
        this);
180

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

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

194
void TelemetryImpl::enable() {}
1✔
195

196
void TelemetryImpl::disable() {}
1✔
197

198
Telemetry::Result TelemetryImpl::set_rate_position_velocity_ned(double rate_hz)
×
199
{
200
    return telemetry_result_from_command_result(
×
NEW
201
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_LOCAL_POSITION_NED, rate_hz));
×
202
}
203

204
Telemetry::Result TelemetryImpl::set_rate_position(double rate_hz)
×
205
{
206
    _position_rate_hz = rate_hz;
×
207
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
208

209
    return telemetry_result_from_command_result(
×
210
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, max_rate_hz));
×
211
}
212

213
Telemetry::Result TelemetryImpl::set_rate_home(double rate_hz)
×
214
{
215
    return telemetry_result_from_command_result(
×
216
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_HOME_POSITION, rate_hz));
×
217
}
218

219
Telemetry::Result TelemetryImpl::set_rate_in_air(double rate_hz)
×
220
{
221
    return set_rate_landed_state(rate_hz);
×
222
}
223

224
Telemetry::Result TelemetryImpl::set_rate_vtol_state(double rate_hz)
×
225
{
226
    return set_rate_landed_state(rate_hz);
×
227
}
228

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

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

241
Telemetry::Result TelemetryImpl::set_rate_attitude_euler(double rate_hz)
×
242
{
243
    return telemetry_result_from_command_result(
×
244
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_ATTITUDE, rate_hz));
×
245
}
246

247
Telemetry::Result TelemetryImpl::set_rate_velocity_ned(double rate_hz)
×
248
{
249
    _velocity_ned_rate_hz = rate_hz;
×
250
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
251

252
    return telemetry_result_from_command_result(
×
253
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, max_rate_hz));
×
254
}
255

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

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

268
Telemetry::Result TelemetryImpl::set_rate_raw_imu(double rate_hz)
×
269
{
270
    return telemetry_result_from_command_result(
×
271
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_RAW_IMU, rate_hz));
×
272
}
273

274
Telemetry::Result TelemetryImpl::set_rate_fixedwing_metrics(double rate_hz)
×
275
{
276
    return telemetry_result_from_command_result(
×
277
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_VFR_HUD, rate_hz));
×
278
}
279

280
Telemetry::Result TelemetryImpl::set_rate_ground_truth(double rate_hz)
×
281
{
282
    return telemetry_result_from_command_result(
×
283
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_HIL_STATE_QUATERNION, rate_hz));
×
284
}
285

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

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

298
Telemetry::Result TelemetryImpl::set_rate_rc_status(double rate_hz)
×
299
{
300
    UNUSED(rate_hz);
×
301
    LogWarn() << "System status is usually fixed at 1 Hz";
×
302
    return Telemetry::Result::Unsupported;
×
303
}
304

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

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

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

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

329
Telemetry::Result TelemetryImpl::set_rate_scaled_pressure(double rate_hz)
×
330
{
331
    return telemetry_result_from_command_result(
×
332
        _system_impl->set_msg_rate(MAVLINK_MSG_ID_SCALED_PRESSURE, rate_hz));
×
333
}
334

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

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

347
void TelemetryImpl::set_rate_position_velocity_ned_async(
×
348
    double rate_hz, Telemetry::ResultCallback callback)
349
{
350
    _system_impl->set_msg_rate_async(
×
351
        MAVLINK_MSG_ID_LOCAL_POSITION_NED,
352
        rate_hz,
353
        [callback](MavlinkCommandSender::Result command_result, float) {
×
354
            command_result_callback(command_result, callback);
×
355
        });
×
356
}
×
357

358
void TelemetryImpl::set_rate_position_async(double rate_hz, Telemetry::ResultCallback callback)
×
359
{
360
    _position_rate_hz = rate_hz;
×
361
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
362

363
    _system_impl->set_msg_rate_async(
×
364
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
365
        max_rate_hz,
366
        [callback](MavlinkCommandSender::Result command_result, float) {
×
367
            command_result_callback(command_result, callback);
×
368
        });
×
369
}
×
370

371
void TelemetryImpl::set_rate_home_async(double rate_hz, Telemetry::ResultCallback callback)
×
372
{
373
    _system_impl->set_msg_rate_async(
×
374
        MAVLINK_MSG_ID_HOME_POSITION,
375
        rate_hz,
376
        [callback](MavlinkCommandSender::Result command_result, float) {
×
377
            command_result_callback(command_result, callback);
×
378
        });
×
379
}
×
380

381
void TelemetryImpl::set_rate_in_air_async(double rate_hz, Telemetry::ResultCallback callback)
×
382
{
383
    set_rate_landed_state_async(rate_hz, callback);
×
384
}
×
385

386
void TelemetryImpl::set_rate_vtol_state_async(double rate_hz, Telemetry::ResultCallback callback)
×
387
{
388
    set_rate_landed_state_async(rate_hz, callback);
×
389
}
×
390

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

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

411
void TelemetryImpl::set_rate_attitude_quaternion_async(
×
412
    double rate_hz, Telemetry::ResultCallback callback)
413
{
414
    _system_impl->set_msg_rate_async(
×
415
        MAVLINK_MSG_ID_ATTITUDE_QUATERNION,
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_attitude_euler_async(
×
423
    double rate_hz, Telemetry::ResultCallback callback)
424
{
425
    _system_impl->set_msg_rate_async(
×
426
        MAVLINK_MSG_ID_ATTITUDE,
427
        rate_hz,
428
        [callback](MavlinkCommandSender::Result command_result, float) {
×
429
            command_result_callback(command_result, callback);
×
430
        });
×
431
}
×
432

433
void TelemetryImpl::set_rate_velocity_ned_async(double rate_hz, Telemetry::ResultCallback callback)
×
434
{
435
    _velocity_ned_rate_hz = rate_hz;
×
436
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
437

438
    _system_impl->set_msg_rate_async(
×
439
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
440
        max_rate_hz,
441
        [callback](MavlinkCommandSender::Result command_result, float) {
×
442
            command_result_callback(command_result, callback);
×
443
        });
×
444
}
×
445

446
void TelemetryImpl::set_rate_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
447
{
448
    _system_impl->set_msg_rate_async(
×
449
        MAVLINK_MSG_ID_HIGHRES_IMU,
450
        rate_hz,
451
        [callback](MavlinkCommandSender::Result command_result, float) {
×
452
            command_result_callback(command_result, callback);
×
453
        });
×
454
}
×
455

456
void TelemetryImpl::set_rate_scaled_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
457
{
458
    _system_impl->set_msg_rate_async(
×
459
        MAVLINK_MSG_ID_SCALED_IMU,
460
        rate_hz,
461
        [callback](MavlinkCommandSender::Result command_result, float) {
×
462
            command_result_callback(command_result, callback);
×
463
        });
×
464
}
×
465

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

476
void TelemetryImpl::set_rate_fixedwing_metrics_async(
×
477
    double rate_hz, Telemetry::ResultCallback callback)
478
{
479
    _system_impl->set_msg_rate_async(
×
480
        MAVLINK_MSG_ID_VFR_HUD,
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_ground_truth_async(double rate_hz, Telemetry::ResultCallback callback)
×
488
{
489
    _system_impl->set_msg_rate_async(
×
490
        MAVLINK_MSG_ID_HIL_STATE_QUATERNION,
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_gps_info_async(double rate_hz, Telemetry::ResultCallback callback)
×
498
{
499
    _system_impl->set_msg_rate_async(
×
500
        MAVLINK_MSG_ID_GPS_RAW_INT,
501
        rate_hz,
502
        [callback](MavlinkCommandSender::Result command_result, float) {
×
503
            command_result_callback(command_result, callback);
×
504
        });
×
505
}
×
506

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

517
void TelemetryImpl::set_rate_rc_status_async(double rate_hz, Telemetry::ResultCallback callback)
×
518
{
519
    UNUSED(rate_hz);
×
520
    LogWarn() << "System status is usually fixed at 1 Hz";
×
521
    _system_impl->call_user_callback([callback]() { callback(Telemetry::Result::Unsupported); });
×
522
}
×
523

524
void TelemetryImpl::set_rate_unix_epoch_time_async(
×
525
    double rate_hz, Telemetry::ResultCallback callback)
526
{
527
    _system_impl->set_msg_rate_async(
×
528
        MAVLINK_MSG_ID_UTM_GLOBAL_POSITION,
529
        rate_hz,
530
        [callback](MavlinkCommandSender::Result command_result, float) {
×
531
            command_result_callback(command_result, callback);
×
532
        });
×
533
}
×
534

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

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

557
void TelemetryImpl::set_rate_odometry_async(double rate_hz, Telemetry::ResultCallback callback)
×
558
{
559
    _system_impl->set_msg_rate_async(
×
560
        MAVLINK_MSG_ID_ODOMETRY,
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_distance_sensor_async(
×
568
    double rate_hz, Telemetry::ResultCallback callback)
569
{
570
    _system_impl->set_msg_rate_async(
×
571
        MAVLINK_MSG_ID_DISTANCE_SENSOR,
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_scaled_pressure_async(
×
579
    double rate_hz, Telemetry::ResultCallback callback)
580
{
581
    _system_impl->set_msg_rate_async(
×
582
        MAVLINK_MSG_ID_SCALED_PRESSURE,
583
        rate_hz,
584
        [callback](MavlinkCommandSender::Result command_result, float) {
×
585
            command_result_callback(command_result, callback);
×
586
        });
×
587
}
×
588

589
Telemetry::Result
590
TelemetryImpl::telemetry_result_from_command_result(MavlinkCommandSender::Result command_result)
×
591
{
592
    switch (command_result) {
×
593
        case MavlinkCommandSender::Result::Success:
×
594
            return Telemetry::Result::Success;
×
595
        case MavlinkCommandSender::Result::NoSystem:
×
596
            return Telemetry::Result::NoSystem;
×
597
        case MavlinkCommandSender::Result::ConnectionError:
×
598
            return Telemetry::Result::ConnectionError;
×
599
        case MavlinkCommandSender::Result::Busy:
×
600
            return Telemetry::Result::Busy;
×
601
        case MavlinkCommandSender::Result::Denied:
×
602
            // FALLTHROUGH
603
        case MavlinkCommandSender::Result::TemporarilyRejected:
604
            return Telemetry::Result::CommandDenied;
×
605
        case MavlinkCommandSender::Result::Timeout:
×
606
            return Telemetry::Result::Timeout;
×
607
        case MavlinkCommandSender::Result::Unsupported:
×
608
            return Telemetry::Result::Unsupported;
×
609
        default:
×
610
            return Telemetry::Result::Unknown;
×
611
    }
612
}
613

614
void TelemetryImpl::command_result_callback(
×
615
    MavlinkCommandSender::Result command_result, const Telemetry::ResultCallback& callback)
616
{
617
    Telemetry::Result action_result = telemetry_result_from_command_result(command_result);
×
618

619
    callback(action_result);
×
620
}
×
621

622
void TelemetryImpl::process_position_velocity_ned(const mavlink_message_t& message)
×
623
{
624
    mavlink_local_position_ned_t local_position;
×
625
    mavlink_msg_local_position_ned_decode(&message, &local_position);
×
626

627
    Telemetry::PositionVelocityNed position_velocity;
×
628
    position_velocity.position.north_m = local_position.x;
×
629
    position_velocity.position.east_m = local_position.y;
×
630
    position_velocity.position.down_m = local_position.z;
×
631
    position_velocity.velocity.north_m_s = local_position.vx;
×
632
    position_velocity.velocity.east_m_s = local_position.vy;
×
633
    position_velocity.velocity.down_m_s = local_position.vz;
×
634

635
    set_position_velocity_ned(position_velocity);
×
636

637
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
638
    _position_velocity_ned_subscriptions.queue(position_velocity_ned(), [this](const auto& func) {
×
639
        _system_impl->call_user_callback(func);
×
640
    });
×
641

642
    set_health_local_position(true);
×
643
}
×
644

645
void TelemetryImpl::process_global_position_int(const mavlink_message_t& message)
×
646
{
647
    mavlink_global_position_int_t global_position_int;
×
648
    mavlink_msg_global_position_int_decode(&message, &global_position_int);
×
649

650
    {
651
        Telemetry::Position position;
×
652
        position.latitude_deg = global_position_int.lat * 1e-7;
×
653
        position.longitude_deg = global_position_int.lon * 1e-7;
×
654
        position.absolute_altitude_m = global_position_int.alt * 1e-3f;
×
655
        position.relative_altitude_m = global_position_int.relative_alt * 1e-3f;
×
656
        set_position(position);
×
657
    }
658

659
    {
660
        Telemetry::VelocityNed velocity;
×
661
        velocity.north_m_s = global_position_int.vx * 1e-2f;
×
662
        velocity.east_m_s = global_position_int.vy * 1e-2f;
×
663
        velocity.down_m_s = global_position_int.vz * 1e-2f;
×
664
        set_velocity_ned(velocity);
×
665
    }
666

667
    {
668
        Telemetry::Heading heading;
×
669
        heading.heading_deg = (global_position_int.hdg != std::numeric_limits<uint16_t>::max()) ?
×
670
                                  static_cast<double>(global_position_int.hdg) * 1e-2 :
×
671
                                  static_cast<double>(NAN);
672
        set_heading(heading);
×
673
    }
674

675
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
676
    _position_subscriptions.queue(
×
677
        position(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
678

679
    _velocity_ned_subscriptions.queue(
×
680
        velocity_ned(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
681

682
    _heading_subscriptions.queue(
×
683
        heading(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
684
}
×
685

686
void TelemetryImpl::process_home_position(const mavlink_message_t& message)
×
687
{
688
    mavlink_home_position_t home_position;
×
689
    mavlink_msg_home_position_decode(&message, &home_position);
×
690
    Telemetry::Position new_pos;
×
691
    new_pos.latitude_deg = home_position.latitude * 1e-7;
×
692
    new_pos.longitude_deg = home_position.longitude * 1e-7;
×
693
    new_pos.absolute_altitude_m = home_position.altitude * 1e-3f;
×
694
    new_pos.relative_altitude_m = 0.0f; // 0 by definition.
×
695

696
    set_home_position(new_pos);
×
697

698
    set_health_home_position(true);
×
699

700
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
701
    _home_position_subscriptions.queue(
×
702
        home(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
703
}
×
704

705
void TelemetryImpl::process_attitude(const mavlink_message_t& message)
×
706
{
707
    mavlink_attitude_t attitude;
×
708
    mavlink_msg_attitude_decode(&message, &attitude);
×
709

710
    Telemetry::EulerAngle euler_angle;
×
711
    euler_angle.roll_deg = to_deg_from_rad(attitude.roll);
×
712
    euler_angle.pitch_deg = to_deg_from_rad(attitude.pitch);
×
713
    euler_angle.yaw_deg = to_deg_from_rad(attitude.yaw);
×
714
    euler_angle.timestamp_us = static_cast<uint64_t>(attitude.time_boot_ms) * 1000;
×
715
    set_attitude_euler(euler_angle);
×
716

717
    Telemetry::AngularVelocityBody angular_velocity_body;
×
718
    angular_velocity_body.roll_rad_s = attitude.rollspeed;
×
719
    angular_velocity_body.pitch_rad_s = attitude.pitchspeed;
×
720
    angular_velocity_body.yaw_rad_s = attitude.yawspeed;
×
721
    set_attitude_angular_velocity_body(angular_velocity_body);
×
722

723
    _attitude_euler_angle_subscriptions.queue(
×
724
        attitude_euler(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
725

726
    _attitude_angular_velocity_body_subscriptions.queue(
×
727
        attitude_angular_velocity_body(),
728
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
729
}
×
730

731
void TelemetryImpl::process_attitude_quaternion(const mavlink_message_t& message)
×
732
{
733
    mavlink_attitude_quaternion_t mavlink_attitude_quaternion;
×
734
    mavlink_msg_attitude_quaternion_decode(&message, &mavlink_attitude_quaternion);
×
735

736
    Telemetry::Quaternion quaternion;
×
737
    quaternion.w = mavlink_attitude_quaternion.q1;
×
738
    quaternion.x = mavlink_attitude_quaternion.q2;
×
739
    quaternion.y = mavlink_attitude_quaternion.q3;
×
740
    quaternion.z = mavlink_attitude_quaternion.q4;
×
741
    quaternion.timestamp_us =
×
742
        static_cast<uint64_t>(mavlink_attitude_quaternion.time_boot_ms) * 1000;
×
743

744
    Telemetry::AngularVelocityBody angular_velocity_body;
×
745
    angular_velocity_body.roll_rad_s = mavlink_attitude_quaternion.rollspeed;
×
746
    angular_velocity_body.pitch_rad_s = mavlink_attitude_quaternion.pitchspeed;
×
747
    angular_velocity_body.yaw_rad_s = mavlink_attitude_quaternion.yawspeed;
×
748

749
    set_attitude_quaternion(quaternion);
×
750

751
    set_attitude_angular_velocity_body(angular_velocity_body);
×
752

753
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
754
    _attitude_quaternion_angle_subscriptions.queue(attitude_quaternion(), [this](const auto& func) {
×
755
        _system_impl->call_user_callback(func);
×
756
    });
×
757

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

763
void TelemetryImpl::process_altitude(const mavlink_message_t& message)
×
764
{
765
    mavlink_altitude_t mavlink_altitude;
×
766
    mavlink_msg_altitude_decode(&message, &mavlink_altitude);
×
767

768
    Telemetry::Altitude new_altitude;
×
769
    new_altitude.altitude_monotonic_m = mavlink_altitude.altitude_monotonic;
×
770
    new_altitude.altitude_amsl_m = mavlink_altitude.altitude_amsl;
×
771
    new_altitude.altitude_local_m = mavlink_altitude.altitude_local;
×
772
    new_altitude.altitude_relative_m = mavlink_altitude.altitude_relative;
×
773
    new_altitude.altitude_terrain_m = mavlink_altitude.altitude_terrain;
×
774
    new_altitude.bottom_clearance_m = mavlink_altitude.bottom_clearance;
×
775

776
    set_altitude(new_altitude);
×
777

778
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
779
    _altitude_subscriptions.queue(
×
780
        altitude(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
781
}
×
782

783
void TelemetryImpl::process_wind(const mavlink_message_t& message)
×
784
{
785
    __mavlink_wind_cov_t mavlink_wind_cov;
×
786
    mavlink_msg_wind_cov_decode(&message, &mavlink_wind_cov);
×
787

788
    Telemetry::Wind new_wind;
×
789
    new_wind.wind_x_ned_m_s = mavlink_wind_cov.wind_x;
×
790
    new_wind.wind_y_ned_m_s = mavlink_wind_cov.wind_y;
×
791
    new_wind.wind_z_ned_m_s = mavlink_wind_cov.wind_z;
×
792
    new_wind.horizontal_variability_stddev_m_s = mavlink_wind_cov.var_horiz;
×
793
    new_wind.vertical_variability_stddev_m_s = mavlink_wind_cov.var_vert;
×
794
    new_wind.wind_altitude_msl_m = mavlink_wind_cov.wind_alt;
×
795
    new_wind.horizontal_wind_speed_accuracy_m_s = mavlink_wind_cov.horiz_accuracy;
×
796
    new_wind.vertical_wind_speed_accuracy_m_s = mavlink_wind_cov.vert_accuracy;
×
797

798
    set_wind(new_wind);
×
799

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

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

822
    set_imu_reading_ned(new_imu);
×
823

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

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

846
    set_scaled_imu(new_imu);
×
847

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

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

870
    set_raw_imu(new_imu);
×
871

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

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

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

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

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

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

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

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

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

953
    set_ground_truth(new_ground_truth);
×
954

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

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

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

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

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

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

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

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

997
    Telemetry::FixedwingMetrics new_fixedwing_metrics;
×
998
    new_fixedwing_metrics.airspeed_m_s = vfr_hud.airspeed;
×
999
    new_fixedwing_metrics.groundspeed_m_s = vfr_hud.groundspeed;
×
1000
    new_fixedwing_metrics.heading_deg = vfr_hud.heading;
×
1001
    new_fixedwing_metrics.throttle_percentage = vfr_hud.throttle * 1e-2f;
×
1002
    new_fixedwing_metrics.absolute_altitude_m = vfr_hud.alt;
×
1003
    new_fixedwing_metrics.climb_rate_m_s = vfr_hud.climb;
×
1004

1005
    set_fixedwing_metrics(new_fixedwing_metrics);
×
1006

1007
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1008
    _fixedwing_metrics_subscriptions.queue(
×
1009
        fixedwing_metrics(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1010
}
×
1011

1012
void TelemetryImpl::process_sys_status(const mavlink_message_t& message)
×
1013
{
1014
    mavlink_sys_status_t sys_status;
×
1015
    mavlink_msg_sys_status_decode(&message, &sys_status);
×
1016

1017
    if (!_has_bat_status) {
×
1018
        Telemetry::Battery new_battery;
×
1019
        new_battery.voltage_v = sys_status.voltage_battery * 1e-3f;
×
1020
        new_battery.remaining_percent = sys_status.battery_remaining;
×
1021

1022
        set_battery(new_battery);
×
1023

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

1031
    const bool rc_ok =
×
1032
        sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
×
1033

1034
    set_rc_status({rc_ok}, std::nullopt);
×
1035

1036
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_GYRO) {
×
1037
        set_health_gyrometer_calibration(
×
1038
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_GYRO);
×
1039
    }
1040

1041
    // PX4 v1.15.3 and previous has the bug that it doesn't set 3D_ACCEL present.
1042
    // Therefore, we ignore that and look at the health flag only.
1043
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_ACCEL ||
×
1044
        _system_impl->autopilot() == Autopilot::Px4) {
×
1045
        set_health_accelerometer_calibration(
×
1046
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_ACCEL);
×
1047
    }
1048

1049
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_MAG) {
×
1050
        set_health_magnetometer_calibration(
×
1051
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_MAG);
×
1052
    }
1053

1054
    const bool global_position_ok =
1055
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_GPS);
×
1056

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

1060
    const bool local_position_ok =
1061
        global_position_ok ||
×
1062
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW) ||
×
1063
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_VISION_POSITION);
×
1064

1065
    set_health_local_position(local_position_ok);
×
1066
    set_health_global_position(global_position_ok);
×
1067

1068
    set_rc_status({rc_ok}, std::nullopt);
×
1069

1070
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1071
    _rc_status_subscriptions.queue(
×
1072
        rc_status(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1073

1074
    const bool armable = sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_PREARM_CHECK;
×
1075
    set_health_armable(armable);
×
1076
    _health_all_ok_subscriptions.queue(
×
1077
        health_all_ok(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1078
}
×
1079

1080
bool TelemetryImpl::sys_status_present_enabled_health(
×
1081
    const mavlink_sys_status_t& sys_status, MAV_SYS_STATUS_SENSOR flag)
1082
{
1083
    // FIXME: it doesn't look like PX4 sets enabled for GPS
1084
    return (sys_status.onboard_control_sensors_present & flag) != 0 &&
×
1085
           // (sys_status.onboard_control_sensors_enabled & flag) != 0 &&
1086
           (sys_status.onboard_control_sensors_health & flag) != 0;
×
1087
}
1088

1089
void TelemetryImpl::process_battery_status(const mavlink_message_t& message)
×
1090
{
1091
    mavlink_battery_status_t bat_status;
×
1092
    mavlink_msg_battery_status_decode(&message, &bat_status);
×
1093

1094
    _has_bat_status = true;
×
1095

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

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

1121
    new_battery.remaining_percent = bat_status.battery_remaining;
×
1122
    new_battery.current_battery_a = (bat_status.current_battery == -1) ?
×
1123
                                        static_cast<float>(NAN) :
1124
                                        bat_status.current_battery * 1e-2f; // cA to A
×
1125
    new_battery.capacity_consumed_ah = (bat_status.current_consumed == -1) ?
×
1126
                                           static_cast<float>(NAN) :
1127
                                           bat_status.current_consumed * 1e-3f; // mAh to Ah
×
1128

1129
    set_battery(new_battery);
×
1130

1131
    {
1132
        std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1133
        _battery_subscriptions.queue(
×
1134
            battery(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1135
    }
×
1136
}
×
1137

1138
void TelemetryImpl::process_heartbeat(const mavlink_message_t& message)
1✔
1139
{
1140
    if (message.compid != MAV_COMP_ID_AUTOPILOT1) {
1✔
1141
        return;
×
1142
    }
1143

1144
    mavlink_heartbeat_t heartbeat;
1✔
1145
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
1✔
1146

1147
    set_armed(((heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) ? true : false));
1✔
1148

1149
    std::lock_guard<std::mutex> lock(_subscription_mutex);
1✔
1150
    _armed_subscriptions.queue(
2✔
1151
        armed(), [this](const auto& func) { _system_impl->call_user_callback(func); });
1✔
1152

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

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

1160
    _health_all_ok_subscriptions.queue(
2✔
1161
        health_all_ok(), [this](const auto& func) { _system_impl->call_user_callback(func); });
1✔
1162
}
1✔
1163

1164
void TelemetryImpl::receive_statustext(const MavlinkStatustextHandler::Statustext& statustext)
3✔
1165
{
1166
    Telemetry::StatusText new_status_text;
3✔
1167

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

1199
    new_status_text.text = statustext.text;
3✔
1200

1201
    set_status_text(new_status_text);
3✔
1202

1203
    std::lock_guard<std::mutex> lock(_subscription_mutex);
6✔
1204
    _status_text_subscriptions.queue(
9✔
1205
        status_text(), [this](const auto& func) { _system_impl->call_user_callback(func); });
11✔
1206
}
3✔
1207

1208
void TelemetryImpl::process_rc_channels(const mavlink_message_t& message)
×
1209
{
1210
    mavlink_rc_channels_t rc_channels;
×
1211
    mavlink_msg_rc_channels_decode(&message, &rc_channels);
×
1212

1213
    if (rc_channels.rssi != std::numeric_limits<uint8_t>::max()) {
×
1214
        set_rc_status(std::nullopt, {rc_channels.rssi});
×
1215
    }
1216

1217
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1218
    _rc_status_subscriptions.queue(
×
1219
        rc_status(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1220
}
×
1221

1222
void TelemetryImpl::process_unix_epoch_time(const mavlink_message_t& message)
×
1223
{
1224
    mavlink_system_time_t system_time;
×
1225
    mavlink_msg_system_time_decode(&message, &system_time);
×
1226

1227
    set_unix_epoch_time_us(system_time.time_unix_usec);
×
1228

1229
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1230
    _unix_epoch_time_subscriptions.queue(
×
1231
        unix_epoch_time(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1232
}
×
1233

1234
void TelemetryImpl::process_actuator_control_target(const mavlink_message_t& message)
×
1235
{
1236
    mavlink_set_actuator_control_target_t target;
×
1237
    mavlink_msg_set_actuator_control_target_decode(&message, &target);
×
1238

1239
    uint32_t group = target.group_mlx;
×
1240
    std::vector<float> controls;
×
1241

1242
    const unsigned control_size = sizeof(target.controls) / sizeof(target.controls[0]);
×
1243
    // Can't use std::copy because target is packed.
1244
    for (std::size_t i = 0; i < control_size; ++i) {
×
1245
        controls.push_back(target.controls[i]);
×
1246
    }
1247

1248
    set_actuator_control_target(group, controls);
×
1249

1250
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1251
    _actuator_control_target_subscriptions.queue(
×
1252
        actuator_control_target(),
×
1253
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1254
}
×
1255

1256
void TelemetryImpl::process_actuator_output_status(const mavlink_message_t& message)
×
1257
{
1258
    mavlink_actuator_output_status_t status;
×
1259
    mavlink_msg_actuator_output_status_decode(&message, &status);
×
1260

1261
    uint32_t active = status.active;
×
1262
    std::vector<float> actuators;
×
1263

1264
    const unsigned actuators_size = sizeof(status.actuator) / sizeof(status.actuator[0]);
×
1265
    // Can't use std::copy because status is packed.
1266
    for (std::size_t i = 0; i < actuators_size; ++i) {
×
1267
        actuators.push_back(status.actuator[i]);
×
1268
    }
1269

1270
    set_actuator_output_status(active, actuators);
×
1271

1272
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1273
    _actuator_output_status_subscriptions.queue(actuator_output_status(), [this](const auto& func) {
×
1274
        _system_impl->call_user_callback(func);
×
1275
    });
×
1276
}
×
1277

1278
void TelemetryImpl::process_odometry(const mavlink_message_t& message)
×
1279
{
1280
    mavlink_odometry_t odometry_msg;
×
1281
    mavlink_msg_odometry_decode(&message, &odometry_msg);
×
1282

1283
    Telemetry::Odometry odometry_struct{};
×
1284

1285
    odometry_struct.time_usec = odometry_msg.time_usec;
×
1286
    odometry_struct.frame_id = static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.frame_id);
×
1287
    odometry_struct.child_frame_id =
×
1288
        static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.child_frame_id);
×
1289

1290
    odometry_struct.position_body.x_m = odometry_msg.x;
×
1291
    odometry_struct.position_body.y_m = odometry_msg.y;
×
1292
    odometry_struct.position_body.z_m = odometry_msg.z;
×
1293

1294
    odometry_struct.q.w = odometry_msg.q[0];
×
1295
    odometry_struct.q.x = odometry_msg.q[1];
×
1296
    odometry_struct.q.y = odometry_msg.q[2];
×
1297
    odometry_struct.q.z = odometry_msg.q[3];
×
1298

1299
    odometry_struct.velocity_body.x_m_s = odometry_msg.vx;
×
1300
    odometry_struct.velocity_body.y_m_s = odometry_msg.vy;
×
1301
    odometry_struct.velocity_body.z_m_s = odometry_msg.vz;
×
1302

1303
    odometry_struct.angular_velocity_body.roll_rad_s = odometry_msg.rollspeed;
×
1304
    odometry_struct.angular_velocity_body.pitch_rad_s = odometry_msg.pitchspeed;
×
1305
    odometry_struct.angular_velocity_body.yaw_rad_s = odometry_msg.yawspeed;
×
1306

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

1314
    const std::size_t len_velocity_covariance =
×
1315
        sizeof(odometry_msg.velocity_covariance) / sizeof(odometry_msg.velocity_covariance[0]);
1316
    for (std::size_t i = 0; i < len_velocity_covariance; ++i) {
×
1317
        odometry_struct.velocity_covariance.covariance_matrix.push_back(
×
1318
            odometry_msg.velocity_covariance[i]);
×
1319
    }
1320

1321
    set_odometry(odometry_struct);
×
1322

1323
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1324
    _odometry_subscriptions.queue(
×
1325
        odometry(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1326
}
×
1327

1328
void TelemetryImpl::process_distance_sensor(const mavlink_message_t& message)
×
1329
{
1330
    mavlink_distance_sensor_t distance_sensor_msg;
×
1331
    mavlink_msg_distance_sensor_decode(&message, &distance_sensor_msg);
×
1332

1333
    Telemetry::DistanceSensor distance_sensor_struct{};
×
1334

1335
    distance_sensor_struct.minimum_distance_m =
×
1336
        static_cast<float>(distance_sensor_msg.min_distance) * 1e-2f; // cm to m
×
1337
    distance_sensor_struct.maximum_distance_m =
×
1338
        static_cast<float>(distance_sensor_msg.max_distance) * 1e-2f; // cm to m
×
1339
    distance_sensor_struct.current_distance_m =
×
1340
        static_cast<float>(distance_sensor_msg.current_distance) * 1e-2f; // cm to m
×
1341
    distance_sensor_struct.orientation = extractOrientation(distance_sensor_msg);
×
1342

1343
    set_distance_sensor(distance_sensor_struct);
×
1344

1345
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1346
    _distance_sensor_subscriptions.queue(
×
1347
        distance_sensor(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1348
}
×
1349

1350
Telemetry::EulerAngle
1351
TelemetryImpl::extractOrientation(mavlink_distance_sensor_t distance_sensor_msg)
×
1352
{
1353
    MavSensorOrientation orientation =
×
1354
        static_cast<MavSensorOrientation>(distance_sensor_msg.orientation);
×
1355

1356
    Telemetry::EulerAngle euler_angle;
×
1357
    euler_angle.roll_deg = 0;
×
1358
    euler_angle.pitch_deg = 0;
×
1359
    euler_angle.yaw_deg = 0;
×
1360

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

1557
    return euler_angle;
×
1558
}
1559

1560
void TelemetryImpl::process_scaled_pressure(const mavlink_message_t& message)
×
1561
{
1562
    mavlink_scaled_pressure_t scaled_pressure_msg;
×
1563
    mavlink_msg_scaled_pressure_decode(&message, &scaled_pressure_msg);
×
1564

1565
    Telemetry::ScaledPressure scaled_pressure_struct{};
×
1566

1567
    scaled_pressure_struct.timestamp_us =
×
1568
        static_cast<uint64_t>(scaled_pressure_msg.time_boot_ms) * 1000;
×
1569
    scaled_pressure_struct.absolute_pressure_hpa = scaled_pressure_msg.press_abs;
×
1570
    scaled_pressure_struct.differential_pressure_hpa = scaled_pressure_msg.press_diff;
×
1571
    scaled_pressure_struct.temperature_deg =
×
1572
        static_cast<float>(scaled_pressure_msg.temperature) * 1e-2f;
×
1573
    scaled_pressure_struct.differential_pressure_temperature_deg =
×
1574
        static_cast<float>(scaled_pressure_msg.temperature_press_diff) * 1e-2f;
×
1575

1576
    set_scaled_pressure(scaled_pressure_struct);
×
1577

1578
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1579
    _scaled_pressure_subscriptions.queue(
×
1580
        scaled_pressure(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1581
}
×
1582

1583
Telemetry::LandedState
1584
TelemetryImpl::to_landed_state(mavlink_extended_sys_state_t extended_sys_state)
×
1585
{
1586
    switch (extended_sys_state.landed_state) {
×
1587
        case MAV_LANDED_STATE_IN_AIR:
×
1588
            return Telemetry::LandedState::InAir;
×
1589
        case MAV_LANDED_STATE_TAKEOFF:
×
1590
            return Telemetry::LandedState::TakingOff;
×
1591
        case MAV_LANDED_STATE_LANDING:
×
1592
            return Telemetry::LandedState::Landing;
×
1593
        case MAV_LANDED_STATE_ON_GROUND:
×
1594
            return Telemetry::LandedState::OnGround;
×
1595
        default:
×
1596
            return Telemetry::LandedState::Unknown;
×
1597
    }
1598
}
1599

1600
Telemetry::VtolState TelemetryImpl::to_vtol_state(mavlink_extended_sys_state_t extended_sys_state)
×
1601
{
1602
    switch (extended_sys_state.vtol_state) {
×
1603
        case MAV_VTOL_STATE::MAV_VTOL_STATE_TRANSITION_TO_FW:
×
1604
            return Telemetry::VtolState::TransitionToFw;
×
1605
        case MAV_VTOL_STATE_TRANSITION_TO_MC:
×
1606
            return Telemetry::VtolState::TransitionToMc;
×
1607
        case MAV_VTOL_STATE_MC:
×
1608
            return Telemetry::VtolState::Mc;
×
1609
        case MAV_VTOL_STATE_FW:
×
1610
            return Telemetry::VtolState::Fw;
×
1611
        default:
×
1612
            return Telemetry::VtolState::Undefined;
×
1613
    }
1614
}
1615

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

1652
Telemetry::PositionVelocityNed TelemetryImpl::position_velocity_ned() const
×
1653
{
1654
    std::lock_guard<std::mutex> lock(_position_velocity_ned_mutex);
×
1655
    return _position_velocity_ned;
×
1656
}
×
1657

1658
void TelemetryImpl::set_position_velocity_ned(Telemetry::PositionVelocityNed position_velocity_ned)
×
1659
{
1660
    std::lock_guard<std::mutex> lock(_position_velocity_ned_mutex);
×
1661
    _position_velocity_ned = position_velocity_ned;
×
1662
}
×
1663

1664
Telemetry::Position TelemetryImpl::position() const
×
1665
{
1666
    std::lock_guard<std::mutex> lock(_position_mutex);
×
1667
    return _position;
×
1668
}
×
1669

1670
void TelemetryImpl::set_position(Telemetry::Position position)
×
1671
{
1672
    std::lock_guard<std::mutex> lock(_position_mutex);
×
1673
    _position = position;
×
1674
}
×
1675

1676
Telemetry::Heading TelemetryImpl::heading() const
×
1677
{
1678
    std::lock_guard<std::mutex> lock(_heading_mutex);
×
1679
    return _heading;
×
1680
}
×
1681

1682
void TelemetryImpl::set_heading(Telemetry::Heading heading)
×
1683
{
1684
    std::lock_guard<std::mutex> lock(_heading_mutex);
×
1685
    _heading = heading;
×
1686
}
×
1687

1688
Telemetry::Altitude TelemetryImpl::altitude() const
×
1689
{
1690
    std::lock_guard<std::mutex> lock(_altitude_mutex);
×
1691
    return _altitude;
×
1692
}
×
1693

1694
void TelemetryImpl::set_altitude(Telemetry::Altitude altitude)
×
1695
{
1696
    std::lock_guard<std::mutex> lock(_altitude_mutex);
×
1697
    _altitude = altitude;
×
1698
}
×
1699

1700
Telemetry::Wind TelemetryImpl::wind() const
×
1701
{
1702
    std::lock_guard<std::mutex> lock(_wind_mutex);
×
1703
    return _wind;
×
1704
}
×
1705

1706
void TelemetryImpl::set_wind(Telemetry::Wind wind)
×
1707
{
1708
    std::lock_guard<std::mutex> lock(_wind_mutex);
×
1709
    _wind = wind;
×
1710
}
×
1711

1712
Telemetry::Position TelemetryImpl::home() const
×
1713
{
1714
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
1715
    return _home_position;
×
1716
}
×
1717

1718
void TelemetryImpl::set_home_position(Telemetry::Position home_position)
×
1719
{
1720
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
1721
    _home_position = home_position;
×
1722
}
×
1723

1724
bool TelemetryImpl::armed() const
1✔
1725
{
1726
    return _armed;
1✔
1727
}
1728

1729
bool TelemetryImpl::in_air() const
×
1730
{
1731
    return _in_air;
×
1732
}
1733

1734
void TelemetryImpl::set_in_air(bool in_air_new)
×
1735
{
1736
    _in_air = in_air_new;
×
1737
}
×
1738

1739
void TelemetryImpl::set_status_text(Telemetry::StatusText status_text)
3✔
1740
{
1741
    std::lock_guard<std::mutex> lock(_status_text_mutex);
3✔
1742
    _status_text = status_text;
3✔
1743
}
3✔
1744

1745
Telemetry::StatusText TelemetryImpl::status_text() const
3✔
1746
{
1747
    std::lock_guard<std::mutex> lock(_status_text_mutex);
3✔
1748
    return _status_text;
3✔
1749
}
3✔
1750

1751
void TelemetryImpl::set_armed(bool armed_new)
1✔
1752
{
1753
    _armed = armed_new;
1✔
1754
}
1✔
1755

1756
Telemetry::Quaternion TelemetryImpl::attitude_quaternion() const
×
1757
{
1758
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1759
    return _attitude_quaternion;
×
1760
}
×
1761

1762
Telemetry::AngularVelocityBody TelemetryImpl::attitude_angular_velocity_body() const
×
1763
{
1764
    std::lock_guard<std::mutex> lock(_attitude_angular_velocity_body_mutex);
×
1765
    return _attitude_angular_velocity_body;
×
1766
}
×
1767

1768
Telemetry::GroundTruth TelemetryImpl::ground_truth() const
×
1769
{
1770
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
1771
    return _ground_truth;
×
1772
}
×
1773

1774
Telemetry::FixedwingMetrics TelemetryImpl::fixedwing_metrics() const
×
1775
{
1776
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
1777
    return _fixedwing_metrics;
×
1778
}
×
1779

1780
Telemetry::EulerAngle TelemetryImpl::attitude_euler() const
×
1781
{
1782
    std::lock_guard<std::mutex> lock(_attitude_euler_mutex);
×
1783
    return _attitude_euler;
×
1784
}
×
1785

1786
void TelemetryImpl::set_attitude_quaternion(Telemetry::Quaternion quaternion)
×
1787
{
1788
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1789
    _attitude_quaternion = quaternion;
×
1790
}
×
1791

1792
void TelemetryImpl::set_attitude_euler(Telemetry::EulerAngle euler)
×
1793
{
1794
    std::lock_guard<std::mutex> lock(_attitude_euler_mutex);
×
1795
    _attitude_euler = euler;
×
1796
}
×
1797

1798
void TelemetryImpl::set_attitude_angular_velocity_body(
×
1799
    Telemetry::AngularVelocityBody angular_velocity_body)
1800
{
1801
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1802
    _attitude_angular_velocity_body = angular_velocity_body;
×
1803
}
×
1804

1805
void TelemetryImpl::set_ground_truth(Telemetry::GroundTruth ground_truth)
×
1806
{
1807
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
1808
    _ground_truth = ground_truth;
×
1809
}
×
1810

1811
void TelemetryImpl::set_fixedwing_metrics(Telemetry::FixedwingMetrics fixedwing_metrics)
×
1812
{
1813
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
1814
    _fixedwing_metrics = fixedwing_metrics;
×
1815
}
×
1816

1817
Telemetry::VelocityNed TelemetryImpl::velocity_ned() const
×
1818
{
1819
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
1820
    return _velocity_ned;
×
1821
}
×
1822

1823
void TelemetryImpl::set_velocity_ned(Telemetry::VelocityNed velocity_ned)
×
1824
{
1825
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
1826
    _velocity_ned = velocity_ned;
×
1827
}
×
1828

1829
Telemetry::Imu TelemetryImpl::imu() const
×
1830
{
1831
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
1832
    return _imu_reading_ned;
×
1833
}
×
1834

1835
void TelemetryImpl::set_imu_reading_ned(Telemetry::Imu imu_reading_ned)
×
1836
{
1837
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
1838
    _imu_reading_ned = imu_reading_ned;
×
1839
}
×
1840

1841
Telemetry::Imu TelemetryImpl::scaled_imu() const
×
1842
{
1843
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
1844
    return _scaled_imu;
×
1845
}
×
1846

1847
void TelemetryImpl::set_scaled_imu(Telemetry::Imu scaled_imu)
×
1848
{
1849
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
1850
    _scaled_imu = scaled_imu;
×
1851
}
×
1852

1853
Telemetry::Imu TelemetryImpl::raw_imu() const
×
1854
{
1855
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
1856
    return _raw_imu;
×
1857
}
×
1858

1859
void TelemetryImpl::set_raw_imu(Telemetry::Imu raw_imu)
×
1860
{
1861
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
1862
    _raw_imu = raw_imu;
×
1863
}
×
1864

1865
Telemetry::GpsInfo TelemetryImpl::gps_info() const
×
1866
{
1867
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
×
1868
    return _gps_info;
×
1869
}
×
1870

1871
void TelemetryImpl::set_gps_info(Telemetry::GpsInfo gps_info)
×
1872
{
1873
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
×
1874
    _gps_info = gps_info;
×
1875
}
×
1876

1877
Telemetry::RawGps TelemetryImpl::raw_gps() const
×
1878
{
1879
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
×
1880
    return _raw_gps;
×
1881
}
×
1882

1883
void TelemetryImpl::set_raw_gps(Telemetry::RawGps raw_gps)
×
1884
{
1885
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
×
1886
    _raw_gps = raw_gps;
×
1887
}
×
1888

1889
Telemetry::Battery TelemetryImpl::battery() const
×
1890
{
1891
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
1892
    return _battery;
×
1893
}
×
1894

1895
void TelemetryImpl::set_battery(Telemetry::Battery battery)
×
1896
{
1897
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
1898
    _battery = battery;
×
1899
}
×
1900

1901
Telemetry::FlightMode TelemetryImpl::flight_mode() const
×
1902
{
1903
    return telemetry_flight_mode_from_flight_mode(_system_impl->get_flight_mode());
×
1904
}
1905

1906
Telemetry::Health TelemetryImpl::health() const
1✔
1907
{
1908
    std::lock_guard<std::mutex> lock(_health_mutex);
1✔
1909
    return _health;
2✔
1910
}
1✔
1911

1912
bool TelemetryImpl::health_all_ok() const
1✔
1913
{
1914
    std::lock_guard<std::mutex> lock(_health_mutex);
1✔
1915
    if (_health.is_gyrometer_calibration_ok && _health.is_accelerometer_calibration_ok &&
1✔
1916
        _health.is_magnetometer_calibration_ok && _health.is_local_position_ok &&
×
1917
        _health.is_global_position_ok && _health.is_home_position_ok) {
×
1918
        return true;
×
1919
    } else {
1920
        return false;
1✔
1921
    }
1922
}
1✔
1923

1924
Telemetry::RcStatus TelemetryImpl::rc_status() const
×
1925
{
1926
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
1927
    return _rc_status;
×
1928
}
×
1929

1930
uint64_t TelemetryImpl::unix_epoch_time() const
×
1931
{
1932
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
1933
    return _unix_epoch_time_us;
×
1934
}
×
1935

1936
Telemetry::ActuatorControlTarget TelemetryImpl::actuator_control_target() const
×
1937
{
1938
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
1939
    return _actuator_control_target;
×
1940
}
×
1941

1942
Telemetry::ActuatorOutputStatus TelemetryImpl::actuator_output_status() const
×
1943
{
1944
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
1945
    return _actuator_output_status;
×
1946
}
×
1947

1948
Telemetry::Odometry TelemetryImpl::odometry() const
×
1949
{
1950
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
1951
    return _odometry;
×
1952
}
×
1953

1954
Telemetry::DistanceSensor TelemetryImpl::distance_sensor() const
×
1955
{
1956
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
1957
    return _distance_sensor;
×
1958
}
×
1959

1960
Telemetry::ScaledPressure TelemetryImpl::scaled_pressure() const
×
1961
{
1962
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
1963
    return _scaled_pressure;
×
1964
}
×
1965

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

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

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

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

1990
void TelemetryImpl::set_health_accelerometer_calibration(bool ok)
×
1991
{
1992
    std::lock_guard<std::mutex> lock(_health_mutex);
×
1993
    _health.is_accelerometer_calibration_ok = ok;
×
1994
}
×
1995

1996
void TelemetryImpl::set_health_magnetometer_calibration(bool ok)
×
1997
{
1998
    std::lock_guard<std::mutex> lock(_health_mutex);
×
1999
    _health.is_magnetometer_calibration_ok = ok;
×
2000
}
×
2001

2002
void TelemetryImpl::set_health_armable(bool ok)
×
2003
{
2004
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2005
    _health.is_armable = ok;
×
2006
}
×
2007

2008
Telemetry::VtolState TelemetryImpl::vtol_state() const
×
2009
{
2010
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
2011
    return _vtol_state;
×
2012
}
×
2013

2014
void TelemetryImpl::set_vtol_state(Telemetry::VtolState vtol_state)
×
2015
{
2016
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
2017
    _vtol_state = vtol_state;
×
2018
}
×
2019

2020
Telemetry::LandedState TelemetryImpl::landed_state() const
×
2021
{
2022
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2023
    return _landed_state;
×
2024
}
×
2025

2026
void TelemetryImpl::set_landed_state(Telemetry::LandedState landed_state)
×
2027
{
2028
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2029
    _landed_state = landed_state;
×
2030
}
×
2031

2032
void TelemetryImpl::set_rc_status(
×
2033
    std::optional<bool> maybe_available, std::optional<float> maybe_signal_strength_percent)
2034
{
2035
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
2036

2037
    if (maybe_available) {
×
2038
        _rc_status.is_available = maybe_available.value();
×
2039
        if (maybe_available.value()) {
×
2040
            _rc_status.was_available_once = true;
×
2041
        }
2042
    }
2043

2044
    if (maybe_signal_strength_percent) {
×
2045
        _rc_status.signal_strength_percent = maybe_signal_strength_percent.value();
×
2046
    }
2047
}
×
2048

2049
void TelemetryImpl::set_unix_epoch_time_us(uint64_t time_us)
×
2050
{
2051
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
2052
    _unix_epoch_time_us = time_us;
×
2053
}
×
2054

2055
void TelemetryImpl::set_actuator_control_target(uint8_t group, const std::vector<float>& controls)
×
2056
{
2057
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
2058
    _actuator_control_target.group = group;
×
2059
    _actuator_control_target.controls = controls;
×
2060
}
×
2061

2062
void TelemetryImpl::set_actuator_output_status(uint32_t active, const std::vector<float>& actuators)
×
2063
{
2064
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
2065
    _actuator_output_status.active = active;
×
2066
    _actuator_output_status.actuator = actuators;
×
2067
}
×
2068

2069
void TelemetryImpl::set_odometry(Telemetry::Odometry& odometry)
×
2070
{
2071
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
2072
    _odometry = odometry;
×
2073
}
×
2074

2075
void TelemetryImpl::set_distance_sensor(Telemetry::DistanceSensor& distance_sensor)
×
2076
{
2077
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
2078
    _distance_sensor = distance_sensor;
×
2079
}
×
2080

2081
void TelemetryImpl::set_scaled_pressure(Telemetry::ScaledPressure& scaled_pressure)
×
2082
{
2083
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
2084
    _scaled_pressure = scaled_pressure;
×
2085
}
×
2086

2087
Telemetry::PositionVelocityNedHandle TelemetryImpl::subscribe_position_velocity_ned(
×
2088
    const Telemetry::PositionVelocityNedCallback& callback)
2089
{
2090
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2091
    return _position_velocity_ned_subscriptions.subscribe(callback);
×
2092
}
×
2093

2094
void TelemetryImpl::unsubscribe_position_velocity_ned(Telemetry::PositionVelocityNedHandle handle)
×
2095
{
2096
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2097
    _position_velocity_ned_subscriptions.unsubscribe(handle);
×
2098
}
×
2099

2100
Telemetry::PositionHandle
2101
TelemetryImpl::subscribe_position(const Telemetry::PositionCallback& callback)
×
2102
{
2103
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2104
    return _position_subscriptions.subscribe(callback);
×
2105
}
×
2106

2107
void TelemetryImpl::unsubscribe_position(Telemetry::PositionHandle handle)
×
2108
{
2109
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2110
    _position_subscriptions.unsubscribe(handle);
×
2111
}
×
2112

2113
Telemetry::HomeHandle TelemetryImpl::subscribe_home(const Telemetry::PositionCallback& callback)
×
2114
{
2115
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2116
    return _home_position_subscriptions.subscribe(callback);
×
2117
}
×
2118

2119
void TelemetryImpl::unsubscribe_home(Telemetry::HomeHandle handle)
×
2120
{
2121
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2122
    _home_position_subscriptions.unsubscribe(handle);
×
2123
}
×
2124

2125
Telemetry::InAirHandle TelemetryImpl::subscribe_in_air(const Telemetry::InAirCallback& callback)
×
2126
{
2127
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2128
    return _in_air_subscriptions.subscribe(callback);
×
2129
}
×
2130

2131
void TelemetryImpl::unsubscribe_in_air(Telemetry::InAirHandle handle)
×
2132
{
2133
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2134
    return _in_air_subscriptions.unsubscribe(handle);
×
2135
}
×
2136

2137
Telemetry::StatusTextHandle
2138
TelemetryImpl::subscribe_status_text(const Telemetry::StatusTextCallback& callback)
2✔
2139
{
2140
    std::lock_guard<std::mutex> lock(_subscription_mutex);
2✔
2141
    return _status_text_subscriptions.subscribe(callback);
2✔
2142
}
2✔
2143

2144
void TelemetryImpl::unsubscribe_status_text(Handle<Telemetry::StatusText> handle)
1✔
2145
{
2146
    std::lock_guard<std::mutex> lock(_subscription_mutex);
1✔
2147
    _status_text_subscriptions.unsubscribe(handle);
1✔
2148
}
1✔
2149

2150
Telemetry::ArmedHandle TelemetryImpl::subscribe_armed(const Telemetry::ArmedCallback& callback)
×
2151
{
2152
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2153
    return _armed_subscriptions.subscribe(callback);
×
2154
}
×
2155

2156
void TelemetryImpl::unsubscribe_armed(Telemetry::ArmedHandle handle)
×
2157
{
2158
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2159
    _armed_subscriptions.unsubscribe(handle);
×
2160
}
×
2161

2162
Telemetry::AttitudeQuaternionHandle
2163
TelemetryImpl::subscribe_attitude_quaternion(const Telemetry::AttitudeQuaternionCallback& callback)
×
2164
{
2165
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2166
    return _attitude_quaternion_angle_subscriptions.subscribe(callback);
×
2167
}
×
2168

2169
void TelemetryImpl::unsubscribe_attitude_quaternion(Telemetry::AttitudeQuaternionHandle handle)
×
2170
{
2171
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2172
    _attitude_quaternion_angle_subscriptions.unsubscribe(handle);
×
2173
}
×
2174

2175
Telemetry::AttitudeEulerHandle
2176
TelemetryImpl::subscribe_attitude_euler(const Telemetry::AttitudeEulerCallback& callback)
×
2177
{
2178
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2179
    return _attitude_euler_angle_subscriptions.subscribe(callback);
×
2180
}
×
2181

2182
void TelemetryImpl::unsubscribe_attitude_euler(Telemetry::AttitudeEulerHandle handle)
×
2183
{
2184
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2185
    _attitude_euler_angle_subscriptions.unsubscribe(handle);
×
2186
}
×
2187

2188
Telemetry::AttitudeAngularVelocityBodyHandle
2189
TelemetryImpl::subscribe_attitude_angular_velocity_body(
×
2190
    const Telemetry::AttitudeAngularVelocityBodyCallback& callback)
2191
{
2192
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2193
    return _attitude_angular_velocity_body_subscriptions.subscribe(callback);
×
2194
}
×
2195

2196
void TelemetryImpl::unsubscribe_attitude_angular_velocity_body(
×
2197
    Telemetry::AttitudeAngularVelocityBodyHandle handle)
2198
{
2199
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2200
    _attitude_angular_velocity_body_subscriptions.unsubscribe(handle);
×
2201
}
×
2202

2203
Telemetry::FixedwingMetricsHandle
2204
TelemetryImpl::subscribe_fixedwing_metrics(const Telemetry::FixedwingMetricsCallback& callback)
×
2205
{
2206
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2207
    return _fixedwing_metrics_subscriptions.subscribe(callback);
×
2208
}
×
2209

2210
void TelemetryImpl::unsubscribe_fixedwing_metrics(Telemetry::FixedwingMetricsHandle handle)
×
2211
{
2212
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2213
    _fixedwing_metrics_subscriptions.unsubscribe(handle);
×
2214
}
×
2215

2216
Telemetry::GroundTruthHandle
2217
TelemetryImpl::subscribe_ground_truth(const Telemetry::GroundTruthCallback& callback)
×
2218
{
2219
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2220
    return _ground_truth_subscriptions.subscribe(callback);
×
2221
}
×
2222

2223
void TelemetryImpl::unsubscribe_ground_truth(Telemetry::GroundTruthHandle handle)
×
2224
{
2225
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2226
    _ground_truth_subscriptions.unsubscribe(handle);
×
2227
}
×
2228

2229
Telemetry::VelocityNedHandle
2230
TelemetryImpl::subscribe_velocity_ned(const Telemetry::VelocityNedCallback& callback)
×
2231
{
2232
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2233
    return _velocity_ned_subscriptions.subscribe(callback);
×
2234
}
×
2235

2236
void TelemetryImpl::unsubscribe_velocity_ned(Telemetry::VelocityNedHandle handle)
×
2237
{
2238
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2239
    _velocity_ned_subscriptions.unsubscribe(handle);
×
2240
}
×
2241

2242
Telemetry::ImuHandle TelemetryImpl::subscribe_imu(const Telemetry::ImuCallback& callback)
×
2243
{
2244
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2245
    return _imu_reading_ned_subscriptions.subscribe(callback);
×
2246
}
×
2247

2248
void TelemetryImpl::unsubscribe_imu(Telemetry::ImuHandle handle)
×
2249
{
2250
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2251
    return _imu_reading_ned_subscriptions.unsubscribe(handle);
×
2252
}
×
2253

2254
Telemetry::ScaledImuHandle
2255
TelemetryImpl::subscribe_scaled_imu(const Telemetry::ScaledImuCallback& callback)
×
2256
{
2257
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2258
    return _scaled_imu_subscriptions.subscribe(callback);
×
2259
}
×
2260

2261
void TelemetryImpl::unsubscribe_scaled_imu(Telemetry::ScaledImuHandle handle)
×
2262
{
2263
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2264
    _scaled_imu_subscriptions.unsubscribe(handle);
×
2265
}
×
2266

2267
Telemetry::RawImuHandle TelemetryImpl::subscribe_raw_imu(const Telemetry::RawImuCallback& callback)
×
2268
{
2269
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2270
    return _raw_imu_subscriptions.subscribe(callback);
×
2271
}
×
2272

2273
void TelemetryImpl::unsubscribe_raw_imu(Telemetry::RawImuHandle handle)
×
2274
{
2275
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2276
    _raw_imu_subscriptions.unsubscribe(handle);
×
2277
}
×
2278

2279
Telemetry::GpsInfoHandle
2280
TelemetryImpl::subscribe_gps_info(const Telemetry::GpsInfoCallback& callback)
×
2281
{
2282
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2283
    return _gps_info_subscriptions.subscribe(callback);
×
2284
}
×
2285

2286
void TelemetryImpl::unsubscribe_gps_info(Telemetry::GpsInfoHandle handle)
×
2287
{
2288
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2289
    _gps_info_subscriptions.unsubscribe(handle);
×
2290
}
×
2291

2292
Telemetry::RawGpsHandle TelemetryImpl::subscribe_raw_gps(const Telemetry::RawGpsCallback& callback)
×
2293
{
2294
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2295
    return _raw_gps_subscriptions.subscribe(callback);
×
2296
}
×
2297

2298
void TelemetryImpl::unsubscribe_raw_gps(Telemetry::RawGpsHandle handle)
×
2299
{
2300
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2301
    _raw_gps_subscriptions.unsubscribe(handle);
×
2302
}
×
2303

2304
Telemetry::BatteryHandle
2305
TelemetryImpl::subscribe_battery(const Telemetry::BatteryCallback& callback)
×
2306
{
2307
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2308
    return _battery_subscriptions.subscribe(callback);
×
2309
}
×
2310

2311
void TelemetryImpl::unsubscribe_battery(Telemetry::BatteryHandle handle)
×
2312
{
2313
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2314
    _battery_subscriptions.unsubscribe(handle);
×
2315
}
×
2316

2317
Telemetry::FlightModeHandle
2318
TelemetryImpl::subscribe_flight_mode(const Telemetry::FlightModeCallback& callback)
×
2319
{
2320
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2321
    return _flight_mode_subscriptions.subscribe(callback);
×
2322
}
×
2323

2324
void TelemetryImpl::unsubscribe_flight_mode(Telemetry::FlightModeHandle handle)
×
2325
{
2326
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2327
    _flight_mode_subscriptions.unsubscribe(handle);
×
2328
}
×
2329

2330
Telemetry::HealthHandle TelemetryImpl::subscribe_health(const Telemetry::HealthCallback& callback)
×
2331
{
2332
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2333
    return _health_subscriptions.subscribe(callback);
×
2334
}
×
2335

2336
void TelemetryImpl::unsubscribe_health(Telemetry::HealthHandle handle)
×
2337
{
2338
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2339
    _health_subscriptions.unsubscribe(handle);
×
2340
}
×
2341

2342
Telemetry::HealthAllOkHandle
2343
TelemetryImpl::subscribe_health_all_ok(const Telemetry::HealthAllOkCallback& callback)
×
2344
{
2345
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2346
    return _health_all_ok_subscriptions.subscribe(callback);
×
2347
}
×
2348

2349
void TelemetryImpl::unsubscribe_health_all_ok(Telemetry::HealthAllOkHandle handle)
×
2350
{
2351
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2352
    _health_all_ok_subscriptions.unsubscribe(handle);
×
2353
}
×
2354

2355
Telemetry::VtolStateHandle
2356
TelemetryImpl::subscribe_vtol_state(const Telemetry::VtolStateCallback& callback)
×
2357
{
2358
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2359
    return _vtol_state_subscriptions.subscribe(callback);
×
2360
}
×
2361

2362
void TelemetryImpl::unsubscribe_vtol_state(Telemetry::VtolStateHandle handle)
×
2363
{
2364
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2365
    _vtol_state_subscriptions.unsubscribe(handle);
×
2366
}
×
2367

2368
Telemetry::LandedStateHandle
2369
TelemetryImpl::subscribe_landed_state(const Telemetry::LandedStateCallback& callback)
×
2370
{
2371
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2372
    return _landed_state_subscriptions.subscribe(callback);
×
2373
}
×
2374

2375
void TelemetryImpl::unsubscribe_landed_state(Telemetry::LandedStateHandle handle)
×
2376
{
2377
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2378
    _landed_state_subscriptions.unsubscribe(handle);
×
2379
}
×
2380

2381
Telemetry::RcStatusHandle
2382
TelemetryImpl::subscribe_rc_status(const Telemetry::RcStatusCallback& callback)
×
2383
{
2384
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2385
    return _rc_status_subscriptions.subscribe(callback);
×
2386
}
×
2387

2388
void TelemetryImpl::unsubscribe_rc_status(Telemetry::RcStatusHandle handle)
×
2389
{
2390
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2391
    _rc_status_subscriptions.unsubscribe(handle);
×
2392
}
×
2393

2394
Telemetry::UnixEpochTimeHandle
2395
TelemetryImpl::subscribe_unix_epoch_time(const Telemetry::UnixEpochTimeCallback& callback)
×
2396
{
2397
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2398
    return _unix_epoch_time_subscriptions.subscribe(callback);
×
2399
}
×
2400

2401
void TelemetryImpl::unsubscribe_unix_epoch_time(Telemetry::UnixEpochTimeHandle handle)
×
2402
{
2403
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2404
    _unix_epoch_time_subscriptions.unsubscribe(handle);
×
2405
}
×
2406

2407
Telemetry::ActuatorControlTargetHandle TelemetryImpl::subscribe_actuator_control_target(
×
2408
    const Telemetry::ActuatorControlTargetCallback& callback)
2409
{
2410
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2411
    return _actuator_control_target_subscriptions.subscribe(callback);
×
2412
}
×
2413

2414
void TelemetryImpl::unsubscribe_actuator_control_target(
×
2415
    Telemetry::ActuatorControlTargetHandle handle)
2416
{
2417
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2418
    _actuator_control_target_subscriptions.unsubscribe(handle);
×
2419
}
×
2420

2421
Telemetry::ActuatorOutputStatusHandle TelemetryImpl::subscribe_actuator_output_status(
×
2422
    const Telemetry::ActuatorOutputStatusCallback& callback)
2423
{
2424
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2425
    return _actuator_output_status_subscriptions.subscribe(callback);
×
2426
}
×
2427

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

2434
Telemetry::OdometryHandle
2435
TelemetryImpl::subscribe_odometry(const Telemetry::OdometryCallback& callback)
×
2436
{
2437
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2438
    return _odometry_subscriptions.subscribe(callback);
×
2439
}
×
2440

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

2447
Telemetry::DistanceSensorHandle
2448
TelemetryImpl::subscribe_distance_sensor(const Telemetry::DistanceSensorCallback& callback)
×
2449
{
2450
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2451
    return _distance_sensor_subscriptions.subscribe(callback);
×
2452
}
×
2453

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

2460
Telemetry::ScaledPressureHandle
2461
TelemetryImpl::subscribe_scaled_pressure(const Telemetry::ScaledPressureCallback& callback)
×
2462
{
2463
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2464
    return _scaled_pressure_subscriptions.subscribe(callback);
×
2465
}
×
2466

2467
void TelemetryImpl::unsubscribe_scaled_pressure(Telemetry::ScaledPressureHandle handle)
×
2468
{
2469
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2470
    _scaled_pressure_subscriptions.unsubscribe(handle);
×
2471
}
×
2472

2473
Telemetry::HeadingHandle
2474
TelemetryImpl::subscribe_heading(const Telemetry::HeadingCallback& callback)
×
2475
{
2476
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2477
    return _heading_subscriptions.subscribe(callback);
×
2478
}
×
2479

2480
void TelemetryImpl::unsubscribe_heading(Telemetry::HeadingHandle handle)
×
2481
{
2482
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2483
    _heading_subscriptions.unsubscribe(handle);
×
2484
}
×
2485

2486
Telemetry::AltitudeHandle
2487
TelemetryImpl::subscribe_altitude(const Telemetry::AltitudeCallback& callback)
×
2488
{
2489
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2490
    return _altitude_subscriptions.subscribe(callback);
×
2491
}
×
2492

2493
void TelemetryImpl::unsubscribe_altitude(Telemetry::AltitudeHandle handle)
×
2494
{
2495
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2496
    _altitude_subscriptions.unsubscribe(handle);
×
2497
}
×
2498

2499
Telemetry::WindHandle TelemetryImpl::subscribe_wind(const Telemetry::WindCallback& callback)
×
2500
{
2501
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2502
    return _wind_subscriptions.subscribe(callback);
×
2503
}
×
2504

2505
void TelemetryImpl::unsubscribe_wind(Telemetry::WindHandle handle)
×
2506
{
2507
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2508
    _wind_subscriptions.unsubscribe(handle);
×
2509
}
×
2510

2511
void TelemetryImpl::get_gps_global_origin_async(
×
2512
    const Telemetry::GetGpsGlobalOriginCallback callback)
2513
{
2514
    _system_impl->mavlink_request_message().request(
×
2515
        MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN,
2516
        MAV_COMP_ID_AUTOPILOT1,
2517
        [this, callback](MavlinkCommandSender::Result result, const mavlink_message_t& message) {
×
2518
            if (result == MavlinkCommandSender::Result::Success) {
×
2519
                mavlink_gps_global_origin_t mavlink_gps_global_origin;
×
2520
                mavlink_msg_gps_global_origin_decode(&message, &mavlink_gps_global_origin);
×
2521

2522
                Telemetry::GpsGlobalOrigin gps_global_origin;
×
2523
                gps_global_origin.latitude_deg = mavlink_gps_global_origin.latitude * 1e-7;
×
2524
                gps_global_origin.longitude_deg = mavlink_gps_global_origin.longitude * 1e-7;
×
2525
                gps_global_origin.altitude_m = mavlink_gps_global_origin.altitude * 1e-3f;
×
2526
                _system_impl->call_user_callback([callback, gps_global_origin]() {
×
2527
                    callback(Telemetry::Result::Success, gps_global_origin);
2528
                });
2529

2530
            } else {
2531
                _system_impl->call_user_callback([callback, result]() {
×
2532
                    callback(telemetry_result_from_command_result(result), {});
2533
                });
2534
            }
2535
        });
×
2536
}
×
2537

2538
std::pair<Telemetry::Result, Telemetry::GpsGlobalOrigin> TelemetryImpl::get_gps_global_origin()
×
2539
{
2540
    auto prom = std::promise<std::pair<Telemetry::Result, Telemetry::GpsGlobalOrigin>>();
×
2541
    auto fut = prom.get_future();
×
2542

2543
    get_gps_global_origin_async(
×
2544
        [&prom](Telemetry::Result result, Telemetry::GpsGlobalOrigin gps_global_origin) {
×
2545
            prom.set_value(std::make_pair(result, gps_global_origin));
×
2546
        });
×
2547
    return fut.get();
×
2548
}
×
2549

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

© 2026 Coveralls, Inc