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

mavlink / MAVSDK / 13874502435

15 Mar 2025 04:09PM UTC coverage: 44.369% (-0.05%) from 44.423%
13874502435

Pull #2524

github

web-flow
Merge 8262f9b6d into effa4a8ff
Pull Request #2524: PR Update Battery Remaining Time and Battery Function

0 of 41 new or added lines in 2 files covered. (0.0%)

4 existing lines in 3 files now uncovered.

14593 of 32890 relevant lines covered (44.37%)

283.74 hits per line

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

7.06
/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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

175
    _system_impl->register_statustext_handler(
1✔
176
        [this](const MavlinkStatustextHandler::Statustext& statustext) {
3✔
177
            receive_statustext(statustext);
3✔
178
        },
3✔
179
        this);
180
}
1✔
181

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

391
void TelemetryImpl::set_rate_home_async(double rate_hz, Telemetry::ResultCallback callback)
×
392
{
393
    _system_impl->set_msg_rate_async(
×
394
        MAVLINK_MSG_ID_HOME_POSITION,
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_in_air_async(double rate_hz, Telemetry::ResultCallback callback)
×
402
{
403
    set_rate_landed_state_async(rate_hz, callback);
×
404
}
×
405

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

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

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

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

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

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

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

466
void TelemetryImpl::set_rate_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
467
{
468
    _system_impl->set_msg_rate_async(
×
469
        MAVLINK_MSG_ID_HIGHRES_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_scaled_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
477
{
478
    _system_impl->set_msg_rate_async(
×
479
        MAVLINK_MSG_ID_SCALED_IMU,
480
        rate_hz,
481
        [callback](MavlinkCommandSender::Result command_result, float) {
×
482
            command_result_callback(command_result, callback);
×
483
        });
×
484
}
×
485

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

496
void TelemetryImpl::set_rate_fixedwing_metrics_async(
×
497
    double rate_hz, Telemetry::ResultCallback callback)
498
{
499
    _system_impl->set_msg_rate_async(
×
500
        MAVLINK_MSG_ID_VFR_HUD,
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_ground_truth_async(double rate_hz, Telemetry::ResultCallback callback)
×
508
{
509
    _system_impl->set_msg_rate_async(
×
510
        MAVLINK_MSG_ID_HIL_STATE_QUATERNION,
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_gps_info_async(double rate_hz, Telemetry::ResultCallback callback)
×
518
{
519
    _system_impl->set_msg_rate_async(
×
520
        MAVLINK_MSG_ID_GPS_RAW_INT,
521
        rate_hz,
522
        [callback](MavlinkCommandSender::Result command_result, float) {
×
523
            command_result_callback(command_result, callback);
×
524
        });
×
525
}
×
526

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

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

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

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

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

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

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

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

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

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

639
    callback(action_result);
×
640
}
×
641

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

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

655
    set_position_velocity_ned(position_velocity);
×
656

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

662
    set_health_local_position(true);
×
663
}
×
664

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

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

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

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

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

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

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

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

716
    set_home_position(new_pos);
×
717

718
    set_health_home_position(true);
×
719

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

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

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

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

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

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

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

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

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

769
    set_attitude_quaternion(quaternion);
×
770

771
    set_attitude_angular_velocity_body(angular_velocity_body);
×
772

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

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

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

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

796
    set_altitude(new_altitude);
×
797

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

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

820
    set_imu_reading_ned(new_imu);
×
821

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

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

844
    set_scaled_imu(new_imu);
×
845

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

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

868
    set_raw_imu(new_imu);
×
869

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

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

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

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

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

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

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

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

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

951
    set_ground_truth(new_ground_truth);
×
952

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

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

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

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

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

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

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

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

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

1003
    set_fixedwing_metrics(new_fixedwing_metrics);
×
1004

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

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

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

1020
        set_battery(new_battery);
×
1021

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

1029
    const bool rc_ok =
×
1030
        sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
×
1031

1032
    set_rc_status({rc_ok}, std::nullopt);
×
1033

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

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

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

1052
    const bool global_position_ok =
1053
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_GPS);
×
1054

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

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

1063
    set_health_local_position(local_position_ok);
×
1064
    set_health_global_position(global_position_ok);
×
1065

1066
    set_rc_status({rc_ok}, std::nullopt);
×
1067

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

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

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

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

1092
    _has_bat_status = true;
×
1093

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

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

1119
    new_battery.remaining_percent = bat_status.battery_remaining;
×
1120
    new_battery.current_battery_a = (bat_status.current_battery == -1) ?
×
1121
                                        static_cast<float>(NAN) :
1122
                                        bat_status.current_battery * 1e-2f; // cA to A
×
NEW
1123
    new_battery.capacity_consumed_ah = (bat_status.current_consumed == -1) ?
×
1124
                                           static_cast<float>(NAN) :
NEW
1125
                                           bat_status.current_consumed * 1e-3f; // mAh to Ah
×
UNCOV
1126
    new_battery.time_remaining_s = (bat_status.time_remaining == std::numeric_limits<int16_t>::max()) ?
×
1127
                                       static_cast<float>(NAN) :
NEW
1128
                                       bat_status.time_remaining;
×
1129

1130
    Telemetry::BatteryFunction battery_function;
NEW
1131
    switch (bat_status.battery_function) {
×
NEW
1132
        case 0:
×
NEW
1133
            battery_function = Telemetry::BatteryFunction::Unknown;
×
NEW
1134
            break;
×
NEW
1135
        case 1:
×
NEW
1136
            battery_function = Telemetry::BatteryFunction::All;
×
NEW
1137
            break;
×
NEW
1138
        case 2:
×
NEW
1139
            battery_function = Telemetry::BatteryFunction::Propulsion;
×
NEW
1140
            break;
×
NEW
1141
        case 3:
×
NEW
1142
            battery_function = Telemetry::BatteryFunction::Avionics;
×
NEW
1143
            break;
×
NEW
1144
        case 4:
×
NEW
1145
            battery_function = Telemetry::BatteryFunction::Payload;
×
NEW
1146
            break;
×
1147

NEW
1148
        default:
×
NEW
1149
            battery_function = Telemetry::BatteryFunction::Unknown;
×
1150
            break;
×
1151
    }
UNCOV
1152
    new_battery.battery_function = battery_function;
×
1153
    set_battery(new_battery);
×
1154

1155
    {
1156
        std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1157
        _battery_subscriptions.queue(
×
1158
            battery(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1159
    }
×
1160
}
×
1161

1162
void TelemetryImpl::process_heartbeat(const mavlink_message_t& message)
1✔
1163
{
1164
    if (message.compid != MAV_COMP_ID_AUTOPILOT1) {
1✔
1165
        return;
×
1166
    }
1167

1168
    mavlink_heartbeat_t heartbeat;
1✔
1169
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
1✔
1170

1171
    set_armed(((heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) ? true : false));
1✔
1172

1173
    std::lock_guard<std::mutex> lock(_subscription_mutex);
1✔
1174
    _armed_subscriptions.queue(
2✔
1175
        armed(), [this](const auto& func) { _system_impl->call_user_callback(func); });
1✔
1176

1177
    _flight_mode_subscriptions.queue(
2✔
1178
        telemetry_flight_mode_from_flight_mode(_system_impl->get_flight_mode()),
1✔
1179
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1180

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

1184
    _health_all_ok_subscriptions.queue(
2✔
1185
        health_all_ok(), [this](const auto& func) { _system_impl->call_user_callback(func); });
1✔
1186
}
1✔
1187

1188
void TelemetryImpl::receive_statustext(const MavlinkStatustextHandler::Statustext& statustext)
3✔
1189
{
1190
    Telemetry::StatusText new_status_text;
3✔
1191

1192
    switch (statustext.severity) {
3✔
1193
        case MAV_SEVERITY_EMERGENCY:
×
1194
            new_status_text.type = Telemetry::StatusTextType::Emergency;
×
1195
            break;
×
1196
        case MAV_SEVERITY_ALERT:
×
1197
            new_status_text.type = Telemetry::StatusTextType::Alert;
×
1198
            break;
×
1199
        case MAV_SEVERITY_CRITICAL:
×
1200
            new_status_text.type = Telemetry::StatusTextType::Critical;
×
1201
            break;
×
1202
        case MAV_SEVERITY_ERROR:
×
1203
            new_status_text.type = Telemetry::StatusTextType::Error;
×
1204
            break;
×
1205
        case MAV_SEVERITY_WARNING:
×
1206
            new_status_text.type = Telemetry::StatusTextType::Warning;
×
1207
            break;
×
1208
        case MAV_SEVERITY_NOTICE:
×
1209
            new_status_text.type = Telemetry::StatusTextType::Notice;
×
1210
            break;
×
1211
        case MAV_SEVERITY_INFO:
3✔
1212
            new_status_text.type = Telemetry::StatusTextType::Info;
3✔
1213
            break;
3✔
1214
        case MAV_SEVERITY_DEBUG:
×
1215
            new_status_text.type = Telemetry::StatusTextType::Debug;
×
1216
            break;
×
1217
        default:
×
1218
            LogWarn() << "Unknown StatusText severity";
×
1219
            new_status_text.type = Telemetry::StatusTextType::Info;
×
1220
            break;
×
1221
    }
1222

1223
    new_status_text.text = statustext.text;
3✔
1224

1225
    set_status_text(new_status_text);
3✔
1226

1227
    std::lock_guard<std::mutex> lock(_subscription_mutex);
6✔
1228
    _status_text_subscriptions.queue(
9✔
1229
        status_text(), [this](const auto& func) { _system_impl->call_user_callback(func); });
11✔
1230
}
3✔
1231

1232
void TelemetryImpl::process_rc_channels(const mavlink_message_t& message)
×
1233
{
1234
    mavlink_rc_channels_t rc_channels;
×
1235
    mavlink_msg_rc_channels_decode(&message, &rc_channels);
×
1236

1237
    if (rc_channels.rssi != std::numeric_limits<uint8_t>::max()) {
×
1238
        set_rc_status(std::nullopt, {rc_channels.rssi});
×
1239
    }
1240

1241
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1242
    _rc_status_subscriptions.queue(
×
1243
        rc_status(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1244
}
×
1245

1246
void TelemetryImpl::process_unix_epoch_time(const mavlink_message_t& message)
×
1247
{
1248
    mavlink_system_time_t system_time;
×
1249
    mavlink_msg_system_time_decode(&message, &system_time);
×
1250

1251
    set_unix_epoch_time_us(system_time.time_unix_usec);
×
1252

1253
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1254
    _unix_epoch_time_subscriptions.queue(
×
1255
        unix_epoch_time(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1256
}
×
1257

1258
void TelemetryImpl::process_actuator_control_target(const mavlink_message_t& message)
×
1259
{
1260
    mavlink_set_actuator_control_target_t target;
×
1261
    mavlink_msg_set_actuator_control_target_decode(&message, &target);
×
1262

1263
    uint32_t group = target.group_mlx;
×
1264
    std::vector<float> controls;
×
1265

1266
    const unsigned control_size = sizeof(target.controls) / sizeof(target.controls[0]);
×
1267
    // Can't use std::copy because target is packed.
1268
    for (std::size_t i = 0; i < control_size; ++i) {
×
1269
        controls.push_back(target.controls[i]);
×
1270
    }
1271

1272
    set_actuator_control_target(group, controls);
×
1273

1274
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1275
    _actuator_control_target_subscriptions.queue(
×
1276
        actuator_control_target(),
×
1277
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1278
}
×
1279

1280
void TelemetryImpl::process_actuator_output_status(const mavlink_message_t& message)
×
1281
{
1282
    mavlink_actuator_output_status_t status;
×
1283
    mavlink_msg_actuator_output_status_decode(&message, &status);
×
1284

1285
    uint32_t active = status.active;
×
1286
    std::vector<float> actuators;
×
1287

1288
    const unsigned actuators_size = sizeof(status.actuator) / sizeof(status.actuator[0]);
×
1289
    // Can't use std::copy because status is packed.
1290
    for (std::size_t i = 0; i < actuators_size; ++i) {
×
1291
        actuators.push_back(status.actuator[i]);
×
1292
    }
1293

1294
    set_actuator_output_status(active, actuators);
×
1295

1296
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1297
    _actuator_output_status_subscriptions.queue(actuator_output_status(), [this](const auto& func) {
×
1298
        _system_impl->call_user_callback(func);
×
1299
    });
×
1300
}
×
1301

1302
void TelemetryImpl::process_odometry(const mavlink_message_t& message)
×
1303
{
1304
    mavlink_odometry_t odometry_msg;
×
1305
    mavlink_msg_odometry_decode(&message, &odometry_msg);
×
1306

1307
    Telemetry::Odometry odometry_struct{};
×
1308

1309
    odometry_struct.time_usec = odometry_msg.time_usec;
×
1310
    odometry_struct.frame_id = static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.frame_id);
×
1311
    odometry_struct.child_frame_id =
×
1312
        static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.child_frame_id);
×
1313

1314
    odometry_struct.position_body.x_m = odometry_msg.x;
×
1315
    odometry_struct.position_body.y_m = odometry_msg.y;
×
1316
    odometry_struct.position_body.z_m = odometry_msg.z;
×
1317

1318
    odometry_struct.q.w = odometry_msg.q[0];
×
1319
    odometry_struct.q.x = odometry_msg.q[1];
×
1320
    odometry_struct.q.y = odometry_msg.q[2];
×
1321
    odometry_struct.q.z = odometry_msg.q[3];
×
1322

1323
    odometry_struct.velocity_body.x_m_s = odometry_msg.vx;
×
1324
    odometry_struct.velocity_body.y_m_s = odometry_msg.vy;
×
1325
    odometry_struct.velocity_body.z_m_s = odometry_msg.vz;
×
1326

1327
    odometry_struct.angular_velocity_body.roll_rad_s = odometry_msg.rollspeed;
×
1328
    odometry_struct.angular_velocity_body.pitch_rad_s = odometry_msg.pitchspeed;
×
1329
    odometry_struct.angular_velocity_body.yaw_rad_s = odometry_msg.yawspeed;
×
1330

1331
    const std::size_t len_pose_covariance =
×
1332
        sizeof(odometry_msg.pose_covariance) / sizeof(odometry_msg.pose_covariance[0]);
1333
    for (std::size_t i = 0; i < len_pose_covariance; ++i) {
×
1334
        odometry_struct.pose_covariance.covariance_matrix.push_back(
×
1335
            odometry_msg.pose_covariance[i]);
×
1336
    }
1337

1338
    const std::size_t len_velocity_covariance =
×
1339
        sizeof(odometry_msg.velocity_covariance) / sizeof(odometry_msg.velocity_covariance[0]);
1340
    for (std::size_t i = 0; i < len_velocity_covariance; ++i) {
×
1341
        odometry_struct.velocity_covariance.covariance_matrix.push_back(
×
1342
            odometry_msg.velocity_covariance[i]);
×
1343
    }
1344

1345
    set_odometry(odometry_struct);
×
1346

1347
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1348
    _odometry_subscriptions.queue(
×
1349
        odometry(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1350
}
×
1351

1352
void TelemetryImpl::process_distance_sensor(const mavlink_message_t& message)
×
1353
{
1354
    mavlink_distance_sensor_t distance_sensor_msg;
×
1355
    mavlink_msg_distance_sensor_decode(&message, &distance_sensor_msg);
×
1356

1357
    Telemetry::DistanceSensor distance_sensor_struct{};
×
1358

1359
    distance_sensor_struct.minimum_distance_m =
×
1360
        static_cast<float>(distance_sensor_msg.min_distance) * 1e-2f; // cm to m
×
1361
    distance_sensor_struct.maximum_distance_m =
×
1362
        static_cast<float>(distance_sensor_msg.max_distance) * 1e-2f; // cm to m
×
1363
    distance_sensor_struct.current_distance_m =
×
1364
        static_cast<float>(distance_sensor_msg.current_distance) * 1e-2f; // cm to m
×
1365
    distance_sensor_struct.orientation = extractOrientation(distance_sensor_msg);
×
1366

1367
    set_distance_sensor(distance_sensor_struct);
×
1368

1369
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1370
    _distance_sensor_subscriptions.queue(
×
1371
        distance_sensor(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1372
}
×
1373

1374
Telemetry::EulerAngle
1375
TelemetryImpl::extractOrientation(mavlink_distance_sensor_t distance_sensor_msg)
×
1376
{
1377
    MavSensorOrientation orientation =
×
1378
        static_cast<MavSensorOrientation>(distance_sensor_msg.orientation);
×
1379

1380
    Telemetry::EulerAngle euler_angle;
×
1381
    euler_angle.roll_deg = 0;
×
1382
    euler_angle.pitch_deg = 0;
×
1383
    euler_angle.yaw_deg = 0;
×
1384

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

1581
    return euler_angle;
×
1582
}
1583

1584
void TelemetryImpl::process_scaled_pressure(const mavlink_message_t& message)
×
1585
{
1586
    mavlink_scaled_pressure_t scaled_pressure_msg;
×
1587
    mavlink_msg_scaled_pressure_decode(&message, &scaled_pressure_msg);
×
1588

1589
    Telemetry::ScaledPressure scaled_pressure_struct{};
×
1590

1591
    scaled_pressure_struct.timestamp_us =
×
1592
        static_cast<uint64_t>(scaled_pressure_msg.time_boot_ms) * 1000;
×
1593
    scaled_pressure_struct.absolute_pressure_hpa = scaled_pressure_msg.press_abs;
×
1594
    scaled_pressure_struct.differential_pressure_hpa = scaled_pressure_msg.press_diff;
×
1595
    scaled_pressure_struct.temperature_deg =
×
1596
        static_cast<float>(scaled_pressure_msg.temperature) * 1e-2f;
×
1597
    scaled_pressure_struct.differential_pressure_temperature_deg =
×
1598
        static_cast<float>(scaled_pressure_msg.temperature_press_diff) * 1e-2f;
×
1599

1600
    set_scaled_pressure(scaled_pressure_struct);
×
1601

1602
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1603
    _scaled_pressure_subscriptions.queue(
×
1604
        scaled_pressure(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1605
}
×
1606

1607
Telemetry::LandedState
1608
TelemetryImpl::to_landed_state(mavlink_extended_sys_state_t extended_sys_state)
×
1609
{
1610
    switch (extended_sys_state.landed_state) {
×
1611
        case MAV_LANDED_STATE_IN_AIR:
×
1612
            return Telemetry::LandedState::InAir;
×
1613
        case MAV_LANDED_STATE_TAKEOFF:
×
1614
            return Telemetry::LandedState::TakingOff;
×
1615
        case MAV_LANDED_STATE_LANDING:
×
1616
            return Telemetry::LandedState::Landing;
×
1617
        case MAV_LANDED_STATE_ON_GROUND:
×
1618
            return Telemetry::LandedState::OnGround;
×
1619
        default:
×
1620
            return Telemetry::LandedState::Unknown;
×
1621
    }
1622
}
1623

1624
Telemetry::VtolState TelemetryImpl::to_vtol_state(mavlink_extended_sys_state_t extended_sys_state)
×
1625
{
1626
    switch (extended_sys_state.vtol_state) {
×
1627
        case MAV_VTOL_STATE::MAV_VTOL_STATE_TRANSITION_TO_FW:
×
1628
            return Telemetry::VtolState::TransitionToFw;
×
1629
        case MAV_VTOL_STATE_TRANSITION_TO_MC:
×
1630
            return Telemetry::VtolState::TransitionToMc;
×
1631
        case MAV_VTOL_STATE_MC:
×
1632
            return Telemetry::VtolState::Mc;
×
1633
        case MAV_VTOL_STATE_FW:
×
1634
            return Telemetry::VtolState::Fw;
×
1635
        default:
×
1636
            return Telemetry::VtolState::Undefined;
×
1637
    }
1638
}
1639

1640
Telemetry::FlightMode TelemetryImpl::telemetry_flight_mode_from_flight_mode(FlightMode flight_mode)
1✔
1641
{
1642
    switch (flight_mode) {
1✔
1643
        case FlightMode::Ready:
×
1644
            return Telemetry::FlightMode::Ready;
×
1645
        case FlightMode::Takeoff:
×
1646
            return Telemetry::FlightMode::Takeoff;
×
1647
        case FlightMode::Hold:
×
1648
            return Telemetry::FlightMode::Hold;
×
1649
        case FlightMode::Mission:
×
1650
            return Telemetry::FlightMode::Mission;
×
1651
        case FlightMode::ReturnToLaunch:
×
1652
            return Telemetry::FlightMode::ReturnToLaunch;
×
1653
        case FlightMode::Land:
×
1654
            return Telemetry::FlightMode::Land;
×
1655
        case FlightMode::Offboard:
×
1656
            return Telemetry::FlightMode::Offboard;
×
1657
        case FlightMode::FollowMe:
×
1658
            return Telemetry::FlightMode::FollowMe;
×
1659
        case FlightMode::Manual:
×
1660
            return Telemetry::FlightMode::Manual;
×
1661
        case FlightMode::Posctl:
×
1662
            return Telemetry::FlightMode::Posctl;
×
1663
        case FlightMode::Altctl:
×
1664
            return Telemetry::FlightMode::Altctl;
×
1665
        case FlightMode::Rattitude:
×
1666
            return Telemetry::FlightMode::Rattitude;
×
1667
        case FlightMode::Acro:
×
1668
            return Telemetry::FlightMode::Acro;
×
1669
        case FlightMode::Stabilized:
×
1670
            return Telemetry::FlightMode::Stabilized;
×
1671
        default:
1✔
1672
            return Telemetry::FlightMode::Unknown;
1✔
1673
    }
1674
}
1675

1676
Telemetry::PositionVelocityNed TelemetryImpl::position_velocity_ned() const
×
1677
{
1678
    std::lock_guard<std::mutex> lock(_position_velocity_ned_mutex);
×
1679
    return _position_velocity_ned;
×
1680
}
×
1681

1682
void TelemetryImpl::set_position_velocity_ned(Telemetry::PositionVelocityNed position_velocity_ned)
×
1683
{
1684
    std::lock_guard<std::mutex> lock(_position_velocity_ned_mutex);
×
1685
    _position_velocity_ned = position_velocity_ned;
×
1686
}
×
1687

1688
Telemetry::Position TelemetryImpl::position() const
×
1689
{
1690
    std::lock_guard<std::mutex> lock(_position_mutex);
×
1691
    return _position;
×
1692
}
×
1693

1694
void TelemetryImpl::set_position(Telemetry::Position position)
×
1695
{
1696
    std::lock_guard<std::mutex> lock(_position_mutex);
×
1697
    _position = position;
×
1698
}
×
1699

1700
Telemetry::Heading TelemetryImpl::heading() const
×
1701
{
1702
    std::lock_guard<std::mutex> lock(_heading_mutex);
×
1703
    return _heading;
×
1704
}
×
1705

1706
void TelemetryImpl::set_heading(Telemetry::Heading heading)
×
1707
{
1708
    std::lock_guard<std::mutex> lock(_heading_mutex);
×
1709
    _heading = heading;
×
1710
}
×
1711

1712
Telemetry::Altitude TelemetryImpl::altitude() const
×
1713
{
1714
    std::lock_guard<std::mutex> lock(_altitude_mutex);
×
1715
    return _altitude;
×
1716
}
×
1717

1718
void TelemetryImpl::set_altitude(Telemetry::Altitude altitude)
×
1719
{
1720
    std::lock_guard<std::mutex> lock(_altitude_mutex);
×
1721
    _altitude = altitude;
×
1722
}
×
1723

1724
Telemetry::Position TelemetryImpl::home() const
×
1725
{
1726
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
1727
    return _home_position;
×
1728
}
×
1729

1730
void TelemetryImpl::set_home_position(Telemetry::Position home_position)
×
1731
{
1732
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
1733
    _home_position = home_position;
×
1734
}
×
1735

1736
bool TelemetryImpl::armed() const
1✔
1737
{
1738
    return _armed;
1✔
1739
}
1740

1741
bool TelemetryImpl::in_air() const
×
1742
{
1743
    return _in_air;
×
1744
}
1745

1746
void TelemetryImpl::set_in_air(bool in_air_new)
×
1747
{
1748
    _in_air = in_air_new;
×
1749
}
×
1750

1751
void TelemetryImpl::set_status_text(Telemetry::StatusText status_text)
3✔
1752
{
1753
    std::lock_guard<std::mutex> lock(_status_text_mutex);
3✔
1754
    _status_text = status_text;
3✔
1755
}
3✔
1756

1757
Telemetry::StatusText TelemetryImpl::status_text() const
3✔
1758
{
1759
    std::lock_guard<std::mutex> lock(_status_text_mutex);
3✔
1760
    return _status_text;
3✔
1761
}
3✔
1762

1763
void TelemetryImpl::set_armed(bool armed_new)
1✔
1764
{
1765
    _armed = armed_new;
1✔
1766
}
1✔
1767

1768
Telemetry::Quaternion TelemetryImpl::attitude_quaternion() const
×
1769
{
1770
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1771
    return _attitude_quaternion;
×
1772
}
×
1773

1774
Telemetry::AngularVelocityBody TelemetryImpl::attitude_angular_velocity_body() const
×
1775
{
1776
    std::lock_guard<std::mutex> lock(_attitude_angular_velocity_body_mutex);
×
1777
    return _attitude_angular_velocity_body;
×
1778
}
×
1779

1780
Telemetry::GroundTruth TelemetryImpl::ground_truth() const
×
1781
{
1782
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
1783
    return _ground_truth;
×
1784
}
×
1785

1786
Telemetry::FixedwingMetrics TelemetryImpl::fixedwing_metrics() const
×
1787
{
1788
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
1789
    return _fixedwing_metrics;
×
1790
}
×
1791

1792
Telemetry::EulerAngle TelemetryImpl::attitude_euler() const
×
1793
{
1794
    std::lock_guard<std::mutex> lock(_attitude_euler_mutex);
×
1795
    return _attitude_euler;
×
1796
}
×
1797

1798
void TelemetryImpl::set_attitude_quaternion(Telemetry::Quaternion quaternion)
×
1799
{
1800
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1801
    _attitude_quaternion = quaternion;
×
1802
}
×
1803

1804
void TelemetryImpl::set_attitude_euler(Telemetry::EulerAngle euler)
×
1805
{
1806
    std::lock_guard<std::mutex> lock(_attitude_euler_mutex);
×
1807
    _attitude_euler = euler;
×
1808
}
×
1809

1810
void TelemetryImpl::set_attitude_angular_velocity_body(
×
1811
    Telemetry::AngularVelocityBody angular_velocity_body)
1812
{
1813
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1814
    _attitude_angular_velocity_body = angular_velocity_body;
×
1815
}
×
1816

1817
void TelemetryImpl::set_ground_truth(Telemetry::GroundTruth ground_truth)
×
1818
{
1819
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
1820
    _ground_truth = ground_truth;
×
1821
}
×
1822

1823
void TelemetryImpl::set_fixedwing_metrics(Telemetry::FixedwingMetrics fixedwing_metrics)
×
1824
{
1825
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
1826
    _fixedwing_metrics = fixedwing_metrics;
×
1827
}
×
1828

1829
Telemetry::VelocityNed TelemetryImpl::velocity_ned() const
×
1830
{
1831
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
1832
    return _velocity_ned;
×
1833
}
×
1834

1835
void TelemetryImpl::set_velocity_ned(Telemetry::VelocityNed velocity_ned)
×
1836
{
1837
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
1838
    _velocity_ned = velocity_ned;
×
1839
}
×
1840

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

1847
void TelemetryImpl::set_imu_reading_ned(Telemetry::Imu imu_reading_ned)
×
1848
{
1849
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
1850
    _imu_reading_ned = imu_reading_ned;
×
1851
}
×
1852

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

1859
void TelemetryImpl::set_scaled_imu(Telemetry::Imu scaled_imu)
×
1860
{
1861
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
1862
    _scaled_imu = scaled_imu;
×
1863
}
×
1864

1865
Telemetry::Imu TelemetryImpl::raw_imu() const
×
1866
{
1867
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
1868
    return _raw_imu;
×
1869
}
×
1870

1871
void TelemetryImpl::set_raw_imu(Telemetry::Imu raw_imu)
×
1872
{
1873
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
1874
    _raw_imu = raw_imu;
×
1875
}
×
1876

1877
Telemetry::GpsInfo TelemetryImpl::gps_info() const
×
1878
{
1879
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
×
1880
    return _gps_info;
×
1881
}
×
1882

1883
void TelemetryImpl::set_gps_info(Telemetry::GpsInfo gps_info)
×
1884
{
1885
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
×
1886
    _gps_info = gps_info;
×
1887
}
×
1888

1889
Telemetry::RawGps TelemetryImpl::raw_gps() const
×
1890
{
1891
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
×
1892
    return _raw_gps;
×
1893
}
×
1894

1895
void TelemetryImpl::set_raw_gps(Telemetry::RawGps raw_gps)
×
1896
{
1897
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
×
1898
    _raw_gps = raw_gps;
×
1899
}
×
1900

1901
Telemetry::Battery TelemetryImpl::battery() const
×
1902
{
1903
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
1904
    return _battery;
×
1905
}
×
1906

1907
void TelemetryImpl::set_battery(Telemetry::Battery battery)
×
1908
{
1909
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
1910
    _battery = battery;
×
1911
}
×
1912

1913
Telemetry::FlightMode TelemetryImpl::flight_mode() const
×
1914
{
1915
    return telemetry_flight_mode_from_flight_mode(_system_impl->get_flight_mode());
×
1916
}
1917

1918
Telemetry::Health TelemetryImpl::health() const
1✔
1919
{
1920
    std::lock_guard<std::mutex> lock(_health_mutex);
1✔
1921
    return _health;
2✔
1922
}
1✔
1923

1924
bool TelemetryImpl::health_all_ok() const
1✔
1925
{
1926
    std::lock_guard<std::mutex> lock(_health_mutex);
1✔
1927
    if (_health.is_gyrometer_calibration_ok && _health.is_accelerometer_calibration_ok &&
1✔
1928
        _health.is_magnetometer_calibration_ok && _health.is_local_position_ok &&
×
1929
        _health.is_global_position_ok && _health.is_home_position_ok) {
×
1930
        return true;
×
1931
    } else {
1932
        return false;
1✔
1933
    }
1934
}
1✔
1935

1936
Telemetry::RcStatus TelemetryImpl::rc_status() const
×
1937
{
1938
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
1939
    return _rc_status;
×
1940
}
×
1941

1942
uint64_t TelemetryImpl::unix_epoch_time() const
×
1943
{
1944
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
1945
    return _unix_epoch_time_us;
×
1946
}
×
1947

1948
Telemetry::ActuatorControlTarget TelemetryImpl::actuator_control_target() const
×
1949
{
1950
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
1951
    return _actuator_control_target;
×
1952
}
×
1953

1954
Telemetry::ActuatorOutputStatus TelemetryImpl::actuator_output_status() const
×
1955
{
1956
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
1957
    return _actuator_output_status;
×
1958
}
×
1959

1960
Telemetry::Odometry TelemetryImpl::odometry() const
×
1961
{
1962
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
1963
    return _odometry;
×
1964
}
×
1965

1966
Telemetry::DistanceSensor TelemetryImpl::distance_sensor() const
×
1967
{
1968
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
1969
    return _distance_sensor;
×
1970
}
×
1971

1972
Telemetry::ScaledPressure TelemetryImpl::scaled_pressure() const
×
1973
{
1974
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
1975
    return _scaled_pressure;
×
1976
}
×
1977

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

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

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

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

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

2008
void TelemetryImpl::set_health_magnetometer_calibration(bool ok)
×
2009
{
2010
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2011
    _health.is_magnetometer_calibration_ok = ok;
×
2012
}
×
2013

2014
void TelemetryImpl::set_health_armable(bool ok)
×
2015
{
2016
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2017
    _health.is_armable = ok;
×
2018
}
×
2019

2020
Telemetry::VtolState TelemetryImpl::vtol_state() const
×
2021
{
2022
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
2023
    return _vtol_state;
×
2024
}
×
2025

2026
void TelemetryImpl::set_vtol_state(Telemetry::VtolState vtol_state)
×
2027
{
2028
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
2029
    _vtol_state = vtol_state;
×
2030
}
×
2031

2032
Telemetry::LandedState TelemetryImpl::landed_state() const
×
2033
{
2034
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2035
    return _landed_state;
×
2036
}
×
2037

2038
void TelemetryImpl::set_landed_state(Telemetry::LandedState landed_state)
×
2039
{
2040
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2041
    _landed_state = landed_state;
×
2042
}
×
2043

2044
void TelemetryImpl::set_rc_status(
×
2045
    std::optional<bool> maybe_available, std::optional<float> maybe_signal_strength_percent)
2046
{
2047
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
2048

2049
    if (maybe_available) {
×
2050
        _rc_status.is_available = maybe_available.value();
×
2051
        if (maybe_available.value()) {
×
2052
            _rc_status.was_available_once = true;
×
2053
        }
2054
    }
2055

2056
    if (maybe_signal_strength_percent) {
×
2057
        _rc_status.signal_strength_percent = maybe_signal_strength_percent.value();
×
2058
    }
2059
}
×
2060

2061
void TelemetryImpl::set_unix_epoch_time_us(uint64_t time_us)
×
2062
{
2063
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
2064
    _unix_epoch_time_us = time_us;
×
2065
}
×
2066

2067
void TelemetryImpl::set_actuator_control_target(uint8_t group, const std::vector<float>& controls)
×
2068
{
2069
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
2070
    _actuator_control_target.group = group;
×
2071
    _actuator_control_target.controls = controls;
×
2072
}
×
2073

2074
void TelemetryImpl::set_actuator_output_status(uint32_t active, const std::vector<float>& actuators)
×
2075
{
2076
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
2077
    _actuator_output_status.active = active;
×
2078
    _actuator_output_status.actuator = actuators;
×
2079
}
×
2080

2081
void TelemetryImpl::set_odometry(Telemetry::Odometry& odometry)
×
2082
{
2083
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
2084
    _odometry = odometry;
×
2085
}
×
2086

2087
void TelemetryImpl::set_distance_sensor(Telemetry::DistanceSensor& distance_sensor)
×
2088
{
2089
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
2090
    _distance_sensor = distance_sensor;
×
2091
}
×
2092

2093
void TelemetryImpl::set_scaled_pressure(Telemetry::ScaledPressure& scaled_pressure)
×
2094
{
2095
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
2096
    _scaled_pressure = scaled_pressure;
×
2097
}
×
2098

2099
Telemetry::PositionVelocityNedHandle TelemetryImpl::subscribe_position_velocity_ned(
×
2100
    const Telemetry::PositionVelocityNedCallback& callback)
2101
{
2102
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2103
    return _position_velocity_ned_subscriptions.subscribe(callback);
×
2104
}
×
2105

2106
void TelemetryImpl::unsubscribe_position_velocity_ned(Telemetry::PositionVelocityNedHandle handle)
×
2107
{
2108
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2109
    _position_velocity_ned_subscriptions.unsubscribe(handle);
×
2110
}
×
2111

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

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

2125
Telemetry::HomeHandle TelemetryImpl::subscribe_home(const Telemetry::PositionCallback& callback)
×
2126
{
2127
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2128
    return _home_position_subscriptions.subscribe(callback);
×
2129
}
×
2130

2131
void TelemetryImpl::unsubscribe_home(Telemetry::HomeHandle handle)
×
2132
{
2133
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2134
    _home_position_subscriptions.unsubscribe(handle);
×
2135
}
×
2136

2137
Telemetry::InAirHandle TelemetryImpl::subscribe_in_air(const Telemetry::InAirCallback& callback)
×
2138
{
2139
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2140
    return _in_air_subscriptions.subscribe(callback);
×
2141
}
×
2142

2143
void TelemetryImpl::unsubscribe_in_air(Telemetry::InAirHandle handle)
×
2144
{
2145
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2146
    return _in_air_subscriptions.unsubscribe(handle);
×
2147
}
×
2148

2149
Telemetry::StatusTextHandle
2150
TelemetryImpl::subscribe_status_text(const Telemetry::StatusTextCallback& callback)
2✔
2151
{
2152
    std::lock_guard<std::mutex> lock(_subscription_mutex);
2✔
2153
    return _status_text_subscriptions.subscribe(callback);
2✔
2154
}
2✔
2155

2156
void TelemetryImpl::unsubscribe_status_text(Handle<Telemetry::StatusText> handle)
1✔
2157
{
2158
    std::lock_guard<std::mutex> lock(_subscription_mutex);
1✔
2159
    _status_text_subscriptions.unsubscribe(handle);
1✔
2160
}
1✔
2161

2162
Telemetry::ArmedHandle TelemetryImpl::subscribe_armed(const Telemetry::ArmedCallback& callback)
×
2163
{
2164
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2165
    return _armed_subscriptions.subscribe(callback);
×
2166
}
×
2167

2168
void TelemetryImpl::unsubscribe_armed(Telemetry::ArmedHandle handle)
×
2169
{
2170
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2171
    _armed_subscriptions.unsubscribe(handle);
×
2172
}
×
2173

2174
Telemetry::AttitudeQuaternionHandle
2175
TelemetryImpl::subscribe_attitude_quaternion(const Telemetry::AttitudeQuaternionCallback& callback)
×
2176
{
2177
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2178
    return _attitude_quaternion_angle_subscriptions.subscribe(callback);
×
2179
}
×
2180

2181
void TelemetryImpl::unsubscribe_attitude_quaternion(Telemetry::AttitudeQuaternionHandle handle)
×
2182
{
2183
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2184
    _attitude_quaternion_angle_subscriptions.unsubscribe(handle);
×
2185
}
×
2186

2187
Telemetry::AttitudeEulerHandle
2188
TelemetryImpl::subscribe_attitude_euler(const Telemetry::AttitudeEulerCallback& callback)
×
2189
{
2190
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2191
    return _attitude_euler_angle_subscriptions.subscribe(callback);
×
2192
}
×
2193

2194
void TelemetryImpl::unsubscribe_attitude_euler(Telemetry::AttitudeEulerHandle handle)
×
2195
{
2196
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2197
    _attitude_euler_angle_subscriptions.unsubscribe(handle);
×
2198
}
×
2199

2200
Telemetry::AttitudeAngularVelocityBodyHandle
2201
TelemetryImpl::subscribe_attitude_angular_velocity_body(
×
2202
    const Telemetry::AttitudeAngularVelocityBodyCallback& callback)
2203
{
2204
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2205
    return _attitude_angular_velocity_body_subscriptions.subscribe(callback);
×
2206
}
×
2207

2208
void TelemetryImpl::unsubscribe_attitude_angular_velocity_body(
×
2209
    Telemetry::AttitudeAngularVelocityBodyHandle handle)
2210
{
2211
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2212
    _attitude_angular_velocity_body_subscriptions.unsubscribe(handle);
×
2213
}
×
2214

2215
Telemetry::FixedwingMetricsHandle
2216
TelemetryImpl::subscribe_fixedwing_metrics(const Telemetry::FixedwingMetricsCallback& callback)
×
2217
{
2218
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2219
    return _fixedwing_metrics_subscriptions.subscribe(callback);
×
2220
}
×
2221

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

2228
Telemetry::GroundTruthHandle
2229
TelemetryImpl::subscribe_ground_truth(const Telemetry::GroundTruthCallback& callback)
×
2230
{
2231
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2232
    return _ground_truth_subscriptions.subscribe(callback);
×
2233
}
×
2234

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

2241
Telemetry::VelocityNedHandle
2242
TelemetryImpl::subscribe_velocity_ned(const Telemetry::VelocityNedCallback& callback)
×
2243
{
2244
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2245
    return _velocity_ned_subscriptions.subscribe(callback);
×
2246
}
×
2247

2248
void TelemetryImpl::unsubscribe_velocity_ned(Telemetry::VelocityNedHandle handle)
×
2249
{
2250
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2251
    _velocity_ned_subscriptions.unsubscribe(handle);
×
2252
}
×
2253

2254
Telemetry::ImuHandle TelemetryImpl::subscribe_imu(const Telemetry::ImuCallback& callback)
×
2255
{
2256
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2257
    return _imu_reading_ned_subscriptions.subscribe(callback);
×
2258
}
×
2259

2260
void TelemetryImpl::unsubscribe_imu(Telemetry::ImuHandle handle)
×
2261
{
2262
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2263
    return _imu_reading_ned_subscriptions.unsubscribe(handle);
×
2264
}
×
2265

2266
Telemetry::ScaledImuHandle
2267
TelemetryImpl::subscribe_scaled_imu(const Telemetry::ScaledImuCallback& callback)
×
2268
{
2269
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2270
    return _scaled_imu_subscriptions.subscribe(callback);
×
2271
}
×
2272

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

2279
Telemetry::RawImuHandle TelemetryImpl::subscribe_raw_imu(const Telemetry::RawImuCallback& callback)
×
2280
{
2281
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2282
    return _raw_imu_subscriptions.subscribe(callback);
×
2283
}
×
2284

2285
void TelemetryImpl::unsubscribe_raw_imu(Telemetry::RawImuHandle handle)
×
2286
{
2287
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2288
    _raw_imu_subscriptions.unsubscribe(handle);
×
2289
}
×
2290

2291
Telemetry::GpsInfoHandle
2292
TelemetryImpl::subscribe_gps_info(const Telemetry::GpsInfoCallback& callback)
×
2293
{
2294
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2295
    return _gps_info_subscriptions.subscribe(callback);
×
2296
}
×
2297

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

2304
Telemetry::RawGpsHandle TelemetryImpl::subscribe_raw_gps(const Telemetry::RawGpsCallback& callback)
×
2305
{
2306
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2307
    return _raw_gps_subscriptions.subscribe(callback);
×
2308
}
×
2309

2310
void TelemetryImpl::unsubscribe_raw_gps(Telemetry::RawGpsHandle handle)
×
2311
{
2312
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2313
    _raw_gps_subscriptions.unsubscribe(handle);
×
2314
}
×
2315

2316
Telemetry::BatteryHandle
2317
TelemetryImpl::subscribe_battery(const Telemetry::BatteryCallback& callback)
×
2318
{
2319
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2320
    return _battery_subscriptions.subscribe(callback);
×
2321
}
×
2322

2323
void TelemetryImpl::unsubscribe_battery(Telemetry::BatteryHandle handle)
×
2324
{
2325
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2326
    _battery_subscriptions.unsubscribe(handle);
×
2327
}
×
2328

2329
Telemetry::FlightModeHandle
2330
TelemetryImpl::subscribe_flight_mode(const Telemetry::FlightModeCallback& callback)
×
2331
{
2332
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2333
    return _flight_mode_subscriptions.subscribe(callback);
×
2334
}
×
2335

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

2342
Telemetry::HealthHandle TelemetryImpl::subscribe_health(const Telemetry::HealthCallback& callback)
×
2343
{
2344
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2345
    return _health_subscriptions.subscribe(callback);
×
2346
}
×
2347

2348
void TelemetryImpl::unsubscribe_health(Telemetry::HealthHandle handle)
×
2349
{
2350
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2351
    _health_subscriptions.unsubscribe(handle);
×
2352
}
×
2353

2354
Telemetry::HealthAllOkHandle
2355
TelemetryImpl::subscribe_health_all_ok(const Telemetry::HealthAllOkCallback& callback)
×
2356
{
2357
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2358
    return _health_all_ok_subscriptions.subscribe(callback);
×
2359
}
×
2360

2361
void TelemetryImpl::unsubscribe_health_all_ok(Telemetry::HealthAllOkHandle handle)
×
2362
{
2363
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2364
    _health_all_ok_subscriptions.unsubscribe(handle);
×
2365
}
×
2366

2367
Telemetry::VtolStateHandle
2368
TelemetryImpl::subscribe_vtol_state(const Telemetry::VtolStateCallback& callback)
×
2369
{
2370
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2371
    return _vtol_state_subscriptions.subscribe(callback);
×
2372
}
×
2373

2374
void TelemetryImpl::unsubscribe_vtol_state(Telemetry::VtolStateHandle handle)
×
2375
{
2376
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2377
    _vtol_state_subscriptions.unsubscribe(handle);
×
2378
}
×
2379

2380
Telemetry::LandedStateHandle
2381
TelemetryImpl::subscribe_landed_state(const Telemetry::LandedStateCallback& callback)
×
2382
{
2383
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2384
    return _landed_state_subscriptions.subscribe(callback);
×
2385
}
×
2386

2387
void TelemetryImpl::unsubscribe_landed_state(Telemetry::LandedStateHandle handle)
×
2388
{
2389
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2390
    _landed_state_subscriptions.unsubscribe(handle);
×
2391
}
×
2392

2393
Telemetry::RcStatusHandle
2394
TelemetryImpl::subscribe_rc_status(const Telemetry::RcStatusCallback& callback)
×
2395
{
2396
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2397
    return _rc_status_subscriptions.subscribe(callback);
×
2398
}
×
2399

2400
void TelemetryImpl::unsubscribe_rc_status(Telemetry::RcStatusHandle handle)
×
2401
{
2402
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2403
    _rc_status_subscriptions.unsubscribe(handle);
×
2404
}
×
2405

2406
Telemetry::UnixEpochTimeHandle
2407
TelemetryImpl::subscribe_unix_epoch_time(const Telemetry::UnixEpochTimeCallback& callback)
×
2408
{
2409
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2410
    return _unix_epoch_time_subscriptions.subscribe(callback);
×
2411
}
×
2412

2413
void TelemetryImpl::unsubscribe_unix_epoch_time(Telemetry::UnixEpochTimeHandle handle)
×
2414
{
2415
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2416
    _unix_epoch_time_subscriptions.unsubscribe(handle);
×
2417
}
×
2418

2419
Telemetry::ActuatorControlTargetHandle TelemetryImpl::subscribe_actuator_control_target(
×
2420
    const Telemetry::ActuatorControlTargetCallback& callback)
2421
{
2422
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2423
    return _actuator_control_target_subscriptions.subscribe(callback);
×
2424
}
×
2425

2426
void TelemetryImpl::unsubscribe_actuator_control_target(
×
2427
    Telemetry::ActuatorControlTargetHandle handle)
2428
{
2429
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2430
    _actuator_control_target_subscriptions.unsubscribe(handle);
×
2431
}
×
2432

2433
Telemetry::ActuatorOutputStatusHandle TelemetryImpl::subscribe_actuator_output_status(
×
2434
    const Telemetry::ActuatorOutputStatusCallback& callback)
2435
{
2436
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2437
    return _actuator_output_status_subscriptions.subscribe(callback);
×
2438
}
×
2439

2440
void TelemetryImpl::unsubscribe_actuator_output_status(Telemetry::ActuatorOutputStatusHandle handle)
×
2441
{
2442
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2443
    _actuator_output_status_subscriptions.unsubscribe(handle);
×
2444
}
×
2445

2446
Telemetry::OdometryHandle
2447
TelemetryImpl::subscribe_odometry(const Telemetry::OdometryCallback& callback)
×
2448
{
2449
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2450
    return _odometry_subscriptions.subscribe(callback);
×
2451
}
×
2452

2453
void TelemetryImpl::unsubscribe_odometry(Telemetry::OdometryHandle handle)
×
2454
{
2455
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2456
    _odometry_subscriptions.unsubscribe(handle);
×
2457
}
×
2458

2459
Telemetry::DistanceSensorHandle
2460
TelemetryImpl::subscribe_distance_sensor(const Telemetry::DistanceSensorCallback& callback)
×
2461
{
2462
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2463
    return _distance_sensor_subscriptions.subscribe(callback);
×
2464
}
×
2465

2466
void TelemetryImpl::unsubscribe_distance_sensor(Telemetry::DistanceSensorHandle handle)
×
2467
{
2468
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2469
    _distance_sensor_subscriptions.unsubscribe(handle);
×
2470
}
×
2471

2472
Telemetry::ScaledPressureHandle
2473
TelemetryImpl::subscribe_scaled_pressure(const Telemetry::ScaledPressureCallback& callback)
×
2474
{
2475
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2476
    return _scaled_pressure_subscriptions.subscribe(callback);
×
2477
}
×
2478

2479
void TelemetryImpl::unsubscribe_scaled_pressure(Telemetry::ScaledPressureHandle handle)
×
2480
{
2481
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2482
    _scaled_pressure_subscriptions.unsubscribe(handle);
×
2483
}
×
2484

2485
Telemetry::HeadingHandle
2486
TelemetryImpl::subscribe_heading(const Telemetry::HeadingCallback& callback)
×
2487
{
2488
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2489
    return _heading_subscriptions.subscribe(callback);
×
2490
}
×
2491

2492
void TelemetryImpl::unsubscribe_heading(Telemetry::HeadingHandle handle)
×
2493
{
2494
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2495
    _heading_subscriptions.unsubscribe(handle);
×
2496
}
×
2497

2498
Telemetry::AltitudeHandle
2499
TelemetryImpl::subscribe_altitude(const Telemetry::AltitudeCallback& callback)
×
2500
{
2501
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2502
    return _altitude_subscriptions.subscribe(callback);
×
2503
}
×
2504

2505
void TelemetryImpl::unsubscribe_altitude(Telemetry::AltitudeHandle handle)
×
2506
{
2507
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2508
    _altitude_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