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

mavlink / MAVSDK / 4048518148

pending completion
4048518148

push

github

GitHub
Merge pull request #1971 from mavlink/pr-fix-distance

6 of 6 new or added lines in 1 file covered. (100.0%)

7387 of 23647 relevant lines covered (31.24%)

21.98 hits per line

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

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

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

14
namespace mavsdk {
15

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

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

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

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

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

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

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

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

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

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

91
    _parent->register_mavlink_message_handler(
1✔
92
        MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS,
93
        [this](const mavlink_message_t& message) {
×
94
            process_gimbal_device_attitude_status(message);
×
95
        },
×
96
        this);
97

98
    _parent->register_mavlink_message_handler(
1✔
99
        MAVLINK_MSG_ID_GPS_RAW_INT,
100
        [this](const mavlink_message_t& message) { process_gps_raw_int(message); },
×
101
        this);
102

103
    _parent->register_mavlink_message_handler(
1✔
104
        MAVLINK_MSG_ID_EXTENDED_SYS_STATE,
105
        [this](const mavlink_message_t& message) { process_extended_sys_state(message); },
×
106
        this);
107

108
    _parent->register_mavlink_message_handler(
1✔
109
        MAVLINK_MSG_ID_SYS_STATUS,
110
        [this](const mavlink_message_t& message) { process_sys_status(message); },
×
111
        this);
112

113
    _parent->register_mavlink_message_handler(
1✔
114
        MAVLINK_MSG_ID_BATTERY_STATUS,
115
        [this](const mavlink_message_t& message) { process_battery_status(message); },
×
116
        this);
117

118
    _parent->register_mavlink_message_handler(
1✔
119
        MAVLINK_MSG_ID_HEARTBEAT,
120
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
×
121
        this);
122

123
    _parent->register_mavlink_message_handler(
1✔
124
        MAVLINK_MSG_ID_RC_CHANNELS,
125
        [this](const mavlink_message_t& message) { process_rc_channels(message); },
×
126
        this);
127

128
    _parent->register_mavlink_message_handler(
1✔
129
        MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET,
130
        [this](const mavlink_message_t& message) { process_actuator_control_target(message); },
×
131
        this);
132

133
    _parent->register_mavlink_message_handler(
1✔
134
        MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS,
135
        [this](const mavlink_message_t& message) { process_actuator_output_status(message); },
×
136
        this);
137

138
    _parent->register_mavlink_message_handler(
1✔
139
        MAVLINK_MSG_ID_ODOMETRY,
140
        [this](const mavlink_message_t& message) { process_odometry(message); },
×
141
        this);
142

143
    _parent->register_mavlink_message_handler(
1✔
144
        MAVLINK_MSG_ID_DISTANCE_SENSOR,
145
        [this](const mavlink_message_t& message) { process_distance_sensor(message); },
×
146
        this);
147

148
    _parent->register_mavlink_message_handler(
1✔
149
        MAVLINK_MSG_ID_SCALED_PRESSURE,
150
        [this](const mavlink_message_t& message) { process_scaled_pressure(message); },
×
151
        this);
152

153
    _parent->register_mavlink_message_handler(
1✔
154
        MAVLINK_MSG_ID_UTM_GLOBAL_POSITION,
155
        [this](const mavlink_message_t& message) { process_unix_epoch_time(message); },
×
156
        this);
157

158
    _parent->register_mavlink_message_handler(
1✔
159
        MAVLINK_MSG_ID_HIGHRES_IMU,
160
        [this](const mavlink_message_t& message) { process_imu_reading_ned(message); },
×
161
        this);
162

163
    _parent->register_mavlink_message_handler(
1✔
164
        MAVLINK_MSG_ID_SCALED_IMU,
165
        [this](const mavlink_message_t& message) { process_scaled_imu(message); },
×
166
        this);
167

168
    _parent->register_mavlink_message_handler(
1✔
169
        MAVLINK_MSG_ID_RAW_IMU,
170
        [this](const mavlink_message_t& message) { process_raw_imu(message); },
×
171
        this);
172

173
    _parent->register_mavlink_message_handler(
1✔
174
        MAVLINK_MSG_ID_VFR_HUD,
175
        [this](const mavlink_message_t& message) { process_fixedwing_metrics(message); },
×
176
        this);
177

178
    _parent->register_mavlink_message_handler(
1✔
179
        MAVLINK_MSG_ID_HIL_STATE_QUATERNION,
180
        [this](const mavlink_message_t& message) { process_ground_truth(message); },
×
181
        this);
182

183
    _parent->register_mavlink_message_handler(
1✔
184
        MAVLINK_MSG_ID_ALTITUDE,
185
        [this](const mavlink_message_t& message) { process_altitude(message); },
×
186
        this);
187

188
    _parent->register_param_changed_handler(
1✔
189
        [this](const std::string& name) { process_parameter_update(name); }, this);
×
190

191
    _parent->register_statustext_handler(
1✔
192
        [this](const MavlinkStatustextHandler::Statustext& statustext) {
3✔
193
            receive_statustext(statustext);
3✔
194
        },
3✔
195
        this);
196
}
1✔
197

198
void TelemetryImpl::deinit()
1✔
199
{
200
    _parent->cancel_all_param(this);
1✔
201
    _parent->remove_call_every(_calibration_cookie);
1✔
202
    _parent->unregister_statustext_handler(this);
1✔
203
    _parent->unregister_timeout_handler(_gps_raw_timeout_cookie);
1✔
204
    _parent->unregister_timeout_handler(_unix_epoch_timeout_cookie);
1✔
205
    _parent->unregister_param_changed_handler(this);
1✔
206
    _parent->unregister_all_mavlink_message_handlers(this);
1✔
207

208
    _has_received_gyro_calibration = false;
1✔
209
    _has_received_accel_calibration = false;
1✔
210
    _has_received_mag_calibration = false;
1✔
211

212
    {
213
        std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
1✔
214
        _ap_calibration = {};
1✔
215
    }
216

217
    _sys_status_used_for_position = SysStatusUsed::Unknown;
1✔
218
}
1✔
219

220
void TelemetryImpl::enable()
1✔
221
{
222
    _parent->register_timeout_handler(
1✔
223
        [this]() { receive_gps_raw_timeout(); }, 2.0, &_gps_raw_timeout_cookie);
×
224

225
    _parent->register_timeout_handler(
1✔
226
        [this]() { receive_unix_epoch_timeout(); }, 2.0, &_unix_epoch_timeout_cookie);
×
227

228
    // FIXME: The calibration check should eventually be better than this.
229
    //        For now, we just do the same as QGC does.
230

231
    _parent->add_call_every([this]() { check_calibration(); }, 5.0, &_calibration_cookie);
1✔
232

233
    // We're going to retry until we have the Home Position.
234
    _parent->add_call_every([this]() { request_home_position_again(); }, 2.0f, &_homepos_cookie);
1✔
235
}
1✔
236

237
void TelemetryImpl::disable()
1✔
238
{
239
    _parent->remove_call_every(_calibration_cookie);
1✔
240
    _parent->remove_call_every(_homepos_cookie);
1✔
241
}
1✔
242

243
void TelemetryImpl::request_home_position_again()
×
244
{
245
    {
246
        std::lock_guard<std::mutex> lock(_request_home_position_mutex);
×
247
        if (_health.is_home_position_ok) {
×
248
            _parent->remove_call_every(_homepos_cookie);
×
249
            return;
×
250
        }
251
    }
252
    request_home_position_async();
×
253
}
254

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

261
Telemetry::Result TelemetryImpl::set_rate_position(double rate_hz)
×
262
{
263
    _position_rate_hz = rate_hz;
×
264
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
265

266
    return telemetry_result_from_command_result(
×
267
        _parent->set_msg_rate(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, max_rate_hz));
×
268
}
269

270
Telemetry::Result TelemetryImpl::set_rate_home(double rate_hz)
×
271
{
272
    return telemetry_result_from_command_result(
×
273
        _parent->set_msg_rate(MAVLINK_MSG_ID_HOME_POSITION, rate_hz));
×
274
}
275

276
Telemetry::Result TelemetryImpl::set_rate_in_air(double rate_hz)
×
277
{
278
    return set_rate_landed_state(rate_hz);
×
279
}
280

281
Telemetry::Result TelemetryImpl::set_rate_vtol_state(double rate_hz)
×
282
{
283
    return set_rate_landed_state(rate_hz);
×
284
}
285

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

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

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

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

310
Telemetry::Result TelemetryImpl::set_rate_velocity_ned(double rate_hz)
×
311
{
312
    _velocity_ned_rate_hz = rate_hz;
×
313
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
314

315
    return telemetry_result_from_command_result(
×
316
        _parent->set_msg_rate(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, max_rate_hz));
×
317
}
318

319
Telemetry::Result TelemetryImpl::set_rate_imu(double rate_hz)
×
320
{
321
    return telemetry_result_from_command_result(
×
322
        _parent->set_msg_rate(MAVLINK_MSG_ID_HIGHRES_IMU, rate_hz));
×
323
}
324

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

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

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

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

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

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

361
Telemetry::Result TelemetryImpl::set_rate_rc_status(double rate_hz)
×
362
{
363
    UNUSED(rate_hz);
×
364
    LogWarn() << "System status is usually fixed at 1 Hz";
×
365
    return Telemetry::Result::Unsupported;
×
366
}
367

368
Telemetry::Result TelemetryImpl::set_rate_actuator_control_target(double rate_hz)
×
369
{
370
    return telemetry_result_from_command_result(
×
371
        _parent->set_msg_rate(MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, rate_hz));
×
372
}
373

374
Telemetry::Result TelemetryImpl::set_rate_actuator_output_status(double rate_hz)
×
375
{
376
    return telemetry_result_from_command_result(
×
377
        _parent->set_msg_rate(MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS, rate_hz));
×
378
}
379

380
Telemetry::Result TelemetryImpl::set_rate_odometry(double rate_hz)
×
381
{
382
    return telemetry_result_from_command_result(
×
383
        _parent->set_msg_rate(MAVLINK_MSG_ID_ODOMETRY, rate_hz));
×
384
}
385

386
Telemetry::Result TelemetryImpl::set_rate_distance_sensor(double rate_hz)
×
387
{
388
    return telemetry_result_from_command_result(
×
389
        _parent->set_msg_rate(MAVLINK_MSG_ID_DISTANCE_SENSOR, rate_hz));
×
390
}
391

392
Telemetry::Result TelemetryImpl::set_rate_scaled_pressure(double rate_hz)
×
393
{
394
    return telemetry_result_from_command_result(
×
395
        _parent->set_msg_rate(MAVLINK_MSG_ID_SCALED_PRESSURE, rate_hz));
×
396
}
397

398
Telemetry::Result TelemetryImpl::set_rate_unix_epoch_time(double rate_hz)
×
399
{
400
    return telemetry_result_from_command_result(
×
401
        _parent->set_msg_rate(MAVLINK_MSG_ID_UTM_GLOBAL_POSITION, rate_hz));
×
402
}
403

404
Telemetry::Result TelemetryImpl::set_rate_altitude(double rate_hz)
×
405
{
406
    return telemetry_result_from_command_result(
×
407
        _parent->set_msg_rate(MAVLINK_MSG_ID_ALTITUDE, rate_hz));
×
408
}
409

410
void TelemetryImpl::set_rate_position_velocity_ned_async(
×
411
    double rate_hz, Telemetry::ResultCallback callback)
412
{
413
    _parent->set_msg_rate_async(
×
414
        MAVLINK_MSG_ID_LOCAL_POSITION_NED,
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_position_async(double rate_hz, Telemetry::ResultCallback callback)
×
422
{
423
    _position_rate_hz = rate_hz;
×
424
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
425

426
    _parent->set_msg_rate_async(
×
427
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
428
        max_rate_hz,
429
        [callback](MavlinkCommandSender::Result command_result, float) {
×
430
            command_result_callback(command_result, callback);
×
431
        });
×
432
}
×
433

434
void TelemetryImpl::set_rate_home_async(double rate_hz, Telemetry::ResultCallback callback)
×
435
{
436
    _parent->set_msg_rate_async(
×
437
        MAVLINK_MSG_ID_HOME_POSITION,
438
        rate_hz,
439
        [callback](MavlinkCommandSender::Result command_result, float) {
×
440
            command_result_callback(command_result, callback);
×
441
        });
×
442
}
×
443

444
void TelemetryImpl::set_rate_in_air_async(double rate_hz, Telemetry::ResultCallback callback)
×
445
{
446
    set_rate_landed_state_async(rate_hz, callback);
×
447
}
×
448

449
void TelemetryImpl::set_rate_vtol_state_async(double rate_hz, Telemetry::ResultCallback callback)
×
450
{
451
    set_rate_landed_state_async(rate_hz, callback);
×
452
}
×
453

454
void TelemetryImpl::set_rate_landed_state_async(double rate_hz, Telemetry::ResultCallback callback)
×
455
{
456
    _parent->set_msg_rate_async(
×
457
        MAVLINK_MSG_ID_EXTENDED_SYS_STATE,
458
        rate_hz,
459
        [callback](MavlinkCommandSender::Result command_result, float) {
×
460
            command_result_callback(command_result, callback);
×
461
        });
×
462
}
×
463

464
void TelemetryImpl::set_rate_altitude_async(double rate_hz, Telemetry::ResultCallback callback)
×
465
{
466
    _parent->set_msg_rate_async(
×
467
        MAVLINK_MSG_ID_ALTITUDE,
468
        rate_hz,
469
        [callback](MavlinkCommandSender::Result command_result, float) {
×
470
            command_result_callback(command_result, callback);
×
471
        });
×
472
}
×
473

474
void TelemetryImpl::set_rate_attitude_quaternion_async(
×
475
    double rate_hz, Telemetry::ResultCallback callback)
476
{
477
    _parent->set_msg_rate_async(
×
478
        MAVLINK_MSG_ID_ATTITUDE_QUATERNION,
479
        rate_hz,
480
        [callback](MavlinkCommandSender::Result command_result, float) {
×
481
            command_result_callback(command_result, callback);
×
482
        });
×
483
}
×
484

485
void TelemetryImpl::set_rate_attitude_euler_async(
×
486
    double rate_hz, Telemetry::ResultCallback callback)
487
{
488
    _parent->set_msg_rate_async(
×
489
        MAVLINK_MSG_ID_ATTITUDE,
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_camera_attitude_async(
×
497
    double rate_hz, Telemetry::ResultCallback callback)
498
{
499
    _parent->set_msg_rate_async(
×
500
        MAVLINK_MSG_ID_MOUNT_ORIENTATION,
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_velocity_ned_async(double rate_hz, Telemetry::ResultCallback callback)
×
508
{
509
    _velocity_ned_rate_hz = rate_hz;
×
510
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
511

512
    _parent->set_msg_rate_async(
×
513
        MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
514
        max_rate_hz,
515
        [callback](MavlinkCommandSender::Result command_result, float) {
×
516
            command_result_callback(command_result, callback);
×
517
        });
×
518
}
×
519

520
void TelemetryImpl::set_rate_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
521
{
522
    _parent->set_msg_rate_async(
×
523
        MAVLINK_MSG_ID_HIGHRES_IMU,
524
        rate_hz,
525
        [callback](MavlinkCommandSender::Result command_result, float) {
×
526
            command_result_callback(command_result, callback);
×
527
        });
×
528
}
×
529

530
void TelemetryImpl::set_rate_scaled_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
531
{
532
    _parent->set_msg_rate_async(
×
533
        MAVLINK_MSG_ID_SCALED_IMU,
534
        rate_hz,
535
        [callback](MavlinkCommandSender::Result command_result, float) {
×
536
            command_result_callback(command_result, callback);
×
537
        });
×
538
}
×
539

540
void TelemetryImpl::set_rate_raw_imu_async(double rate_hz, Telemetry::ResultCallback callback)
×
541
{
542
    _parent->set_msg_rate_async(
×
543
        MAVLINK_MSG_ID_RAW_IMU,
544
        rate_hz,
545
        [callback](MavlinkCommandSender::Result command_result, float) {
×
546
            command_result_callback(command_result, callback);
×
547
        });
×
548
}
×
549

550
void TelemetryImpl::set_rate_fixedwing_metrics_async(
×
551
    double rate_hz, Telemetry::ResultCallback callback)
552
{
553
    _parent->set_msg_rate_async(
×
554
        MAVLINK_MSG_ID_VFR_HUD,
555
        rate_hz,
556
        [callback](MavlinkCommandSender::Result command_result, float) {
×
557
            command_result_callback(command_result, callback);
×
558
        });
×
559
}
×
560

561
void TelemetryImpl::set_rate_ground_truth_async(double rate_hz, Telemetry::ResultCallback callback)
×
562
{
563
    _parent->set_msg_rate_async(
×
564
        MAVLINK_MSG_ID_HIL_STATE_QUATERNION,
565
        rate_hz,
566
        [callback](MavlinkCommandSender::Result command_result, float) {
×
567
            command_result_callback(command_result, callback);
×
568
        });
×
569
}
×
570

571
void TelemetryImpl::set_rate_gps_info_async(double rate_hz, Telemetry::ResultCallback callback)
×
572
{
573
    _parent->set_msg_rate_async(
×
574
        MAVLINK_MSG_ID_GPS_RAW_INT,
575
        rate_hz,
576
        [callback](MavlinkCommandSender::Result command_result, float) {
×
577
            command_result_callback(command_result, callback);
×
578
        });
×
579
}
×
580

581
void TelemetryImpl::set_rate_battery_async(double rate_hz, Telemetry::ResultCallback callback)
×
582
{
583
    _parent->set_msg_rate_async(
×
584
        MAVLINK_MSG_ID_SYS_STATUS,
585
        rate_hz,
586
        [callback](MavlinkCommandSender::Result command_result, float) {
×
587
            command_result_callback(command_result, callback);
×
588
        });
×
589
}
×
590

591
void TelemetryImpl::set_rate_rc_status_async(double rate_hz, Telemetry::ResultCallback callback)
×
592
{
593
    UNUSED(rate_hz);
×
594
    LogWarn() << "System status is usually fixed at 1 Hz";
×
595
    _parent->call_user_callback([callback]() { callback(Telemetry::Result::Unsupported); });
×
596
}
×
597

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

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

620
void TelemetryImpl::set_rate_actuator_output_status_async(
×
621
    double rate_hz, Telemetry::ResultCallback callback)
622
{
623
    _parent->set_msg_rate_async(
×
624
        MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS,
625
        rate_hz,
626
        [callback](MavlinkCommandSender::Result command_result, float) {
×
627
            command_result_callback(command_result, callback);
×
628
        });
×
629
}
×
630

631
void TelemetryImpl::set_rate_odometry_async(double rate_hz, Telemetry::ResultCallback callback)
×
632
{
633
    _parent->set_msg_rate_async(
×
634
        MAVLINK_MSG_ID_ODOMETRY,
635
        rate_hz,
636
        [callback](MavlinkCommandSender::Result command_result, float) {
×
637
            command_result_callback(command_result, callback);
×
638
        });
×
639
}
×
640

641
void TelemetryImpl::set_rate_distance_sensor_async(
×
642
    double rate_hz, Telemetry::ResultCallback callback)
643
{
644
    _parent->set_msg_rate_async(
×
645
        MAVLINK_MSG_ID_DISTANCE_SENSOR,
646
        rate_hz,
647
        [callback](MavlinkCommandSender::Result command_result, float) {
×
648
            command_result_callback(command_result, callback);
×
649
        });
×
650
}
×
651

652
void TelemetryImpl::set_rate_scaled_pressure_async(
×
653
    double rate_hz, Telemetry::ResultCallback callback)
654
{
655
    _parent->set_msg_rate_async(
×
656
        MAVLINK_MSG_ID_SCALED_PRESSURE,
657
        rate_hz,
658
        [callback](MavlinkCommandSender::Result command_result, float) {
×
659
            command_result_callback(command_result, callback);
×
660
        });
×
661
}
×
662

663
Telemetry::Result
664
TelemetryImpl::telemetry_result_from_command_result(MavlinkCommandSender::Result command_result)
×
665
{
666
    switch (command_result) {
×
667
        case MavlinkCommandSender::Result::Success:
×
668
            return Telemetry::Result::Success;
×
669
        case MavlinkCommandSender::Result::NoSystem:
×
670
            return Telemetry::Result::NoSystem;
×
671
        case MavlinkCommandSender::Result::ConnectionError:
×
672
            return Telemetry::Result::ConnectionError;
×
673
        case MavlinkCommandSender::Result::Busy:
×
674
            return Telemetry::Result::Busy;
×
675
        case MavlinkCommandSender::Result::Denied:
×
676
            // FALLTHROUGH
677
        case MavlinkCommandSender::Result::TemporarilyRejected:
678
            return Telemetry::Result::CommandDenied;
×
679
        case MavlinkCommandSender::Result::Timeout:
×
680
            return Telemetry::Result::Timeout;
×
681
        case MavlinkCommandSender::Result::Unsupported:
×
682
            return Telemetry::Result::Unsupported;
×
683
        default:
×
684
            return Telemetry::Result::Unknown;
×
685
    }
686
}
687

688
void TelemetryImpl::command_result_callback(
×
689
    MavlinkCommandSender::Result command_result, const Telemetry::ResultCallback& callback)
690
{
691
    Telemetry::Result action_result = telemetry_result_from_command_result(command_result);
×
692

693
    callback(action_result);
×
694
}
×
695

696
void TelemetryImpl::process_position_velocity_ned(const mavlink_message_t& message)
×
697
{
698
    mavlink_local_position_ned_t local_position;
×
699
    mavlink_msg_local_position_ned_decode(&message, &local_position);
×
700

701
    Telemetry::PositionVelocityNed position_velocity;
×
702
    position_velocity.position.north_m = local_position.x;
×
703
    position_velocity.position.east_m = local_position.y;
×
704
    position_velocity.position.down_m = local_position.z;
×
705
    position_velocity.velocity.north_m_s = local_position.vx;
×
706
    position_velocity.velocity.east_m_s = local_position.vy;
×
707
    position_velocity.velocity.down_m_s = local_position.vz;
×
708

709
    set_position_velocity_ned(position_velocity);
×
710

711
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
712
    _position_velocity_ned_subscriptions.queue(
×
713
        position_velocity_ned(), [this](const auto& func) { _parent->call_user_callback(func); });
×
714

715
    set_health_local_position(true);
×
716
}
×
717

718
void TelemetryImpl::process_global_position_int(const mavlink_message_t& message)
×
719
{
720
    mavlink_global_position_int_t global_position_int;
×
721
    mavlink_msg_global_position_int_decode(&message, &global_position_int);
×
722

723
    {
724
        Telemetry::Position position;
×
725
        position.latitude_deg = global_position_int.lat * 1e-7;
×
726
        position.longitude_deg = global_position_int.lon * 1e-7;
×
727
        position.absolute_altitude_m = global_position_int.alt * 1e-3f;
×
728
        position.relative_altitude_m = global_position_int.relative_alt * 1e-3f;
×
729
        set_position(position);
×
730
    }
731

732
    {
733
        Telemetry::VelocityNed velocity;
×
734
        velocity.north_m_s = global_position_int.vx * 1e-2f;
×
735
        velocity.east_m_s = global_position_int.vy * 1e-2f;
×
736
        velocity.down_m_s = global_position_int.vz * 1e-2f;
×
737
        set_velocity_ned(velocity);
×
738
    }
739

740
    {
741
        Telemetry::Heading heading;
×
742
        heading.heading_deg = (global_position_int.hdg != std::numeric_limits<uint16_t>::max()) ?
×
743
                                  static_cast<double>(global_position_int.hdg) * 1e-2 :
×
744
                                  static_cast<double>(NAN);
745
        set_heading(heading);
×
746
    }
747

748
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
749
    _position_subscriptions.queue(
×
750
        position(), [this](const auto& func) { _parent->call_user_callback(func); });
×
751

752
    _velocity_ned_subscriptions.queue(
×
753
        velocity_ned(), [this](const auto& func) { _parent->call_user_callback(func); });
×
754

755
    _heading_subscriptions.queue(
×
756
        heading(), [this](const auto& func) { _parent->call_user_callback(func); });
×
757
}
×
758

759
void TelemetryImpl::process_home_position(const mavlink_message_t& message)
×
760
{
761
    mavlink_home_position_t home_position;
×
762
    mavlink_msg_home_position_decode(&message, &home_position);
×
763
    Telemetry::Position new_pos;
×
764
    new_pos.latitude_deg = home_position.latitude * 1e-7;
×
765
    new_pos.longitude_deg = home_position.longitude * 1e-7;
×
766
    new_pos.absolute_altitude_m = home_position.altitude * 1e-3f;
×
767
    new_pos.relative_altitude_m = 0.0f; // 0 by definition.
×
768

769
    set_home_position(new_pos);
×
770

771
    set_health_home_position(true);
×
772

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

778
void TelemetryImpl::process_attitude(const mavlink_message_t& message)
×
779
{
780
    mavlink_attitude_t attitude;
×
781
    mavlink_msg_attitude_decode(&message, &attitude);
×
782

783
    Telemetry::EulerAngle euler_angle;
×
784
    euler_angle.roll_deg = to_deg_from_rad(attitude.roll);
×
785
    euler_angle.pitch_deg = to_deg_from_rad(attitude.pitch);
×
786
    euler_angle.yaw_deg = to_deg_from_rad(attitude.yaw);
×
787
    euler_angle.timestamp_us = static_cast<uint64_t>(attitude.time_boot_ms) * 1000;
×
788

789
    Telemetry::AngularVelocityBody angular_velocity_body;
×
790
    angular_velocity_body.roll_rad_s = attitude.rollspeed;
×
791
    angular_velocity_body.pitch_rad_s = attitude.pitchspeed;
×
792
    angular_velocity_body.yaw_rad_s = attitude.yawspeed;
×
793
    set_attitude_angular_velocity_body(angular_velocity_body);
×
794

795
    _attitude_euler_angle_subscriptions.queue(
×
796
        attitude_euler(), [this](const auto& func) { _parent->call_user_callback(func); });
×
797

798
    _attitude_angular_velocity_body_subscriptions.queue(
×
799
        attitude_angular_velocity_body(),
800
        [this](const auto& func) { _parent->call_user_callback(func); });
×
801
}
×
802

803
void TelemetryImpl::process_attitude_quaternion(const mavlink_message_t& message)
×
804
{
805
    mavlink_attitude_quaternion_t mavlink_attitude_quaternion;
×
806
    mavlink_msg_attitude_quaternion_decode(&message, &mavlink_attitude_quaternion);
×
807

808
    Telemetry::Quaternion quaternion;
×
809
    quaternion.w = mavlink_attitude_quaternion.q1;
×
810
    quaternion.x = mavlink_attitude_quaternion.q2;
×
811
    quaternion.y = mavlink_attitude_quaternion.q3;
×
812
    quaternion.z = mavlink_attitude_quaternion.q4;
×
813
    quaternion.timestamp_us =
×
814
        static_cast<uint64_t>(mavlink_attitude_quaternion.time_boot_ms) * 1000;
×
815

816
    Telemetry::AngularVelocityBody angular_velocity_body;
×
817
    angular_velocity_body.roll_rad_s = mavlink_attitude_quaternion.rollspeed;
×
818
    angular_velocity_body.pitch_rad_s = mavlink_attitude_quaternion.pitchspeed;
×
819
    angular_velocity_body.yaw_rad_s = mavlink_attitude_quaternion.yawspeed;
×
820

821
    set_attitude_quaternion(quaternion);
×
822

823
    set_attitude_angular_velocity_body(angular_velocity_body);
×
824

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

829
    _attitude_angular_velocity_body_subscriptions.queue(
×
830
        attitude_angular_velocity_body(),
831
        [this](const auto& func) { _parent->call_user_callback(func); });
×
832
}
×
833

834
void TelemetryImpl::process_altitude(const mavlink_message_t& message)
×
835
{
836
    mavlink_altitude_t mavlink_altitude;
×
837
    mavlink_msg_altitude_decode(&message, &mavlink_altitude);
×
838

839
    Telemetry::Altitude new_altitude;
×
840
    new_altitude.altitude_monotonic_m = mavlink_altitude.altitude_monotonic;
×
841
    new_altitude.altitude_amsl_m = mavlink_altitude.altitude_amsl;
×
842
    new_altitude.altitude_local_m = mavlink_altitude.altitude_local;
×
843
    new_altitude.altitude_relative_m = mavlink_altitude.altitude_relative;
×
844
    new_altitude.altitude_terrain_m = mavlink_altitude.altitude_terrain;
×
845
    new_altitude.bottom_clearance_m = mavlink_altitude.bottom_clearance;
×
846

847
    set_altitude(new_altitude);
×
848

849
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
850
    _altitude_subscriptions.queue(
×
851
        altitude(), [this](const auto& func) { _parent->call_user_callback(func); });
×
852
}
×
853

854
void TelemetryImpl::process_mount_orientation(const mavlink_message_t& message)
×
855
{
856
    // TODO: remove this one once we move all the way to gimbal v2 protocol
857
    mavlink_mount_orientation_t mount_orientation;
×
858
    mavlink_msg_mount_orientation_decode(&message, &mount_orientation);
×
859

860
    Telemetry::EulerAngle euler_angle;
×
861
    euler_angle.roll_deg = mount_orientation.roll;
×
862
    euler_angle.pitch_deg = mount_orientation.pitch;
×
863
    euler_angle.yaw_deg = mount_orientation.yaw_absolute;
×
864

865
    set_camera_attitude_euler_angle(euler_angle);
×
866

867
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
868
    _camera_attitude_quaternion_subscriptions.queue(
×
869
        camera_attitude_quaternion(),
870
        [this](const auto& func) { _parent->call_user_callback(func); });
×
871

872
    _camera_attitude_euler_angle_subscriptions.queue(
×
873
        camera_attitude_euler(), [this](const auto& func) { _parent->call_user_callback(func); });
×
874
}
×
875

876
void TelemetryImpl::process_gimbal_device_attitude_status(const mavlink_message_t& message)
×
877
{
878
    // We accept both MOUNT_ORIENTATION and GIMBAL_DEVICE_ATTITUDE_STATUS for now,
879
    // in order to support both gimbal v1 and v2 protocols.
880

881
    mavlink_gimbal_device_attitude_status_t attitude_status;
×
882
    mavlink_msg_gimbal_device_attitude_status_decode(&message, &attitude_status);
×
883

884
    Telemetry::Quaternion q;
×
885
    q.w = attitude_status.q[0];
×
886
    q.x = attitude_status.q[1];
×
887
    q.y = attitude_status.q[2];
×
888
    q.z = attitude_status.q[3];
×
889

890
    Telemetry::EulerAngle euler_angle = to_euler_angle_from_quaternion(q);
×
891

892
    set_camera_attitude_euler_angle(euler_angle);
×
893

894
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
895
    _camera_attitude_quaternion_subscriptions.queue(
×
896
        camera_attitude_quaternion(),
897
        [this](const auto& func) { _parent->call_user_callback(func); });
×
898

899
    _camera_attitude_euler_angle_subscriptions.queue(
×
900
        camera_attitude_euler(), [this](const auto& func) { _parent->call_user_callback(func); });
×
901
}
×
902

903
void TelemetryImpl::process_imu_reading_ned(const mavlink_message_t& message)
×
904
{
905
    mavlink_highres_imu_t highres_imu;
×
906
    mavlink_msg_highres_imu_decode(&message, &highres_imu);
×
907
    Telemetry::Imu new_imu;
×
908
    new_imu.acceleration_frd.forward_m_s2 = highres_imu.xacc;
×
909
    new_imu.acceleration_frd.right_m_s2 = highres_imu.yacc;
×
910
    new_imu.acceleration_frd.down_m_s2 = highres_imu.zacc;
×
911
    new_imu.angular_velocity_frd.forward_rad_s = highres_imu.xgyro;
×
912
    new_imu.angular_velocity_frd.right_rad_s = highres_imu.ygyro;
×
913
    new_imu.angular_velocity_frd.down_rad_s = highres_imu.zgyro;
×
914
    new_imu.magnetic_field_frd.forward_gauss = highres_imu.xmag;
×
915
    new_imu.magnetic_field_frd.right_gauss = highres_imu.ymag;
×
916
    new_imu.magnetic_field_frd.down_gauss = highres_imu.zmag;
×
917
    new_imu.temperature_degc = highres_imu.temperature;
×
918
    new_imu.timestamp_us = highres_imu.time_usec;
×
919

920
    set_imu_reading_ned(new_imu);
×
921

922
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
923
    _imu_reading_ned_subscriptions.queue(
×
924
        imu(), [this](const auto& func) { _parent->call_user_callback(func); });
×
925
}
×
926

927
void TelemetryImpl::process_scaled_imu(const mavlink_message_t& message)
×
928
{
929
    mavlink_scaled_imu_t scaled_imu_reading;
×
930
    mavlink_msg_scaled_imu_decode(&message, &scaled_imu_reading);
×
931
    Telemetry::Imu new_imu;
×
932
    new_imu.acceleration_frd.forward_m_s2 = scaled_imu_reading.xacc;
×
933
    new_imu.acceleration_frd.right_m_s2 = scaled_imu_reading.yacc;
×
934
    new_imu.acceleration_frd.down_m_s2 = scaled_imu_reading.zacc;
×
935
    new_imu.angular_velocity_frd.forward_rad_s = scaled_imu_reading.xgyro;
×
936
    new_imu.angular_velocity_frd.right_rad_s = scaled_imu_reading.ygyro;
×
937
    new_imu.angular_velocity_frd.down_rad_s = scaled_imu_reading.zgyro;
×
938
    new_imu.magnetic_field_frd.forward_gauss = scaled_imu_reading.xmag;
×
939
    new_imu.magnetic_field_frd.right_gauss = scaled_imu_reading.ymag;
×
940
    new_imu.magnetic_field_frd.down_gauss = scaled_imu_reading.zmag;
×
941
    new_imu.temperature_degc = static_cast<float>(scaled_imu_reading.temperature) * 1e-2f;
×
942
    new_imu.timestamp_us = static_cast<uint64_t>(scaled_imu_reading.time_boot_ms) * 1000;
×
943

944
    set_scaled_imu(new_imu);
×
945

946
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
947
    _scaled_imu_subscriptions.queue(
×
948
        scaled_imu(), [this](const auto& func) { _parent->call_user_callback(func); });
×
949
}
×
950

951
void TelemetryImpl::process_raw_imu(const mavlink_message_t& message)
×
952
{
953
    mavlink_raw_imu_t raw_imu_reading;
×
954
    mavlink_msg_raw_imu_decode(&message, &raw_imu_reading);
×
955
    Telemetry::Imu new_imu;
×
956
    new_imu.acceleration_frd.forward_m_s2 = raw_imu_reading.xacc;
×
957
    new_imu.acceleration_frd.right_m_s2 = raw_imu_reading.yacc;
×
958
    new_imu.acceleration_frd.down_m_s2 = raw_imu_reading.zacc;
×
959
    new_imu.angular_velocity_frd.forward_rad_s = raw_imu_reading.xgyro;
×
960
    new_imu.angular_velocity_frd.right_rad_s = raw_imu_reading.ygyro;
×
961
    new_imu.angular_velocity_frd.down_rad_s = raw_imu_reading.zgyro;
×
962
    new_imu.magnetic_field_frd.forward_gauss = raw_imu_reading.xmag;
×
963
    new_imu.magnetic_field_frd.right_gauss = raw_imu_reading.ymag;
×
964
    new_imu.magnetic_field_frd.down_gauss = raw_imu_reading.zmag;
×
965
    new_imu.temperature_degc = static_cast<float>(raw_imu_reading.temperature) * 1e-2f;
×
966
    new_imu.timestamp_us = raw_imu_reading.time_usec;
×
967

968
    set_raw_imu(new_imu);
×
969

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

975
void TelemetryImpl::process_gps_raw_int(const mavlink_message_t& message)
×
976
{
977
    mavlink_gps_raw_int_t gps_raw_int;
×
978
    mavlink_msg_gps_raw_int_decode(&message, &gps_raw_int);
×
979

980
    Telemetry::FixType fix_type;
981
    switch (gps_raw_int.fix_type) {
×
982
        case 0:
×
983
            fix_type = Telemetry::FixType::NoGps;
×
984
            break;
×
985
        case 1:
×
986
            fix_type = Telemetry::FixType::NoFix;
×
987
            break;
×
988
        case 2:
×
989
            fix_type = Telemetry::FixType::Fix2D;
×
990
            break;
×
991
        case 3:
×
992
            fix_type = Telemetry::FixType::Fix3D;
×
993
            break;
×
994
        case 4:
×
995
            fix_type = Telemetry::FixType::FixDgps;
×
996
            break;
×
997
        case 5:
×
998
            fix_type = Telemetry::FixType::RtkFloat;
×
999
            break;
×
1000
        case 6:
×
1001
            fix_type = Telemetry::FixType::RtkFixed;
×
1002
            break;
×
1003

1004
        default:
×
1005
            LogErr() << "Received unknown GPS fix type!";
×
1006
            fix_type = Telemetry::FixType::NoGps;
×
1007
            break;
×
1008
    }
1009

1010
    Telemetry::GpsInfo new_gps_info;
×
1011
    new_gps_info.num_satellites = gps_raw_int.satellites_visible;
×
1012
    new_gps_info.fix_type = fix_type;
×
1013
    set_gps_info(new_gps_info);
×
1014

1015
    Telemetry::RawGps raw_gps_info;
×
1016
    raw_gps_info.timestamp_us = gps_raw_int.time_usec;
×
1017
    raw_gps_info.latitude_deg = gps_raw_int.lat * 1e-7;
×
1018
    raw_gps_info.longitude_deg = gps_raw_int.lon * 1e-7;
×
1019
    raw_gps_info.absolute_altitude_m = gps_raw_int.alt * 1e-3f;
×
1020
    raw_gps_info.hdop = static_cast<float>(gps_raw_int.eph) * 1e-2f;
×
1021
    raw_gps_info.vdop = static_cast<float>(gps_raw_int.epv) * 1e-2f;
×
1022
    raw_gps_info.velocity_m_s = static_cast<float>(gps_raw_int.vel) * 1e-2f;
×
1023
    raw_gps_info.cog_deg = static_cast<float>(gps_raw_int.cog) * 1e-2f;
×
1024
    raw_gps_info.altitude_ellipsoid_m = static_cast<float>(gps_raw_int.alt_ellipsoid) * 1e-3f;
×
1025
    raw_gps_info.horizontal_uncertainty_m = static_cast<float>(gps_raw_int.h_acc) * 1e-3f;
×
1026
    raw_gps_info.vertical_uncertainty_m = static_cast<float>(gps_raw_int.v_acc) * 1e-3f;
×
1027
    raw_gps_info.velocity_uncertainty_m_s = static_cast<float>(gps_raw_int.vel_acc) * 1e-3f;
×
1028
    raw_gps_info.heading_uncertainty_deg = static_cast<float>(gps_raw_int.hdg_acc) * 1e-5f;
×
1029
    raw_gps_info.yaw_deg = static_cast<float>(gps_raw_int.yaw) * 1e-2f;
×
1030
    set_raw_gps(raw_gps_info);
×
1031

1032
    if (_sys_status_used_for_position == SysStatusUsed::No) {
×
1033
        // This is just a fallback if sys_status does not contain the appropriate flags yet.
1034
        const bool gps_ok = ((gps_raw_int.fix_type >= 3) && (gps_raw_int.satellites_visible >= 8));
×
1035

1036
        set_health_global_position(gps_ok);
×
1037
    }
1038

1039
    {
1040
        std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1041
        _gps_info_subscriptions.queue(
×
1042
            gps_info(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1043
        _raw_gps_subscriptions.queue(
×
1044
            raw_gps(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1045
    }
1046

1047
    _parent->refresh_timeout_handler(_gps_raw_timeout_cookie);
×
1048
}
×
1049

1050
void TelemetryImpl::process_ground_truth(const mavlink_message_t& message)
×
1051
{
1052
    mavlink_hil_state_quaternion_t hil_state_quaternion;
×
1053
    mavlink_msg_hil_state_quaternion_decode(&message, &hil_state_quaternion);
×
1054

1055
    Telemetry::GroundTruth new_ground_truth;
×
1056
    new_ground_truth.latitude_deg = hil_state_quaternion.lat * 1e-7;
×
1057
    new_ground_truth.longitude_deg = hil_state_quaternion.lon * 1e-7;
×
1058
    new_ground_truth.absolute_altitude_m = hil_state_quaternion.alt * 1e-3f;
×
1059

1060
    set_ground_truth(new_ground_truth);
×
1061

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

1067
void TelemetryImpl::process_extended_sys_state(const mavlink_message_t& message)
×
1068
{
1069
    mavlink_extended_sys_state_t extended_sys_state;
×
1070
    mavlink_msg_extended_sys_state_decode(&message, &extended_sys_state);
×
1071

1072
    {
1073
        Telemetry::LandedState landed_state = to_landed_state(extended_sys_state);
×
1074
        set_landed_state(landed_state);
×
1075

1076
        Telemetry::VtolState vtol_state = to_vtol_state(extended_sys_state);
×
1077
        set_vtol_state(vtol_state);
×
1078
    }
1079

1080
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1081
    _landed_state_subscriptions.queue(
×
1082
        landed_state(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1083

1084
    _vtol_state_subscriptions.queue(
×
1085
        vtol_state(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1086

1087
    if (extended_sys_state.landed_state == MAV_LANDED_STATE_IN_AIR ||
×
1088
        extended_sys_state.landed_state == MAV_LANDED_STATE_TAKEOFF ||
×
1089
        extended_sys_state.landed_state == MAV_LANDED_STATE_LANDING) {
×
1090
        set_in_air(true);
×
1091
    } else if (extended_sys_state.landed_state == MAV_LANDED_STATE_ON_GROUND) {
×
1092
        set_in_air(false);
×
1093
    }
1094
    // If landed_state is undefined, we use what we have received last.
1095

1096
    _in_air_subscriptions.queue(
×
1097
        in_air(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1098
}
×
1099
void TelemetryImpl::process_fixedwing_metrics(const mavlink_message_t& message)
×
1100
{
1101
    mavlink_vfr_hud_t vfr_hud;
×
1102
    mavlink_msg_vfr_hud_decode(&message, &vfr_hud);
×
1103

1104
    Telemetry::FixedwingMetrics new_fixedwing_metrics;
×
1105
    new_fixedwing_metrics.airspeed_m_s = vfr_hud.airspeed;
×
1106
    new_fixedwing_metrics.throttle_percentage = vfr_hud.throttle * 1e-2f;
×
1107
    new_fixedwing_metrics.climb_rate_m_s = vfr_hud.climb;
×
1108

1109
    set_fixedwing_metrics(new_fixedwing_metrics);
×
1110

1111
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1112
    _fixedwing_metrics_subscriptions.queue(
×
1113
        fixedwing_metrics(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1114
}
×
1115

1116
void TelemetryImpl::process_sys_status(const mavlink_message_t& message)
×
1117
{
1118
    mavlink_sys_status_t sys_status;
×
1119
    mavlink_msg_sys_status_decode(&message, &sys_status);
×
1120

1121
    if (!_has_bat_status) {
×
1122
        Telemetry::Battery new_battery;
×
1123
        new_battery.voltage_v = sys_status.voltage_battery * 1e-3f;
×
1124
        new_battery.remaining_percent = sys_status.battery_remaining;
×
1125

1126
        set_battery(new_battery);
×
1127

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

1135
    const bool rc_ok =
×
1136
        sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
×
1137

1138
    set_rc_status({rc_ok}, std::nullopt);
×
1139

1140
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_GYRO) {
×
1141
        set_health_gyrometer_calibration(
×
1142
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_GYRO);
×
1143
    } else {
1144
        // If the flag is not supported yet, we fall back to the param.
1145
    }
1146

1147
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_ACCEL) {
×
1148
        set_health_accelerometer_calibration(
×
1149
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_ACCEL);
×
1150
    } else {
1151
        // If the flag is not supported yet, we fall back to the param.
1152
    }
1153

1154
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_MAG) {
×
1155
        set_health_magnetometer_calibration(
×
1156
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_MAG);
×
1157
    } else {
1158
        // If the flag is not supported yet, we fall back to the param.
1159
    }
1160

1161
    const bool global_position_ok =
1162
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_GPS);
×
1163

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

1167
    const bool local_position_ok =
1168
        global_position_ok ||
×
1169
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW) ||
×
1170
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_VISION_POSITION);
×
1171

1172
    set_health_local_position(local_position_ok);
×
1173
    set_health_global_position(global_position_ok);
×
1174

1175
    // If any of these sensors were marked present, we don't have to fall back to check for
1176
    // satellite count.
1177
    _sys_status_used_for_position =
×
1178
        ((sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_GPS) != 0 ||
×
1179
         (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW) != 0 ||
×
1180
         (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_VISION_POSITION) !=
×
1181
             0) ?
1182
            SysStatusUsed::Yes :
1183
            SysStatusUsed::No;
1184

1185
    set_rc_status({rc_ok}, std::nullopt);
×
1186

1187
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1188
    _rc_status_subscriptions.queue(
×
1189
        rc_status(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1190

1191
    const bool armable = sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_PREARM_CHECK;
×
1192
    set_health_armable(armable);
×
1193
    _health_all_ok_subscriptions.queue(
×
1194
        health_all_ok(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1195
}
×
1196

1197
bool TelemetryImpl::sys_status_present_enabled_health(
×
1198
    const mavlink_sys_status_t& sys_status, MAV_SYS_STATUS_SENSOR flag)
1199
{
1200
    // FIXME: it doesn't look like PX4 sets enabled for GPS
1201
    return (sys_status.onboard_control_sensors_present & flag) != 0 &&
×
1202
           // (sys_status.onboard_control_sensors_enabled & flag) != 0 &&
1203
           (sys_status.onboard_control_sensors_health & flag) != 0;
×
1204
}
1205

1206
void TelemetryImpl::process_battery_status(const mavlink_message_t& message)
×
1207
{
1208
    mavlink_battery_status_t bat_status;
×
1209
    mavlink_msg_battery_status_decode(&message, &bat_status);
×
1210

1211
    _has_bat_status = true;
×
1212

1213
    Telemetry::Battery new_battery;
×
1214
    new_battery.id = bat_status.id;
×
1215
    new_battery.temperature_degc = (bat_status.temperature == std::numeric_limits<int16_t>::max()) ?
×
1216
                                       static_cast<float>(NAN) :
1217
                                       bat_status.temperature * 1e-2f; // cdegC to degC
×
1218
    new_battery.voltage_v = 0.0f;
×
1219
    for (int i = 0; i < 255; i++) {
×
1220
        if (bat_status.voltages[i] == std::numeric_limits<uint16_t>::max())
×
1221
            break;
×
1222
        new_battery.voltage_v += static_cast<float>(bat_status.voltages[i]) * 1e-3f;
×
1223
    }
1224
    new_battery.remaining_percent = bat_status.battery_remaining;
×
1225
    new_battery.current_battery_a = (bat_status.current_battery == -1) ?
×
1226
                                        static_cast<float>(NAN) :
1227
                                        bat_status.current_battery * 1e-2f; // cA to A
×
1228
    new_battery.capacity_consumed_ah = (bat_status.current_consumed == -1) ?
×
1229
                                           static_cast<float>(NAN) :
1230
                                           bat_status.current_consumed * 1e-3f; // mAh to Ah
×
1231

1232
    set_battery(new_battery);
×
1233

1234
    {
1235
        std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1236
        _battery_subscriptions.queue(
×
1237
            battery(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1238
    }
1239
}
×
1240

1241
void TelemetryImpl::process_heartbeat(const mavlink_message_t& message)
×
1242
{
1243
    if (message.compid != MAV_COMP_ID_AUTOPILOT1) {
×
1244
        return;
×
1245
    }
1246

1247
    mavlink_heartbeat_t heartbeat;
×
1248
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
×
1249

1250
    set_armed(((heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) ? true : false));
×
1251

1252
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1253
    _armed_subscriptions.queue(
×
1254
        armed(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1255

1256
    _flight_mode_subscriptions.queue(
×
1257
        telemetry_flight_mode_from_flight_mode(_parent->get_flight_mode()),
×
1258
        [this](const auto& func) { _parent->call_user_callback(func); });
×
1259

1260
    _health_subscriptions.queue(
×
1261
        health(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1262

1263
    _health_all_ok_subscriptions.queue(
×
1264
        health_all_ok(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1265
}
1266

1267
void TelemetryImpl::receive_statustext(const MavlinkStatustextHandler::Statustext& statustext)
3✔
1268
{
1269
    Telemetry::StatusText new_status_text;
6✔
1270

1271
    switch (statustext.severity) {
3✔
1272
        case MAV_SEVERITY_EMERGENCY:
×
1273
            new_status_text.type = Telemetry::StatusTextType::Emergency;
×
1274
            break;
×
1275
        case MAV_SEVERITY_ALERT:
×
1276
            new_status_text.type = Telemetry::StatusTextType::Alert;
×
1277
            break;
×
1278
        case MAV_SEVERITY_CRITICAL:
×
1279
            new_status_text.type = Telemetry::StatusTextType::Critical;
×
1280
            break;
×
1281
        case MAV_SEVERITY_ERROR:
×
1282
            new_status_text.type = Telemetry::StatusTextType::Error;
×
1283
            break;
×
1284
        case MAV_SEVERITY_WARNING:
×
1285
            new_status_text.type = Telemetry::StatusTextType::Warning;
×
1286
            break;
×
1287
        case MAV_SEVERITY_NOTICE:
×
1288
            new_status_text.type = Telemetry::StatusTextType::Notice;
×
1289
            break;
×
1290
        case MAV_SEVERITY_INFO:
3✔
1291
            new_status_text.type = Telemetry::StatusTextType::Info;
3✔
1292
            break;
3✔
1293
        case MAV_SEVERITY_DEBUG:
×
1294
            new_status_text.type = Telemetry::StatusTextType::Debug;
×
1295
            break;
×
1296
        default:
×
1297
            LogWarn() << "Unknown StatusText severity";
×
1298
            new_status_text.type = Telemetry::StatusTextType::Info;
×
1299
            break;
×
1300
    }
1301

1302
    new_status_text.text = statustext.text;
3✔
1303

1304
    set_status_text(new_status_text);
3✔
1305

1306
    std::lock_guard<std::mutex> lock(_subscription_mutex);
6✔
1307
    _status_text_subscriptions.queue(
9✔
1308
        status_text(), [this](const auto& func) { _parent->call_user_callback(func); });
11✔
1309
}
3✔
1310

1311
void TelemetryImpl::process_rc_channels(const mavlink_message_t& message)
×
1312
{
1313
    mavlink_rc_channels_t rc_channels;
×
1314
    mavlink_msg_rc_channels_decode(&message, &rc_channels);
×
1315

1316
    if (rc_channels.rssi != std::numeric_limits<uint8_t>::max()) {
×
1317
        set_rc_status(std::nullopt, {rc_channels.rssi});
×
1318
    }
1319

1320
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1321
    _rc_status_subscriptions.queue(
×
1322
        rc_status(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1323

1324
    _parent->refresh_timeout_handler(_rc_channels_timeout_cookie);
×
1325
}
×
1326

1327
void TelemetryImpl::process_unix_epoch_time(const mavlink_message_t& message)
×
1328
{
1329
    mavlink_utm_global_position_t utm_global_position;
×
1330
    mavlink_msg_utm_global_position_decode(&message, &utm_global_position);
×
1331

1332
    set_unix_epoch_time_us(utm_global_position.time);
×
1333

1334
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1335
    _unix_epoch_time_subscriptions.queue(
×
1336
        unix_epoch_time(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1337

1338
    _parent->refresh_timeout_handler(_unix_epoch_timeout_cookie);
×
1339
}
×
1340

1341
void TelemetryImpl::process_actuator_control_target(const mavlink_message_t& message)
×
1342
{
1343
    mavlink_set_actuator_control_target_t target;
×
1344
    mavlink_msg_set_actuator_control_target_decode(&message, &target);
×
1345

1346
    uint32_t group = target.group_mlx;
×
1347
    std::vector<float> controls;
×
1348

1349
    const unsigned control_size = sizeof(target.controls) / sizeof(target.controls[0]);
×
1350
    // Can't use std::copy because target is packed.
1351
    for (std::size_t i = 0; i < control_size; ++i) {
×
1352
        controls.push_back(target.controls[i]);
×
1353
    }
1354

1355
    set_actuator_control_target(group, controls);
×
1356

1357
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1358
    _actuator_control_target_subscriptions.queue(
×
1359
        actuator_control_target(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1360
}
×
1361

1362
void TelemetryImpl::process_actuator_output_status(const mavlink_message_t& message)
×
1363
{
1364
    mavlink_actuator_output_status_t status;
×
1365
    mavlink_msg_actuator_output_status_decode(&message, &status);
×
1366

1367
    uint32_t active = status.active;
×
1368
    std::vector<float> actuators;
×
1369

1370
    const unsigned actuators_size = sizeof(status.actuator) / sizeof(status.actuator[0]);
×
1371
    // Can't use std::copy because status is packed.
1372
    for (std::size_t i = 0; i < actuators_size; ++i) {
×
1373
        actuators.push_back(status.actuator[i]);
×
1374
    }
1375

1376
    set_actuator_output_status(active, actuators);
×
1377

1378
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1379
    _actuator_output_status_subscriptions.queue(
×
1380
        actuator_output_status(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1381
}
×
1382

1383
void TelemetryImpl::process_odometry(const mavlink_message_t& message)
×
1384
{
1385
    mavlink_odometry_t odometry_msg;
×
1386
    mavlink_msg_odometry_decode(&message, &odometry_msg);
×
1387

1388
    Telemetry::Odometry odometry_struct{};
×
1389

1390
    odometry_struct.time_usec = odometry_msg.time_usec;
×
1391
    odometry_struct.frame_id = static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.frame_id);
×
1392
    odometry_struct.child_frame_id =
×
1393
        static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.child_frame_id);
×
1394

1395
    odometry_struct.position_body.x_m = odometry_msg.x;
×
1396
    odometry_struct.position_body.y_m = odometry_msg.y;
×
1397
    odometry_struct.position_body.z_m = odometry_msg.z;
×
1398

1399
    odometry_struct.q.w = odometry_msg.q[0];
×
1400
    odometry_struct.q.x = odometry_msg.q[1];
×
1401
    odometry_struct.q.y = odometry_msg.q[2];
×
1402
    odometry_struct.q.z = odometry_msg.q[3];
×
1403

1404
    odometry_struct.velocity_body.x_m_s = odometry_msg.vx;
×
1405
    odometry_struct.velocity_body.y_m_s = odometry_msg.vy;
×
1406
    odometry_struct.velocity_body.z_m_s = odometry_msg.vz;
×
1407

1408
    odometry_struct.angular_velocity_body.roll_rad_s = odometry_msg.rollspeed;
×
1409
    odometry_struct.angular_velocity_body.pitch_rad_s = odometry_msg.pitchspeed;
×
1410
    odometry_struct.angular_velocity_body.yaw_rad_s = odometry_msg.yawspeed;
×
1411

1412
    const std::size_t len_pose_covariance =
×
1413
        sizeof(odometry_msg.pose_covariance) / sizeof(odometry_msg.pose_covariance[0]);
1414
    for (std::size_t i = 0; i < len_pose_covariance; ++i) {
×
1415
        odometry_struct.pose_covariance.covariance_matrix.push_back(
×
1416
            odometry_msg.pose_covariance[i]);
×
1417
    }
1418

1419
    const std::size_t len_velocity_covariance =
×
1420
        sizeof(odometry_msg.velocity_covariance) / sizeof(odometry_msg.velocity_covariance[0]);
1421
    for (std::size_t i = 0; i < len_velocity_covariance; ++i) {
×
1422
        odometry_struct.velocity_covariance.covariance_matrix.push_back(
×
1423
            odometry_msg.velocity_covariance[i]);
×
1424
    }
1425

1426
    set_odometry(odometry_struct);
×
1427

1428
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1429
    _odometry_subscriptions.queue(
×
1430
        odometry(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1431
}
×
1432

1433
void TelemetryImpl::process_distance_sensor(const mavlink_message_t& message)
×
1434
{
1435
    mavlink_distance_sensor_t distance_sensor_msg;
×
1436
    mavlink_msg_distance_sensor_decode(&message, &distance_sensor_msg);
×
1437

1438
    Telemetry::DistanceSensor distance_sensor_struct{};
×
1439

1440
    distance_sensor_struct.minimum_distance_m =
×
1441
        static_cast<float>(distance_sensor_msg.min_distance) * 1e-2f; // cm to m
×
1442
    distance_sensor_struct.maximum_distance_m =
×
1443
        static_cast<float>(distance_sensor_msg.max_distance) * 1e-2f; // cm to m
×
1444
    distance_sensor_struct.current_distance_m =
×
1445
        static_cast<float>(distance_sensor_msg.current_distance) * 1e-2f; // cm to m
×
1446

1447
    set_distance_sensor(distance_sensor_struct);
×
1448

1449
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1450
    _distance_sensor_subscriptions.queue(
×
1451
        distance_sensor(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1452
}
×
1453

1454
void TelemetryImpl::process_scaled_pressure(const mavlink_message_t& message)
×
1455
{
1456
    mavlink_scaled_pressure_t scaled_pressure_msg;
×
1457
    mavlink_msg_scaled_pressure_decode(&message, &scaled_pressure_msg);
×
1458

1459
    Telemetry::ScaledPressure scaled_pressure_struct{};
×
1460

1461
    scaled_pressure_struct.timestamp_us =
×
1462
        static_cast<uint64_t>(scaled_pressure_msg.time_boot_ms) * 1000;
×
1463
    scaled_pressure_struct.absolute_pressure_hpa = scaled_pressure_msg.press_abs;
×
1464
    scaled_pressure_struct.differential_pressure_hpa = scaled_pressure_msg.press_diff;
×
1465
    scaled_pressure_struct.temperature_deg =
×
1466
        static_cast<float>(scaled_pressure_msg.temperature) * 1e-2f;
×
1467
    scaled_pressure_struct.differential_pressure_temperature_deg =
×
1468
        static_cast<float>(scaled_pressure_msg.temperature_press_diff) * 1e-2f;
×
1469

1470
    set_scaled_pressure(scaled_pressure_struct);
×
1471

1472
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1473
    _scaled_pressure_subscriptions.queue(
×
1474
        scaled_pressure(), [this](const auto& func) { _parent->call_user_callback(func); });
×
1475
}
×
1476

1477
Telemetry::LandedState
1478
TelemetryImpl::to_landed_state(mavlink_extended_sys_state_t extended_sys_state)
×
1479
{
1480
    switch (extended_sys_state.landed_state) {
×
1481
        case MAV_LANDED_STATE_IN_AIR:
×
1482
            return Telemetry::LandedState::InAir;
×
1483
        case MAV_LANDED_STATE_TAKEOFF:
×
1484
            return Telemetry::LandedState::TakingOff;
×
1485
        case MAV_LANDED_STATE_LANDING:
×
1486
            return Telemetry::LandedState::Landing;
×
1487
        case MAV_LANDED_STATE_ON_GROUND:
×
1488
            return Telemetry::LandedState::OnGround;
×
1489
        default:
×
1490
            return Telemetry::LandedState::Unknown;
×
1491
    }
1492
}
1493

1494
Telemetry::VtolState TelemetryImpl::to_vtol_state(mavlink_extended_sys_state_t extended_sys_state)
×
1495
{
1496
    switch (extended_sys_state.vtol_state) {
×
1497
        case MAV_VTOL_STATE::MAV_VTOL_STATE_TRANSITION_TO_FW:
×
1498
            return Telemetry::VtolState::TransitionToFw;
×
1499
        case MAV_VTOL_STATE_TRANSITION_TO_MC:
×
1500
            return Telemetry::VtolState::TransitionToMc;
×
1501
        case MAV_VTOL_STATE_MC:
×
1502
            return Telemetry::VtolState::Mc;
×
1503
        case MAV_VTOL_STATE_FW:
×
1504
            return Telemetry::VtolState::Fw;
×
1505
        default:
×
1506
            return Telemetry::VtolState::Undefined;
×
1507
    }
1508
}
1509

1510
Telemetry::FlightMode TelemetryImpl::telemetry_flight_mode_from_flight_mode(FlightMode flight_mode)
×
1511
{
1512
    switch (flight_mode) {
×
1513
        case FlightMode::Ready:
×
1514
            return Telemetry::FlightMode::Ready;
×
1515
        case FlightMode::Takeoff:
×
1516
            return Telemetry::FlightMode::Takeoff;
×
1517
        case FlightMode::Hold:
×
1518
            return Telemetry::FlightMode::Hold;
×
1519
        case FlightMode::Mission:
×
1520
            return Telemetry::FlightMode::Mission;
×
1521
        case FlightMode::ReturnToLaunch:
×
1522
            return Telemetry::FlightMode::ReturnToLaunch;
×
1523
        case FlightMode::Land:
×
1524
            return Telemetry::FlightMode::Land;
×
1525
        case FlightMode::Offboard:
×
1526
            return Telemetry::FlightMode::Offboard;
×
1527
        case FlightMode::FollowMe:
×
1528
            return Telemetry::FlightMode::FollowMe;
×
1529
        case FlightMode::Manual:
×
1530
            return Telemetry::FlightMode::Manual;
×
1531
        case FlightMode::Posctl:
×
1532
            return Telemetry::FlightMode::Posctl;
×
1533
        case FlightMode::Altctl:
×
1534
            return Telemetry::FlightMode::Altctl;
×
1535
        case FlightMode::Rattitude:
×
1536
            return Telemetry::FlightMode::Rattitude;
×
1537
        case FlightMode::Acro:
×
1538
            return Telemetry::FlightMode::Acro;
×
1539
        case FlightMode::Stabilized:
×
1540
            return Telemetry::FlightMode::Stabilized;
×
1541
        default:
×
1542
            return Telemetry::FlightMode::Unknown;
×
1543
    }
1544
}
1545

1546
void TelemetryImpl::receive_param_cal_gyro(MAVLinkParameters::Result result, int value)
×
1547
{
1548
    if (result != MAVLinkParameters::Result::Success) {
×
1549
        LogErr() << "Error: Param for gyro cal failed.";
×
1550
        return;
×
1551
    }
1552

1553
    bool ok = (value != 0);
×
1554
    set_health_gyrometer_calibration(ok);
×
1555
}
1556

1557
void TelemetryImpl::receive_param_cal_accel(MAVLinkParameters::Result result, int value)
×
1558
{
1559
    if (result != MAVLinkParameters::Result::Success) {
×
1560
        LogErr() << "Error: Param for accel cal failed.";
×
1561
        return;
×
1562
    }
1563

1564
    bool ok = (value != 0);
×
1565
    set_health_accelerometer_calibration(ok);
×
1566
}
1567

1568
void TelemetryImpl::receive_param_cal_mag(MAVLinkParameters::Result result, int value)
×
1569
{
1570
    if (result != MAVLinkParameters::Result::Success) {
×
1571
        LogErr() << "Error: Param for mag cal failed.";
×
1572
        return;
×
1573
    }
1574

1575
    bool ok = (value != 0);
×
1576
    set_health_magnetometer_calibration(ok);
×
1577
}
1578

1579
void TelemetryImpl::receive_param_cal_mag_offset_x(MAVLinkParameters::Result result, float value)
×
1580
{
1581
    if (result != MAVLinkParameters::Result::Success) {
×
1582
        LogErr() << "Error: Param for mag offset_x failed.";
×
1583
        return;
×
1584
    }
1585

1586
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1587
    _ap_calibration.mag_offset.x = {value};
×
1588
    if (_ap_calibration.mag_offset.received_all()) {
×
1589
        set_health_magnetometer_calibration(_ap_calibration.mag_offset.calibrated());
×
1590
    }
1591
}
1592

1593
void TelemetryImpl::receive_param_cal_mag_offset_y(MAVLinkParameters::Result result, float value)
×
1594
{
1595
    if (result != MAVLinkParameters::Result::Success) {
×
1596
        LogErr() << "Error: Param for mag offset_y failed.";
×
1597
        return;
×
1598
    }
1599

1600
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1601
    _ap_calibration.mag_offset.y = {value};
×
1602
    if (_ap_calibration.mag_offset.received_all()) {
×
1603
        set_health_magnetometer_calibration(_ap_calibration.mag_offset.calibrated());
×
1604
    }
1605
}
1606

1607
void TelemetryImpl::receive_param_cal_mag_offset_z(MAVLinkParameters::Result result, float value)
×
1608
{
1609
    if (result != MAVLinkParameters::Result::Success) {
×
1610
        LogErr() << "Error: Param for mag offset_z failed.";
×
1611
        return;
×
1612
    }
1613

1614
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1615
    _ap_calibration.mag_offset.z = {value};
×
1616
    if (_ap_calibration.mag_offset.received_all()) {
×
1617
        set_health_magnetometer_calibration(_ap_calibration.mag_offset.calibrated());
×
1618
    }
1619
}
1620

1621
void TelemetryImpl::receive_param_cal_accel_offset_x(MAVLinkParameters::Result result, float value)
×
1622
{
1623
    if (result != MAVLinkParameters::Result::Success) {
×
1624
        LogErr() << "Error: Param for accel offset_x failed.";
×
1625
        return;
×
1626
    }
1627

1628
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1629
    _ap_calibration.accel_offset.x = {value};
×
1630
    if (_ap_calibration.accel_offset.received_all()) {
×
1631
        set_health_accelerometer_calibration(_ap_calibration.accel_offset.calibrated());
×
1632
    }
1633
}
1634

1635
void TelemetryImpl::receive_param_cal_accel_offset_y(MAVLinkParameters::Result result, float value)
×
1636
{
1637
    if (result != MAVLinkParameters::Result::Success) {
×
1638
        LogErr() << "Error: Param for accel offset_y failed.";
×
1639
        return;
×
1640
    }
1641

1642
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1643
    _ap_calibration.accel_offset.y = {value};
×
1644
    if (_ap_calibration.accel_offset.received_all()) {
×
1645
        set_health_accelerometer_calibration(_ap_calibration.accel_offset.calibrated());
×
1646
    }
1647
}
1648

1649
void TelemetryImpl::receive_param_cal_accel_offset_z(MAVLinkParameters::Result result, float value)
×
1650
{
1651
    if (result != MAVLinkParameters::Result::Success) {
×
1652
        LogErr() << "Error: Param for accel offset_z failed.";
×
1653
        return;
×
1654
    }
1655

1656
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1657
    _ap_calibration.accel_offset.z = {value};
×
1658
    if (_ap_calibration.accel_offset.received_all()) {
×
1659
        set_health_accelerometer_calibration(_ap_calibration.accel_offset.calibrated());
×
1660
    }
1661
}
1662

1663
void TelemetryImpl::receive_param_cal_gyro_offset_x(MAVLinkParameters::Result result, float value)
×
1664
{
1665
    if (result != MAVLinkParameters::Result::Success) {
×
1666
        LogErr() << "Error: Param for gyro offset_x failed.";
×
1667
        return;
×
1668
    }
1669

1670
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1671
    _ap_calibration.gyro_offset.x = {value};
×
1672
    if (_ap_calibration.gyro_offset.received_all()) {
×
1673
        set_health_gyrometer_calibration(_ap_calibration.gyro_offset.calibrated());
×
1674
    }
1675
}
1676

1677
void TelemetryImpl::receive_param_cal_gyro_offset_y(MAVLinkParameters::Result result, float value)
×
1678
{
1679
    if (result != MAVLinkParameters::Result::Success) {
×
1680
        LogErr() << "Error: Param for gyro offset_y failed.";
×
1681
        return;
×
1682
    }
1683

1684
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1685
    _ap_calibration.gyro_offset.y = {value};
×
1686
    if (_ap_calibration.gyro_offset.received_all()) {
×
1687
        set_health_gyrometer_calibration(_ap_calibration.gyro_offset.calibrated());
×
1688
    }
1689
}
1690

1691
void TelemetryImpl::receive_param_cal_gyro_offset_z(MAVLinkParameters::Result result, float value)
×
1692
{
1693
    if (result != MAVLinkParameters::Result::Success) {
×
1694
        LogErr() << "Error: Param for gyro offset_z failed.";
×
1695
        return;
×
1696
    }
1697

1698
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1699
    _ap_calibration.gyro_offset.z = {value};
×
1700
    if (_ap_calibration.gyro_offset.received_all()) {
×
1701
        set_health_gyrometer_calibration(_ap_calibration.gyro_offset.calibrated());
×
1702
    }
1703
}
1704

1705
void TelemetryImpl::receive_param_hitl(MAVLinkParameters::Result result, int value)
×
1706
{
1707
    if (result != MAVLinkParameters::Result::Success) {
×
1708
        LogErr() << "Error: Param to determine hitl failed.";
×
1709
        return;
×
1710
    }
1711

1712
    _hitl_enabled = (value > 0);
×
1713

1714
    // assume sensor calibration ok in hitl
1715
    if (_hitl_enabled) {
×
1716
        set_health_accelerometer_calibration(true);
×
1717
        set_health_gyrometer_calibration(true);
×
1718
        set_health_magnetometer_calibration(true);
×
1719
    }
1720
    _has_received_hitl_param = true;
×
1721
}
1722

1723
void TelemetryImpl::receive_gps_raw_timeout()
×
1724
{
1725
    if (_sys_status_used_for_position == SysStatusUsed::No) {
×
1726
        const bool position_ok = false;
×
1727
        set_health_local_position(position_ok);
×
1728
        set_health_global_position(position_ok);
×
1729
    }
1730
}
×
1731

1732
void TelemetryImpl::receive_unix_epoch_timeout()
×
1733
{
1734
    const uint64_t unix_epoch = 0;
×
1735
    set_unix_epoch_time_us(unix_epoch);
×
1736
}
×
1737

1738
Telemetry::PositionVelocityNed TelemetryImpl::position_velocity_ned() const
×
1739
{
1740
    std::lock_guard<std::mutex> lock(_position_velocity_ned_mutex);
×
1741
    return _position_velocity_ned;
×
1742
}
1743

1744
void TelemetryImpl::set_position_velocity_ned(Telemetry::PositionVelocityNed position_velocity_ned)
×
1745
{
1746
    std::lock_guard<std::mutex> lock(_position_velocity_ned_mutex);
×
1747
    _position_velocity_ned = position_velocity_ned;
×
1748
}
×
1749

1750
Telemetry::Position TelemetryImpl::position() const
×
1751
{
1752
    std::lock_guard<std::mutex> lock(_position_mutex);
×
1753
    return _position;
×
1754
}
1755

1756
void TelemetryImpl::set_position(Telemetry::Position position)
×
1757
{
1758
    std::lock_guard<std::mutex> lock(_position_mutex);
×
1759
    _position = position;
×
1760
}
×
1761

1762
Telemetry::Heading TelemetryImpl::heading() const
×
1763
{
1764
    std::lock_guard<std::mutex> lock(_heading_mutex);
×
1765
    return _heading;
×
1766
}
1767

1768
void TelemetryImpl::set_heading(Telemetry::Heading heading)
×
1769
{
1770
    std::lock_guard<std::mutex> lock(_heading_mutex);
×
1771
    _heading = heading;
×
1772
}
×
1773

1774
Telemetry::Altitude TelemetryImpl::altitude() const
×
1775
{
1776
    std::lock_guard<std::mutex> lock(_altitude_mutex);
×
1777
    return _altitude;
×
1778
}
1779

1780
void TelemetryImpl::set_altitude(Telemetry::Altitude altitude)
×
1781
{
1782
    std::lock_guard<std::mutex> lock(_altitude_mutex);
×
1783
    _altitude = altitude;
×
1784
}
×
1785

1786
Telemetry::Position TelemetryImpl::home() const
×
1787
{
1788
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
1789
    return _home_position;
×
1790
}
1791

1792
void TelemetryImpl::set_home_position(Telemetry::Position home_position)
×
1793
{
1794
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
1795
    _home_position = home_position;
×
1796
}
×
1797

1798
bool TelemetryImpl::armed() const
×
1799
{
1800
    return _armed;
×
1801
}
1802

1803
bool TelemetryImpl::in_air() const
×
1804
{
1805
    return _in_air;
×
1806
}
1807

1808
void TelemetryImpl::set_in_air(bool in_air_new)
×
1809
{
1810
    _in_air = in_air_new;
×
1811
}
×
1812

1813
void TelemetryImpl::set_status_text(Telemetry::StatusText status_text)
3✔
1814
{
1815
    std::lock_guard<std::mutex> lock(_status_text_mutex);
6✔
1816
    _status_text = status_text;
3✔
1817
}
3✔
1818

1819
Telemetry::StatusText TelemetryImpl::status_text() const
3✔
1820
{
1821
    std::lock_guard<std::mutex> lock(_status_text_mutex);
6✔
1822
    return _status_text;
3✔
1823
}
1824

1825
void TelemetryImpl::set_armed(bool armed_new)
×
1826
{
1827
    _armed = armed_new;
×
1828
}
×
1829

1830
Telemetry::Quaternion TelemetryImpl::attitude_quaternion() const
×
1831
{
1832
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1833
    return _attitude_quaternion;
×
1834
}
1835

1836
Telemetry::AngularVelocityBody TelemetryImpl::attitude_angular_velocity_body() const
×
1837
{
1838
    std::lock_guard<std::mutex> lock(_attitude_angular_velocity_body_mutex);
×
1839
    return _attitude_angular_velocity_body;
×
1840
}
1841

1842
Telemetry::GroundTruth TelemetryImpl::ground_truth() const
×
1843
{
1844
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
1845
    return _ground_truth;
×
1846
}
1847

1848
Telemetry::FixedwingMetrics TelemetryImpl::fixedwing_metrics() const
×
1849
{
1850
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
1851
    return _fixedwing_metrics;
×
1852
}
1853

1854
Telemetry::EulerAngle TelemetryImpl::attitude_euler() const
×
1855
{
1856
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1857
    Telemetry::EulerAngle euler = to_euler_angle_from_quaternion(_attitude_quaternion);
×
1858

1859
    return euler;
×
1860
}
1861

1862
void TelemetryImpl::set_attitude_quaternion(Telemetry::Quaternion quaternion)
×
1863
{
1864
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1865
    _attitude_quaternion = quaternion;
×
1866
}
×
1867

1868
void TelemetryImpl::set_attitude_angular_velocity_body(
×
1869
    Telemetry::AngularVelocityBody angular_velocity_body)
1870
{
1871
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
1872
    _attitude_angular_velocity_body = angular_velocity_body;
×
1873
}
×
1874

1875
void TelemetryImpl::set_ground_truth(Telemetry::GroundTruth ground_truth)
×
1876
{
1877
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
1878
    _ground_truth = ground_truth;
×
1879
}
×
1880

1881
void TelemetryImpl::set_fixedwing_metrics(Telemetry::FixedwingMetrics fixedwing_metrics)
×
1882
{
1883
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
1884
    _fixedwing_metrics = fixedwing_metrics;
×
1885
}
×
1886

1887
Telemetry::Quaternion TelemetryImpl::camera_attitude_quaternion() const
×
1888
{
1889
    std::lock_guard<std::mutex> lock(_camera_attitude_euler_angle_mutex);
×
1890
    Telemetry::Quaternion quaternion = to_quaternion_from_euler_angle(_camera_attitude_euler_angle);
×
1891

1892
    return quaternion;
×
1893
}
1894

1895
Telemetry::EulerAngle TelemetryImpl::camera_attitude_euler() const
×
1896
{
1897
    std::lock_guard<std::mutex> lock(_camera_attitude_euler_angle_mutex);
×
1898

1899
    return _camera_attitude_euler_angle;
×
1900
}
1901

1902
void TelemetryImpl::set_camera_attitude_euler_angle(Telemetry::EulerAngle euler_angle)
×
1903
{
1904
    std::lock_guard<std::mutex> lock(_camera_attitude_euler_angle_mutex);
×
1905
    _camera_attitude_euler_angle = euler_angle;
×
1906
}
×
1907

1908
Telemetry::VelocityNed TelemetryImpl::velocity_ned() const
×
1909
{
1910
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
1911
    return _velocity_ned;
×
1912
}
1913

1914
void TelemetryImpl::set_velocity_ned(Telemetry::VelocityNed velocity_ned)
×
1915
{
1916
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
1917
    _velocity_ned = velocity_ned;
×
1918
}
×
1919

1920
Telemetry::Imu TelemetryImpl::imu() const
×
1921
{
1922
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
1923
    return _imu_reading_ned;
×
1924
}
1925

1926
void TelemetryImpl::set_imu_reading_ned(Telemetry::Imu imu_reading_ned)
×
1927
{
1928
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
1929
    _imu_reading_ned = imu_reading_ned;
×
1930
}
×
1931

1932
Telemetry::Imu TelemetryImpl::scaled_imu() const
×
1933
{
1934
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
1935
    return _scaled_imu;
×
1936
}
1937

1938
void TelemetryImpl::set_scaled_imu(Telemetry::Imu scaled_imu)
×
1939
{
1940
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
1941
    _scaled_imu = scaled_imu;
×
1942
}
×
1943

1944
Telemetry::Imu TelemetryImpl::raw_imu() const
×
1945
{
1946
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
1947
    return _raw_imu;
×
1948
}
1949

1950
void TelemetryImpl::set_raw_imu(Telemetry::Imu raw_imu)
×
1951
{
1952
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
1953
    _raw_imu = raw_imu;
×
1954
}
×
1955

1956
Telemetry::GpsInfo TelemetryImpl::gps_info() const
×
1957
{
1958
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
×
1959
    return _gps_info;
×
1960
}
1961

1962
void TelemetryImpl::set_gps_info(Telemetry::GpsInfo gps_info)
×
1963
{
1964
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
×
1965
    _gps_info = gps_info;
×
1966
}
×
1967

1968
Telemetry::RawGps TelemetryImpl::raw_gps() const
×
1969
{
1970
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
×
1971
    return _raw_gps;
×
1972
}
1973

1974
void TelemetryImpl::set_raw_gps(Telemetry::RawGps raw_gps)
×
1975
{
1976
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
×
1977
    _raw_gps = raw_gps;
×
1978
}
×
1979

1980
Telemetry::Battery TelemetryImpl::battery() const
×
1981
{
1982
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
1983
    return _battery;
×
1984
}
1985

1986
void TelemetryImpl::set_battery(Telemetry::Battery battery)
×
1987
{
1988
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
1989
    _battery = battery;
×
1990
}
×
1991

1992
Telemetry::FlightMode TelemetryImpl::flight_mode() const
×
1993
{
1994
    return telemetry_flight_mode_from_flight_mode(_parent->get_flight_mode());
×
1995
}
1996

1997
Telemetry::Health TelemetryImpl::health() const
×
1998
{
1999
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2000
    return _health;
×
2001
}
2002

2003
bool TelemetryImpl::health_all_ok() const
×
2004
{
2005
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2006
    if (_health.is_gyrometer_calibration_ok && _health.is_accelerometer_calibration_ok &&
×
2007
        _health.is_magnetometer_calibration_ok && _health.is_local_position_ok &&
×
2008
        _health.is_global_position_ok && _health.is_home_position_ok) {
×
2009
        return true;
×
2010
    } else {
2011
        return false;
×
2012
    }
2013
}
2014

2015
Telemetry::RcStatus TelemetryImpl::rc_status() const
×
2016
{
2017
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
2018
    return _rc_status;
×
2019
}
2020

2021
uint64_t TelemetryImpl::unix_epoch_time() const
×
2022
{
2023
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
2024
    return _unix_epoch_time_us;
×
2025
}
2026

2027
Telemetry::ActuatorControlTarget TelemetryImpl::actuator_control_target() const
×
2028
{
2029
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
2030
    return _actuator_control_target;
×
2031
}
2032

2033
Telemetry::ActuatorOutputStatus TelemetryImpl::actuator_output_status() const
×
2034
{
2035
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
2036
    return _actuator_output_status;
×
2037
}
2038

2039
Telemetry::Odometry TelemetryImpl::odometry() const
×
2040
{
2041
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
2042
    return _odometry;
×
2043
}
2044

2045
Telemetry::DistanceSensor TelemetryImpl::distance_sensor() const
×
2046
{
2047
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
2048
    return _distance_sensor;
×
2049
}
2050

2051
Telemetry::ScaledPressure TelemetryImpl::scaled_pressure() const
×
2052
{
2053
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
2054
    return _scaled_pressure;
×
2055
}
2056

2057
void TelemetryImpl::set_health_local_position(bool ok)
×
2058
{
2059
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2060
    _health.is_local_position_ok = ok;
×
2061
}
×
2062

2063
void TelemetryImpl::set_health_global_position(bool ok)
×
2064
{
2065
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2066
    _health.is_global_position_ok = ok;
×
2067
}
×
2068

2069
void TelemetryImpl::set_health_home_position(bool ok)
×
2070
{
2071
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2072
    _health.is_home_position_ok = ok;
×
2073
}
×
2074

2075
void TelemetryImpl::set_health_gyrometer_calibration(bool ok)
×
2076
{
2077
    _has_received_gyro_calibration = true;
×
2078

2079
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2080
    _health.is_gyrometer_calibration_ok = (ok || _hitl_enabled);
×
2081
}
×
2082

2083
void TelemetryImpl::set_health_accelerometer_calibration(bool ok)
×
2084
{
2085
    _has_received_accel_calibration = true;
×
2086

2087
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2088
    _health.is_accelerometer_calibration_ok = (ok || _hitl_enabled);
×
2089
}
×
2090

2091
void TelemetryImpl::set_health_magnetometer_calibration(bool ok)
×
2092
{
2093
    _has_received_mag_calibration = true;
×
2094

2095
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2096
    _health.is_magnetometer_calibration_ok = (ok || _hitl_enabled);
×
2097
}
×
2098

2099
void TelemetryImpl::set_health_armable(bool ok)
×
2100
{
2101
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2102
    _health.is_armable = ok;
×
2103
}
×
2104

2105
Telemetry::VtolState TelemetryImpl::vtol_state() const
×
2106
{
2107
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
2108
    return _vtol_state;
×
2109
}
2110

2111
void TelemetryImpl::set_vtol_state(Telemetry::VtolState vtol_state)
×
2112
{
2113
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
2114
    _vtol_state = vtol_state;
×
2115
}
×
2116

2117
Telemetry::LandedState TelemetryImpl::landed_state() const
×
2118
{
2119
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2120
    return _landed_state;
×
2121
}
2122

2123
void TelemetryImpl::set_landed_state(Telemetry::LandedState landed_state)
×
2124
{
2125
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2126
    _landed_state = landed_state;
×
2127
}
×
2128

2129
void TelemetryImpl::set_rc_status(
×
2130
    std::optional<bool> maybe_available, std::optional<float> maybe_signal_strength_percent)
2131
{
2132
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
2133

2134
    if (maybe_available) {
×
2135
        _rc_status.is_available = maybe_available.value();
×
2136
        if (maybe_available.value()) {
×
2137
            _rc_status.was_available_once = true;
×
2138
        }
2139
    }
2140

2141
    if (maybe_signal_strength_percent) {
×
2142
        _rc_status.signal_strength_percent = maybe_signal_strength_percent.value();
×
2143
    }
2144
}
×
2145

2146
void TelemetryImpl::set_unix_epoch_time_us(uint64_t time_us)
×
2147
{
2148
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
2149
    _unix_epoch_time_us = time_us;
×
2150
}
×
2151

2152
void TelemetryImpl::set_actuator_control_target(uint8_t group, const std::vector<float>& controls)
×
2153
{
2154
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
2155
    _actuator_control_target.group = group;
×
2156
    _actuator_control_target.controls = controls;
×
2157
}
×
2158

2159
void TelemetryImpl::set_actuator_output_status(uint32_t active, const std::vector<float>& actuators)
×
2160
{
2161
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
2162
    _actuator_output_status.active = active;
×
2163
    _actuator_output_status.actuator = actuators;
×
2164
}
×
2165

2166
void TelemetryImpl::set_odometry(Telemetry::Odometry& odometry)
×
2167
{
2168
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
2169
    _odometry = odometry;
×
2170
}
×
2171

2172
void TelemetryImpl::set_distance_sensor(Telemetry::DistanceSensor& distance_sensor)
×
2173
{
2174
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
2175
    _distance_sensor = distance_sensor;
×
2176
}
×
2177

2178
void TelemetryImpl::set_scaled_pressure(Telemetry::ScaledPressure& scaled_pressure)
×
2179
{
2180
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
2181
    _scaled_pressure = scaled_pressure;
×
2182
}
×
2183

2184
Telemetry::PositionVelocityNedHandle TelemetryImpl::subscribe_position_velocity_ned(
×
2185
    const Telemetry::PositionVelocityNedCallback& callback)
2186
{
2187
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2188
    return _position_velocity_ned_subscriptions.subscribe(callback);
×
2189
}
2190

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

2197
Telemetry::PositionHandle
2198
TelemetryImpl::subscribe_position(const Telemetry::PositionCallback& callback)
×
2199
{
2200
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2201
    return _position_subscriptions.subscribe(callback);
×
2202
}
2203

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

2210
Telemetry::HomeHandle TelemetryImpl::subscribe_home(const Telemetry::PositionCallback& callback)
×
2211
{
2212
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2213
    return _home_position_subscriptions.subscribe(callback);
×
2214
}
2215

2216
void TelemetryImpl::unsubscribe_home(Telemetry::HomeHandle handle)
×
2217
{
2218
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2219
    _home_position_subscriptions.unsubscribe(handle);
×
2220
}
×
2221

2222
Telemetry::InAirHandle TelemetryImpl::subscribe_in_air(const Telemetry::InAirCallback& callback)
×
2223
{
2224
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2225
    return _in_air_subscriptions.subscribe(callback);
×
2226
}
2227

2228
void TelemetryImpl::unsubscribe_in_air(Telemetry::InAirHandle handle)
×
2229
{
2230
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2231
    return _in_air_subscriptions.unsubscribe(handle);
×
2232
}
2233

2234
Telemetry::StatusTextHandle
2235
TelemetryImpl::subscribe_status_text(const Telemetry::StatusTextCallback& callback)
2✔
2236
{
2237
    std::lock_guard<std::mutex> lock(_subscription_mutex);
4✔
2238
    return _status_text_subscriptions.subscribe(callback);
2✔
2239
}
2240

2241
void TelemetryImpl::unsubscribe_status_text(Handle<Telemetry::StatusText> handle)
1✔
2242
{
2243
    std::lock_guard<std::mutex> lock(_subscription_mutex);
2✔
2244
    _status_text_subscriptions.unsubscribe(handle);
1✔
2245
}
1✔
2246

2247
Telemetry::ArmedHandle TelemetryImpl::subscribe_armed(const Telemetry::ArmedCallback& callback)
×
2248
{
2249
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2250
    return _armed_subscriptions.subscribe(callback);
×
2251
}
2252

2253
void TelemetryImpl::unsubscribe_armed(Telemetry::ArmedHandle handle)
×
2254
{
2255
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2256
    _armed_subscriptions.unsubscribe(handle);
×
2257
}
×
2258

2259
Telemetry::AttitudeQuaternionHandle
2260
TelemetryImpl::subscribe_attitude_quaternion(const Telemetry::AttitudeQuaternionCallback& callback)
×
2261
{
2262
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2263
    return _attitude_quaternion_angle_subscriptions.subscribe(callback);
×
2264
}
2265

2266
void TelemetryImpl::unsubscribe_attitude_quaternion(Telemetry::AttitudeQuaternionHandle handle)
×
2267
{
2268
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2269
    _attitude_quaternion_angle_subscriptions.unsubscribe(handle);
×
2270
}
×
2271

2272
Telemetry::AttitudeEulerHandle
2273
TelemetryImpl::subscribe_attitude_euler(const Telemetry::AttitudeEulerCallback& callback)
×
2274
{
2275
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2276
    return _attitude_euler_angle_subscriptions.subscribe(callback);
×
2277
}
2278

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

2285
Telemetry::AttitudeAngularVelocityBodyHandle
2286
TelemetryImpl::subscribe_attitude_angular_velocity_body(
×
2287
    const Telemetry::AttitudeAngularVelocityBodyCallback& callback)
2288
{
2289
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2290
    return _attitude_angular_velocity_body_subscriptions.subscribe(callback);
×
2291
}
2292

2293
void TelemetryImpl::unsubscribe_attitude_angular_velocity_body(
×
2294
    Telemetry::AttitudeAngularVelocityBodyHandle handle)
2295
{
2296
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2297
    _attitude_angular_velocity_body_subscriptions.unsubscribe(handle);
×
2298
}
×
2299

2300
Telemetry::FixedwingMetricsHandle
2301
TelemetryImpl::subscribe_fixedwing_metrics(const Telemetry::FixedwingMetricsCallback& callback)
×
2302
{
2303
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2304
    return _fixedwing_metrics_subscriptions.subscribe(callback);
×
2305
}
2306

2307
void TelemetryImpl::unsubscribe_fixedwing_metrics(Telemetry::FixedwingMetricsHandle handle)
×
2308
{
2309
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2310
    _fixedwing_metrics_subscriptions.unsubscribe(handle);
×
2311
}
×
2312

2313
Telemetry::GroundTruthHandle
2314
TelemetryImpl::subscribe_ground_truth(const Telemetry::GroundTruthCallback& callback)
×
2315
{
2316
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2317
    return _ground_truth_subscriptions.subscribe(callback);
×
2318
}
2319

2320
void TelemetryImpl::unsubscribe_ground_truth(Telemetry::GroundTruthHandle handle)
×
2321
{
2322
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2323
    _ground_truth_subscriptions.unsubscribe(handle);
×
2324
}
×
2325

2326
Telemetry::AttitudeQuaternionHandle TelemetryImpl::subscribe_camera_attitude_quaternion(
×
2327
    const Telemetry::AttitudeQuaternionCallback& callback)
2328
{
2329
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2330
    return _camera_attitude_quaternion_subscriptions.subscribe(callback);
×
2331
}
2332

2333
void TelemetryImpl::unsubscribe_camera_attitude_quaternion(
×
2334
    Telemetry::AttitudeQuaternionHandle handle)
2335
{
2336
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2337
    _camera_attitude_quaternion_subscriptions.unsubscribe(handle);
×
2338
}
×
2339

2340
Telemetry::AttitudeEulerHandle
2341
TelemetryImpl::subscribe_camera_attitude_euler(const Telemetry::AttitudeEulerCallback& callback)
×
2342
{
2343
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2344
    return _camera_attitude_euler_angle_subscriptions.subscribe(callback);
×
2345
}
2346

2347
void TelemetryImpl::unsubscribe_camera_attitude_euler(Telemetry::AttitudeEulerHandle handle)
×
2348
{
2349
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2350
    _camera_attitude_euler_angle_subscriptions.unsubscribe(handle);
×
2351
}
×
2352

2353
Telemetry::VelocityNedHandle
2354
TelemetryImpl::subscribe_velocity_ned(const Telemetry::VelocityNedCallback& callback)
×
2355
{
2356
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2357
    return _velocity_ned_subscriptions.subscribe(callback);
×
2358
}
2359

2360
void TelemetryImpl::unsubscribe_velocity_ned(Telemetry::VelocityNedHandle handle)
×
2361
{
2362
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2363
    _velocity_ned_subscriptions.unsubscribe(handle);
×
2364
}
×
2365

2366
Telemetry::ImuHandle TelemetryImpl::subscribe_imu(const Telemetry::ImuCallback& callback)
×
2367
{
2368
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2369
    return _imu_reading_ned_subscriptions.subscribe(callback);
×
2370
}
2371

2372
void TelemetryImpl::unsubscribe_imu(Telemetry::ImuHandle handle)
×
2373
{
2374
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2375
    return _imu_reading_ned_subscriptions.unsubscribe(handle);
×
2376
}
2377

2378
Telemetry::ScaledImuHandle
2379
TelemetryImpl::subscribe_scaled_imu(const Telemetry::ScaledImuCallback& callback)
×
2380
{
2381
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2382
    return _scaled_imu_subscriptions.subscribe(callback);
×
2383
}
2384

2385
void TelemetryImpl::unsubscribe_scaled_imu(Telemetry::ScaledImuHandle handle)
×
2386
{
2387
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2388
    _scaled_imu_subscriptions.unsubscribe(handle);
×
2389
}
×
2390

2391
Telemetry::RawImuHandle TelemetryImpl::subscribe_raw_imu(const Telemetry::RawImuCallback& callback)
×
2392
{
2393
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2394
    return _raw_imu_subscriptions.subscribe(callback);
×
2395
}
2396

2397
void TelemetryImpl::unsubscribe_raw_imu(Telemetry::RawImuHandle handle)
×
2398
{
2399
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2400
    _raw_imu_subscriptions.unsubscribe(handle);
×
2401
}
×
2402

2403
Telemetry::GpsInfoHandle
2404
TelemetryImpl::subscribe_gps_info(const Telemetry::GpsInfoCallback& callback)
×
2405
{
2406
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2407
    return _gps_info_subscriptions.subscribe(callback);
×
2408
}
2409

2410
void TelemetryImpl::unsubscribe_gps_info(Telemetry::GpsInfoHandle handle)
×
2411
{
2412
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2413
    _gps_info_subscriptions.unsubscribe(handle);
×
2414
}
×
2415

2416
Telemetry::RawGpsHandle TelemetryImpl::subscribe_raw_gps(const Telemetry::RawGpsCallback& callback)
×
2417
{
2418
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2419
    return _raw_gps_subscriptions.subscribe(callback);
×
2420
}
2421

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

2428
Telemetry::BatteryHandle
2429
TelemetryImpl::subscribe_battery(const Telemetry::BatteryCallback& callback)
×
2430
{
2431
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2432
    return _battery_subscriptions.subscribe(callback);
×
2433
}
2434

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

2441
Telemetry::FlightModeHandle
2442
TelemetryImpl::subscribe_flight_mode(const Telemetry::FlightModeCallback& callback)
×
2443
{
2444
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2445
    return _flight_mode_subscriptions.subscribe(callback);
×
2446
}
2447

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

2454
Telemetry::HealthHandle TelemetryImpl::subscribe_health(const Telemetry::HealthCallback& callback)
×
2455
{
2456
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2457
    return _health_subscriptions.subscribe(callback);
×
2458
}
2459

2460
void TelemetryImpl::unsubscribe_health(Telemetry::HealthHandle handle)
×
2461
{
2462
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2463
    _health_subscriptions.unsubscribe(handle);
×
2464
}
×
2465

2466
Telemetry::HealthAllOkHandle
2467
TelemetryImpl::subscribe_health_all_ok(const Telemetry::HealthAllOkCallback& callback)
×
2468
{
2469
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2470
    return _health_all_ok_subscriptions.subscribe(callback);
×
2471
}
2472

2473
void TelemetryImpl::unsubscribe_health_all_ok(Telemetry::HealthAllOkHandle handle)
×
2474
{
2475
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2476
    _health_all_ok_subscriptions.unsubscribe(handle);
×
2477
}
×
2478

2479
Telemetry::VtolStateHandle
2480
TelemetryImpl::subscribe_vtol_state(const Telemetry::VtolStateCallback& callback)
×
2481
{
2482
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2483
    return _vtol_state_subscriptions.subscribe(callback);
×
2484
}
2485

2486
void TelemetryImpl::unsubscribe_vtol_state(Telemetry::VtolStateHandle handle)
×
2487
{
2488
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2489
    _vtol_state_subscriptions.unsubscribe(handle);
×
2490
}
×
2491

2492
Telemetry::LandedStateHandle
2493
TelemetryImpl::subscribe_landed_state(const Telemetry::LandedStateCallback& callback)
×
2494
{
2495
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2496
    return _landed_state_subscriptions.subscribe(callback);
×
2497
}
2498

2499
void TelemetryImpl::unsubscribe_landed_state(Telemetry::LandedStateHandle handle)
×
2500
{
2501
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2502
    _landed_state_subscriptions.unsubscribe(handle);
×
2503
}
×
2504

2505
Telemetry::RcStatusHandle
2506
TelemetryImpl::subscribe_rc_status(const Telemetry::RcStatusCallback& callback)
×
2507
{
2508
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2509
    return _rc_status_subscriptions.subscribe(callback);
×
2510
}
2511

2512
void TelemetryImpl::unsubscribe_rc_status(Telemetry::RcStatusHandle handle)
×
2513
{
2514
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2515
    _rc_status_subscriptions.unsubscribe(handle);
×
2516
}
×
2517

2518
Telemetry::UnixEpochTimeHandle
2519
TelemetryImpl::subscribe_unix_epoch_time(const Telemetry::UnixEpochTimeCallback& callback)
×
2520
{
2521
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2522
    return _unix_epoch_time_subscriptions.subscribe(callback);
×
2523
}
2524

2525
void TelemetryImpl::unsubscribe_unix_epoch_time(Telemetry::UnixEpochTimeHandle handle)
×
2526
{
2527
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2528
    _unix_epoch_time_subscriptions.unsubscribe(handle);
×
2529
}
×
2530

2531
Telemetry::ActuatorControlTargetHandle TelemetryImpl::subscribe_actuator_control_target(
×
2532
    const Telemetry::ActuatorControlTargetCallback& callback)
2533
{
2534
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2535
    return _actuator_control_target_subscriptions.subscribe(callback);
×
2536
}
2537

2538
void TelemetryImpl::unsubscribe_actuator_control_target(
×
2539
    Telemetry::ActuatorControlTargetHandle handle)
2540
{
2541
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2542
    _actuator_control_target_subscriptions.unsubscribe(handle);
×
2543
}
×
2544

2545
Telemetry::ActuatorOutputStatusHandle TelemetryImpl::subscribe_actuator_output_status(
×
2546
    const Telemetry::ActuatorOutputStatusCallback& callback)
2547
{
2548
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2549
    return _actuator_output_status_subscriptions.subscribe(callback);
×
2550
}
2551

2552
void TelemetryImpl::unsubscribe_actuator_output_status(Telemetry::ActuatorOutputStatusHandle handle)
×
2553
{
2554
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2555
    _actuator_output_status_subscriptions.unsubscribe(handle);
×
2556
}
×
2557

2558
Telemetry::OdometryHandle
2559
TelemetryImpl::subscribe_odometry(const Telemetry::OdometryCallback& callback)
×
2560
{
2561
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2562
    return _odometry_subscriptions.subscribe(callback);
×
2563
}
2564

2565
void TelemetryImpl::unsubscribe_odometry(Telemetry::OdometryHandle handle)
×
2566
{
2567
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2568
    _odometry_subscriptions.unsubscribe(handle);
×
2569
}
×
2570

2571
Telemetry::DistanceSensorHandle
2572
TelemetryImpl::subscribe_distance_sensor(const Telemetry::DistanceSensorCallback& callback)
×
2573
{
2574
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2575
    return _distance_sensor_subscriptions.subscribe(callback);
×
2576
}
2577

2578
void TelemetryImpl::unsubscribe_distance_sensor(Telemetry::DistanceSensorHandle handle)
×
2579
{
2580
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2581
    _distance_sensor_subscriptions.unsubscribe(handle);
×
2582
}
×
2583

2584
Telemetry::ScaledPressureHandle
2585
TelemetryImpl::subscribe_scaled_pressure(const Telemetry::ScaledPressureCallback& callback)
×
2586
{
2587
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2588
    return _scaled_pressure_subscriptions.subscribe(callback);
×
2589
}
2590

2591
void TelemetryImpl::unsubscribe_scaled_pressure(Telemetry::ScaledPressureHandle handle)
×
2592
{
2593
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2594
    _scaled_pressure_subscriptions.unsubscribe(handle);
×
2595
}
×
2596

2597
Telemetry::HeadingHandle
2598
TelemetryImpl::subscribe_heading(const Telemetry::HeadingCallback& callback)
×
2599
{
2600
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2601
    return _heading_subscriptions.subscribe(callback);
×
2602
}
2603

2604
void TelemetryImpl::unsubscribe_heading(Telemetry::HeadingHandle handle)
×
2605
{
2606
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2607
    _heading_subscriptions.unsubscribe(handle);
×
2608
}
×
2609

2610
Telemetry::AltitudeHandle
2611
TelemetryImpl::subscribe_altitude(const Telemetry::AltitudeCallback& callback)
×
2612
{
2613
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2614
    return _altitude_subscriptions.subscribe(callback);
×
2615
}
2616

2617
void TelemetryImpl::unsubscribe_altitude(Telemetry::AltitudeHandle handle)
×
2618
{
2619
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2620
    _altitude_subscriptions.unsubscribe(handle);
×
2621
}
×
2622

2623
void TelemetryImpl::request_home_position_async()
×
2624
{
2625
    MavlinkCommandSender::CommandLong command_request_message{};
×
2626
    command_request_message.command = MAV_CMD_REQUEST_MESSAGE;
×
2627
    command_request_message.target_component_id = MAV_COMP_ID_AUTOPILOT1;
×
2628
    command_request_message.params.maybe_param1 = static_cast<float>(MAVLINK_MSG_ID_HOME_POSITION);
×
2629
    _parent->send_command_async(command_request_message, nullptr);
×
2630
}
×
2631

2632
void TelemetryImpl::get_gps_global_origin_async(
×
2633
    const Telemetry::GetGpsGlobalOriginCallback callback)
2634
{
2635
    _parent->request_message().request(
×
2636
        MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN,
2637
        MAV_COMP_ID_AUTOPILOT1,
2638
        [this, callback](MavlinkCommandSender::Result result, const mavlink_message_t& message) {
×
2639
            if (result == MavlinkCommandSender::Result::Success) {
×
2640
                mavlink_gps_global_origin_t mavlink_gps_global_origin;
×
2641
                mavlink_msg_gps_global_origin_decode(&message, &mavlink_gps_global_origin);
×
2642

2643
                Telemetry::GpsGlobalOrigin gps_global_origin;
×
2644
                gps_global_origin.latitude_deg = mavlink_gps_global_origin.latitude * 1e-7;
×
2645
                gps_global_origin.longitude_deg = mavlink_gps_global_origin.longitude * 1e-7;
×
2646
                gps_global_origin.altitude_m = mavlink_gps_global_origin.altitude * 1e-3f;
×
2647
                _parent->call_user_callback([callback, gps_global_origin]() {
×
2648
                    callback(Telemetry::Result::Success, gps_global_origin);
2649
                });
2650

2651
            } else {
2652
                _parent->call_user_callback([callback, result]() {
×
2653
                    callback(telemetry_result_from_command_result(result), {});
2654
                });
2655
            }
2656
        });
×
2657
}
×
2658

2659
std::pair<Telemetry::Result, Telemetry::GpsGlobalOrigin> TelemetryImpl::get_gps_global_origin()
×
2660
{
2661
    auto prom = std::promise<std::pair<Telemetry::Result, Telemetry::GpsGlobalOrigin>>();
×
2662
    auto fut = prom.get_future();
×
2663

2664
    get_gps_global_origin_async(
×
2665
        [&prom](Telemetry::Result result, Telemetry::GpsGlobalOrigin gps_global_origin) {
×
2666
            prom.set_value(std::make_pair(result, gps_global_origin));
×
2667
        });
×
2668
    return fut.get();
×
2669
}
2670

2671
void TelemetryImpl::check_calibration()
×
2672
{
2673
    {
2674
        std::lock_guard<std::mutex> lock(_health_mutex);
×
2675
        if ((_has_received_gyro_calibration && _has_received_accel_calibration &&
×
2676
             _has_received_mag_calibration) ||
×
2677
            _has_received_hitl_param) {
×
2678
            _parent->remove_call_every(_calibration_cookie);
×
2679
            return;
×
2680
        }
2681
    }
2682
    if (_parent->has_autopilot()) {
×
2683
        if (_parent->autopilot() == SystemImpl::Autopilot::ArduPilot) {
×
2684
            // We need to ask for the home position from ArduPilot
2685
            request_home_position_async();
×
2686

2687
            // ArduPilot calibration sets the offsets,
2688
            // if any offset is 0 the calibration is not complete/unhealthy.
2689
            _parent->get_param_float_async(
×
2690
                std::string("INS_GYROFFS_X"),
×
2691
                [this](MAVLinkParameters::Result result, float value) {
×
2692
                    receive_param_cal_gyro_offset_x(result, value);
×
2693
                },
×
2694
                this);
2695

2696
            _parent->get_param_float_async(
×
2697
                std::string("INS_GYROFFS_Y"),
×
2698
                [this](MAVLinkParameters::Result result, float value) {
×
2699
                    receive_param_cal_gyro_offset_y(result, value);
×
2700
                },
×
2701
                this);
2702

2703
            _parent->get_param_float_async(
×
2704
                std::string("INS_GYROFFS_Z"),
×
2705
                [this](MAVLinkParameters::Result result, float value) {
×
2706
                    receive_param_cal_gyro_offset_z(result, value);
×
2707
                },
×
2708
                this);
2709

2710
            _parent->get_param_float_async(
×
2711
                std::string("INS_ACCOFFS_X"),
×
2712
                [this](MAVLinkParameters::Result result, float value) {
×
2713
                    receive_param_cal_accel_offset_x(result, value);
×
2714
                },
×
2715
                this);
2716

2717
            _parent->get_param_float_async(
×
2718
                std::string("INS_ACCOFFS_Y"),
×
2719
                [this](MAVLinkParameters::Result result, float value) {
×
2720
                    receive_param_cal_accel_offset_y(result, value);
×
2721
                },
×
2722
                this);
2723

2724
            _parent->get_param_float_async(
×
2725
                std::string("INS_ACCOFFS_Z"),
×
2726
                [this](MAVLinkParameters::Result result, float value) {
×
2727
                    receive_param_cal_accel_offset_z(result, value);
×
2728
                },
×
2729
                this);
2730

2731
            _parent->get_param_float_async(
×
2732
                std::string("COMPASS_OFS_X"),
×
2733
                [this](MAVLinkParameters::Result result, float value) {
×
2734
                    receive_param_cal_mag_offset_x(result, value);
×
2735
                },
×
2736
                this);
2737

2738
            _parent->get_param_float_async(
×
2739
                std::string("COMPASS_OFS_Y"),
×
2740
                [this](MAVLinkParameters::Result result, float value) {
×
2741
                    receive_param_cal_mag_offset_y(result, value);
×
2742
                },
×
2743
                this);
2744

2745
            _parent->get_param_float_async(
×
2746
                std::string("COMPASS_OFS_Z"),
×
2747
                [this](MAVLinkParameters::Result result, float value) {
×
2748
                    receive_param_cal_mag_offset_z(result, value);
×
2749
                },
×
2750
                this);
2751

2752
        } else {
2753
            _parent->get_param_int_async(
×
2754
                std::string("CAL_GYRO0_ID"),
×
2755
                [this](MAVLinkParameters::Result result, int32_t value) {
×
2756
                    receive_param_cal_gyro(result, value);
×
2757
                },
×
2758
                this);
2759

2760
            _parent->get_param_int_async(
×
2761
                std::string("CAL_ACC0_ID"),
×
2762
                [this](MAVLinkParameters::Result result, int32_t value) {
×
2763
                    receive_param_cal_accel(result, value);
×
2764
                },
×
2765
                this);
2766

2767
            _parent->get_param_int_async(
×
2768
                std::string("CAL_MAG0_ID"),
×
2769
                [this](MAVLinkParameters::Result result, int32_t value) {
×
2770
                    receive_param_cal_mag(result, value);
×
2771
                },
×
2772
                this);
2773

2774
            _parent->get_param_int_async(
×
2775
                std::string("SYS_HITL"),
×
2776
                [this](MAVLinkParameters::Result result, int32_t value) {
×
2777
                    receive_param_hitl(result, value);
×
2778
                },
×
2779
                this);
2780
        }
2781
    }
2782
}
2783

2784
void TelemetryImpl::process_parameter_update(const std::string& name)
×
2785
{
2786
    if (_parent->autopilot() == SystemImpl::Autopilot::ArduPilot) {
×
2787
        if (name.compare("INS_GYROFFS_X") == 0) {
×
2788
            _parent->get_param_float_async(
×
2789
                std::string("INS_GYROFFS_X"),
×
2790
                [this](MAVLinkParameters::Result result, float value) {
×
2791
                    receive_param_cal_gyro_offset_x(result, value);
×
2792
                },
×
2793
                this);
2794
        } else if (name.compare("INS_GYROFFS_Y") == 0) {
×
2795
            _parent->get_param_float_async(
×
2796
                std::string("INS_GYROFFS_Y"),
×
2797
                [this](MAVLinkParameters::Result result, float value) {
×
2798
                    receive_param_cal_gyro_offset_y(result, value);
×
2799
                },
×
2800
                this);
2801
        } else if (name.compare("INS_GYROFFS_Z") == 0) {
×
2802
            _parent->get_param_float_async(
×
2803
                std::string("INS_GYROFFS_Z"),
×
2804
                [this](MAVLinkParameters::Result result, float value) {
×
2805
                    receive_param_cal_gyro_offset_z(result, value);
×
2806
                },
×
2807
                this);
2808
        } else if (name.compare("INS_ACCOFFS_X") == 0) {
×
2809
            _parent->get_param_float_async(
×
2810
                std::string("INS_ACCOFFS_X"),
×
2811
                [this](MAVLinkParameters::Result result, float value) {
×
2812
                    receive_param_cal_accel_offset_x(result, value);
×
2813
                },
×
2814
                this);
2815
        } else if (name.compare("INS_ACCOFFS_Y") == 0) {
×
2816
            _parent->get_param_float_async(
×
2817
                std::string("INS_ACCOFFS_Y"),
×
2818
                [this](MAVLinkParameters::Result result, float value) {
×
2819
                    receive_param_cal_accel_offset_y(result, value);
×
2820
                },
×
2821
                this);
2822
        } else if (name.compare("INS_ACCOFFS_Z") == 0) {
×
2823
            _parent->get_param_float_async(
×
2824
                std::string("INS_ACCOFFS_Z"),
×
2825
                [this](MAVLinkParameters::Result result, float value) {
×
2826
                    receive_param_cal_accel_offset_z(result, value);
×
2827
                },
×
2828
                this);
2829
        } else if (name.compare("COMPASS_OFS_X") == 0) {
×
2830
            _parent->get_param_float_async(
×
2831
                std::string("COMPASS_OFS_X"),
×
2832
                [this](MAVLinkParameters::Result result, float value) {
×
2833
                    receive_param_cal_mag_offset_x(result, value);
×
2834
                },
×
2835
                this);
2836
        } else if (name.compare("COMPASS_OFS_Y") == 0) {
×
2837
            _parent->get_param_float_async(
×
2838
                std::string("COMPASS_OFS_Y"),
×
2839
                [this](MAVLinkParameters::Result result, float value) {
×
2840
                    receive_param_cal_mag_offset_y(result, value);
×
2841
                },
×
2842
                this);
2843
        } else if (name.compare("COMPASS_OFS_Z") == 0) {
×
2844
            _parent->get_param_float_async(
×
2845
                std::string("COMPASS_OFS_Z"),
×
2846
                [this](MAVLinkParameters::Result result, float value) {
×
2847
                    receive_param_cal_mag_offset_z(result, value);
×
2848
                },
×
2849
                this);
2850
        }
2851
    } else {
2852
        if (name.compare("CAL_GYRO0_ID") == 0) {
×
2853
            _parent->get_param_int_async(
×
2854
                std::string("CAL_GYRO0_ID"),
×
2855
                [this](MAVLinkParameters::Result result, int32_t value) {
×
2856
                    receive_param_cal_gyro(result, value);
×
2857
                },
×
2858
                this);
2859

2860
        } else if (name.compare("CAL_ACC0_ID") == 0) {
×
2861
            _parent->get_param_int_async(
×
2862
                std::string("CAL_ACC0_ID"),
×
2863
                [this](MAVLinkParameters::Result result, int32_t value) {
×
2864
                    receive_param_cal_accel(result, value);
×
2865
                },
×
2866
                this);
2867
        } else if (name.compare("CAL_MAG0_ID") == 0) {
×
2868
            _parent->get_param_int_async(
×
2869
                std::string("CAL_MAG0_ID"),
×
2870
                [this](MAVLinkParameters::Result result, int32_t value) {
×
2871
                    receive_param_cal_mag(result, value);
×
2872
                },
×
2873
                this);
2874

2875
        } else if (name.compare("SYS_HITL") == 0) {
×
2876
            _parent->get_param_int_async(
×
2877
                std::string("SYS_HITL"),
×
2878
                [this](MAVLinkParameters::Result result, int32_t value) {
×
2879
                    receive_param_hitl(result, value);
×
2880
                },
×
2881
                this);
2882
        }
2883
    }
2884
}
×
2885

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