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

mavlink / MAVSDK / 8258243043

13 Mar 2024 12:47AM UTC coverage: 36.094% (-0.3%) from 36.352%
8258243043

push

github

web-flow
gimbal: add attitude (#2244)

It's confusing to have this as part of telemetry, especially once we
support more than one gimbal.

Signed-off-by: Julian Oes <julian@oes.ch>

32 of 289 new or added lines in 7 files covered. (11.07%)

17 existing lines in 6 files now uncovered.

10089 of 27952 relevant lines covered (36.09%)

124.23 hits per line

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

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

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

14
namespace mavsdk {
15

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

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

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

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

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

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

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

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

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

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

91
    _system_impl->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
    _system_impl->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
    _system_impl->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
    _system_impl->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
    _system_impl->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
    _system_impl->register_mavlink_message_handler(
1✔
119
        MAVLINK_MSG_ID_HEARTBEAT,
120
        [this](const mavlink_message_t& message) { process_heartbeat(message); },
×
121
        this);
122

123
    _system_impl->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
    _system_impl->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
    _system_impl->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
    _system_impl->register_mavlink_message_handler(
1✔
139
        MAVLINK_MSG_ID_ODOMETRY,
140
        [this](const mavlink_message_t& message) { process_odometry(message); },
×
141
        this);
142

143
    _system_impl->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
    _system_impl->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
    _system_impl->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
    _system_impl->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
    _system_impl->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
    _system_impl->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
    _system_impl->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
    _system_impl->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
    _system_impl->register_mavlink_message_handler(
1✔
184
        MAVLINK_MSG_ID_ALTITUDE,
185
        [this](const mavlink_message_t& message) { process_altitude(message); },
×
186
        this);
187

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

191
    _system_impl->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
    _system_impl->cancel_all_param(this);
1✔
201
    _system_impl->remove_call_every(_calibration_cookie);
1✔
202
    _system_impl->unregister_statustext_handler(this);
1✔
203
    _system_impl->unregister_timeout_handler(_gps_raw_timeout_cookie);
1✔
204
    _system_impl->unregister_timeout_handler(_unix_epoch_timeout_cookie);
1✔
205
    _system_impl->unregister_param_changed_handler(this);
1✔
206
    _system_impl->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
    _system_impl->register_timeout_handler(
1✔
223
        [this]() { receive_gps_raw_timeout(); }, 2.0, &_gps_raw_timeout_cookie);
×
224

225
    _system_impl->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
    _system_impl->add_call_every([this]() { check_calibration(); }, 5.0, &_calibration_cookie);
2✔
232

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

422
void TelemetryImpl::set_rate_position_async(double rate_hz, Telemetry::ResultCallback callback)
×
423
{
424
    _position_rate_hz = rate_hz;
×
425
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
426

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

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

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

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

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

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

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

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

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

508
void TelemetryImpl::set_rate_velocity_ned_async(double rate_hz, Telemetry::ResultCallback callback)
×
509
{
510
    _velocity_ned_rate_hz = rate_hz;
×
511
    double max_rate_hz = std::max(_position_rate_hz, _velocity_ned_rate_hz);
×
512

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

694
    callback(action_result);
×
695
}
×
696

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

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

710
    set_position_velocity_ned(position_velocity);
×
711

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

717
    set_health_local_position(true);
×
718
}
×
719

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

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

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

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

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

754
    _velocity_ned_subscriptions.queue(
×
755
        velocity_ned(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
756

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

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

771
    set_home_position(new_pos);
×
772

773
    set_health_home_position(true);
×
774

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

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

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

792
    Telemetry::AngularVelocityBody angular_velocity_body;
×
793
    angular_velocity_body.roll_rad_s = attitude.rollspeed;
×
794
    angular_velocity_body.pitch_rad_s = attitude.pitchspeed;
×
795
    angular_velocity_body.yaw_rad_s = attitude.yawspeed;
×
796
    set_attitude_angular_velocity_body(angular_velocity_body);
×
797

798
    _attitude_euler_angle_subscriptions.queue(
×
799
        attitude_euler(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
800

801
    _attitude_angular_velocity_body_subscriptions.queue(
×
802
        attitude_angular_velocity_body(),
803
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
804
}
×
805

806
void TelemetryImpl::process_attitude_quaternion(const mavlink_message_t& message)
×
807
{
808
    mavlink_attitude_quaternion_t mavlink_attitude_quaternion;
×
809
    mavlink_msg_attitude_quaternion_decode(&message, &mavlink_attitude_quaternion);
×
810

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

819
    Telemetry::AngularVelocityBody angular_velocity_body;
×
820
    angular_velocity_body.roll_rad_s = mavlink_attitude_quaternion.rollspeed;
×
821
    angular_velocity_body.pitch_rad_s = mavlink_attitude_quaternion.pitchspeed;
×
822
    angular_velocity_body.yaw_rad_s = mavlink_attitude_quaternion.yawspeed;
×
823

824
    set_attitude_quaternion(quaternion);
×
825

826
    set_attitude_angular_velocity_body(angular_velocity_body);
×
827

828
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
829
    _attitude_quaternion_angle_subscriptions.queue(attitude_quaternion(), [this](const auto& func) {
×
830
        _system_impl->call_user_callback(func);
×
831
    });
×
832

833
    _attitude_angular_velocity_body_subscriptions.queue(
×
834
        attitude_angular_velocity_body(),
835
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
836
}
×
837

838
void TelemetryImpl::process_altitude(const mavlink_message_t& message)
×
839
{
840
    mavlink_altitude_t mavlink_altitude;
×
841
    mavlink_msg_altitude_decode(&message, &mavlink_altitude);
×
842

843
    Telemetry::Altitude new_altitude;
×
844
    new_altitude.altitude_monotonic_m = mavlink_altitude.altitude_monotonic;
×
845
    new_altitude.altitude_amsl_m = mavlink_altitude.altitude_amsl;
×
846
    new_altitude.altitude_local_m = mavlink_altitude.altitude_local;
×
847
    new_altitude.altitude_relative_m = mavlink_altitude.altitude_relative;
×
848
    new_altitude.altitude_terrain_m = mavlink_altitude.altitude_terrain;
×
849
    new_altitude.bottom_clearance_m = mavlink_altitude.bottom_clearance;
×
850

851
    set_altitude(new_altitude);
×
852

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

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

864
    Telemetry::EulerAngle euler_angle;
×
865
    euler_angle.roll_deg = mount_orientation.roll;
×
866
    euler_angle.pitch_deg = mount_orientation.pitch;
×
867
    euler_angle.yaw_deg = mount_orientation.yaw_absolute;
×
868

869
    set_camera_attitude_euler_angle(euler_angle);
×
870

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

876
    _camera_attitude_euler_angle_subscriptions.queue(
×
877
        camera_attitude_euler(),
878
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
879
}
×
880

881
void TelemetryImpl::process_gimbal_device_attitude_status(const mavlink_message_t& message)
×
882
{
883
    // We accept both MOUNT_ORIENTATION and GIMBAL_DEVICE_ATTITUDE_STATUS for now,
884
    // in order to support both gimbal v1 and v2 protocols.
885

886
    mavlink_gimbal_device_attitude_status_t attitude_status;
×
887
    mavlink_msg_gimbal_device_attitude_status_decode(&message, &attitude_status);
×
888

NEW
889
    Quaternion quaternion;
×
NEW
890
    quaternion.w = attitude_status.q[0];
×
NEW
891
    quaternion.x = attitude_status.q[1];
×
NEW
892
    quaternion.y = attitude_status.q[2];
×
NEW
893
    quaternion.z = attitude_status.q[3];
×
894

NEW
895
    EulerAngle euler_angle = to_euler_angle_from_quaternion(quaternion);
×
896

NEW
897
    auto telemetry_euler_angle = Telemetry::EulerAngle{};
×
NEW
898
    telemetry_euler_angle.timestamp_us = attitude_status.time_boot_ms * 1000;
×
NEW
899
    telemetry_euler_angle.roll_deg = euler_angle.roll_deg;
×
NEW
900
    telemetry_euler_angle.pitch_deg = euler_angle.pitch_deg;
×
NEW
901
    telemetry_euler_angle.yaw_deg = euler_angle.yaw_deg;
×
902

NEW
903
    set_camera_attitude_euler_angle(telemetry_euler_angle);
×
904

905
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
906
    _camera_attitude_quaternion_subscriptions.queue(
×
907
        camera_attitude_quaternion(),
908
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
909

910
    _camera_attitude_euler_angle_subscriptions.queue(
×
911
        camera_attitude_euler(),
912
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
913
}
×
914

915
void TelemetryImpl::process_imu_reading_ned(const mavlink_message_t& message)
×
916
{
917
    mavlink_highres_imu_t highres_imu;
×
918
    mavlink_msg_highres_imu_decode(&message, &highres_imu);
×
919
    Telemetry::Imu new_imu;
×
920
    new_imu.acceleration_frd.forward_m_s2 = highres_imu.xacc;
×
921
    new_imu.acceleration_frd.right_m_s2 = highres_imu.yacc;
×
922
    new_imu.acceleration_frd.down_m_s2 = highres_imu.zacc;
×
923
    new_imu.angular_velocity_frd.forward_rad_s = highres_imu.xgyro;
×
924
    new_imu.angular_velocity_frd.right_rad_s = highres_imu.ygyro;
×
925
    new_imu.angular_velocity_frd.down_rad_s = highres_imu.zgyro;
×
926
    new_imu.magnetic_field_frd.forward_gauss = highres_imu.xmag;
×
927
    new_imu.magnetic_field_frd.right_gauss = highres_imu.ymag;
×
928
    new_imu.magnetic_field_frd.down_gauss = highres_imu.zmag;
×
929
    new_imu.temperature_degc = highres_imu.temperature;
×
930
    new_imu.timestamp_us = highres_imu.time_usec;
×
931

932
    set_imu_reading_ned(new_imu);
×
933

934
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
935
    _imu_reading_ned_subscriptions.queue(
×
936
        imu(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
937
}
×
938

939
void TelemetryImpl::process_scaled_imu(const mavlink_message_t& message)
×
940
{
941
    mavlink_scaled_imu_t scaled_imu_reading;
×
942
    mavlink_msg_scaled_imu_decode(&message, &scaled_imu_reading);
×
943
    Telemetry::Imu new_imu;
×
944
    new_imu.acceleration_frd.forward_m_s2 = scaled_imu_reading.xacc;
×
945
    new_imu.acceleration_frd.right_m_s2 = scaled_imu_reading.yacc;
×
946
    new_imu.acceleration_frd.down_m_s2 = scaled_imu_reading.zacc;
×
947
    new_imu.angular_velocity_frd.forward_rad_s = scaled_imu_reading.xgyro;
×
948
    new_imu.angular_velocity_frd.right_rad_s = scaled_imu_reading.ygyro;
×
949
    new_imu.angular_velocity_frd.down_rad_s = scaled_imu_reading.zgyro;
×
950
    new_imu.magnetic_field_frd.forward_gauss = scaled_imu_reading.xmag;
×
951
    new_imu.magnetic_field_frd.right_gauss = scaled_imu_reading.ymag;
×
952
    new_imu.magnetic_field_frd.down_gauss = scaled_imu_reading.zmag;
×
953
    new_imu.temperature_degc = static_cast<float>(scaled_imu_reading.temperature) * 1e-2f;
×
954
    new_imu.timestamp_us = static_cast<uint64_t>(scaled_imu_reading.time_boot_ms) * 1000;
×
955

956
    set_scaled_imu(new_imu);
×
957

958
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
959
    _scaled_imu_subscriptions.queue(
×
960
        scaled_imu(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
961
}
×
962

963
void TelemetryImpl::process_raw_imu(const mavlink_message_t& message)
×
964
{
965
    mavlink_raw_imu_t raw_imu_reading;
×
966
    mavlink_msg_raw_imu_decode(&message, &raw_imu_reading);
×
967
    Telemetry::Imu new_imu;
×
968
    new_imu.acceleration_frd.forward_m_s2 = raw_imu_reading.xacc;
×
969
    new_imu.acceleration_frd.right_m_s2 = raw_imu_reading.yacc;
×
970
    new_imu.acceleration_frd.down_m_s2 = raw_imu_reading.zacc;
×
971
    new_imu.angular_velocity_frd.forward_rad_s = raw_imu_reading.xgyro;
×
972
    new_imu.angular_velocity_frd.right_rad_s = raw_imu_reading.ygyro;
×
973
    new_imu.angular_velocity_frd.down_rad_s = raw_imu_reading.zgyro;
×
974
    new_imu.magnetic_field_frd.forward_gauss = raw_imu_reading.xmag;
×
975
    new_imu.magnetic_field_frd.right_gauss = raw_imu_reading.ymag;
×
976
    new_imu.magnetic_field_frd.down_gauss = raw_imu_reading.zmag;
×
977
    new_imu.temperature_degc = static_cast<float>(raw_imu_reading.temperature) * 1e-2f;
×
978
    new_imu.timestamp_us = raw_imu_reading.time_usec;
×
979

980
    set_raw_imu(new_imu);
×
981

982
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
983
    _raw_imu_subscriptions.queue(
×
984
        raw_imu(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
985
}
×
986

987
void TelemetryImpl::process_gps_raw_int(const mavlink_message_t& message)
×
988
{
989
    mavlink_gps_raw_int_t gps_raw_int;
×
990
    mavlink_msg_gps_raw_int_decode(&message, &gps_raw_int);
×
991

992
    Telemetry::FixType fix_type;
993
    switch (gps_raw_int.fix_type) {
×
994
        case 0:
×
995
            fix_type = Telemetry::FixType::NoGps;
×
996
            break;
×
997
        case 1:
×
998
            fix_type = Telemetry::FixType::NoFix;
×
999
            break;
×
1000
        case 2:
×
1001
            fix_type = Telemetry::FixType::Fix2D;
×
1002
            break;
×
1003
        case 3:
×
1004
            fix_type = Telemetry::FixType::Fix3D;
×
1005
            break;
×
1006
        case 4:
×
1007
            fix_type = Telemetry::FixType::FixDgps;
×
1008
            break;
×
1009
        case 5:
×
1010
            fix_type = Telemetry::FixType::RtkFloat;
×
1011
            break;
×
1012
        case 6:
×
1013
            fix_type = Telemetry::FixType::RtkFixed;
×
1014
            break;
×
1015

1016
        default:
×
1017
            LogErr() << "Received unknown GPS fix type!";
×
1018
            fix_type = Telemetry::FixType::NoGps;
×
1019
            break;
×
1020
    }
1021

1022
    Telemetry::GpsInfo new_gps_info;
×
1023
    new_gps_info.num_satellites = gps_raw_int.satellites_visible;
×
1024
    new_gps_info.fix_type = fix_type;
×
1025
    set_gps_info(new_gps_info);
×
1026

1027
    Telemetry::RawGps raw_gps_info;
×
1028
    raw_gps_info.timestamp_us = gps_raw_int.time_usec;
×
1029
    raw_gps_info.latitude_deg = gps_raw_int.lat * 1e-7;
×
1030
    raw_gps_info.longitude_deg = gps_raw_int.lon * 1e-7;
×
1031
    raw_gps_info.absolute_altitude_m = gps_raw_int.alt * 1e-3f;
×
1032
    raw_gps_info.hdop = static_cast<float>(gps_raw_int.eph) * 1e-2f;
×
1033
    raw_gps_info.vdop = static_cast<float>(gps_raw_int.epv) * 1e-2f;
×
1034
    raw_gps_info.velocity_m_s = static_cast<float>(gps_raw_int.vel) * 1e-2f;
×
1035
    raw_gps_info.cog_deg = static_cast<float>(gps_raw_int.cog) * 1e-2f;
×
1036
    raw_gps_info.altitude_ellipsoid_m = static_cast<float>(gps_raw_int.alt_ellipsoid) * 1e-3f;
×
1037
    raw_gps_info.horizontal_uncertainty_m = static_cast<float>(gps_raw_int.h_acc) * 1e-3f;
×
1038
    raw_gps_info.vertical_uncertainty_m = static_cast<float>(gps_raw_int.v_acc) * 1e-3f;
×
1039
    raw_gps_info.velocity_uncertainty_m_s = static_cast<float>(gps_raw_int.vel_acc) * 1e-3f;
×
1040
    raw_gps_info.heading_uncertainty_deg = static_cast<float>(gps_raw_int.hdg_acc) * 1e-5f;
×
1041
    raw_gps_info.yaw_deg = static_cast<float>(gps_raw_int.yaw) * 1e-2f;
×
1042
    set_raw_gps(raw_gps_info);
×
1043

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

1048
        set_health_global_position(gps_ok);
×
1049
    }
1050

1051
    {
1052
        std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1053
        _gps_info_subscriptions.queue(
×
1054
            gps_info(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1055
        _raw_gps_subscriptions.queue(
×
1056
            raw_gps(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1057
    }
1058

1059
    _system_impl->refresh_timeout_handler(_gps_raw_timeout_cookie);
×
1060
}
×
1061

1062
void TelemetryImpl::process_ground_truth(const mavlink_message_t& message)
×
1063
{
1064
    mavlink_hil_state_quaternion_t hil_state_quaternion;
×
1065
    mavlink_msg_hil_state_quaternion_decode(&message, &hil_state_quaternion);
×
1066

1067
    Telemetry::GroundTruth new_ground_truth;
×
1068
    new_ground_truth.latitude_deg = hil_state_quaternion.lat * 1e-7;
×
1069
    new_ground_truth.longitude_deg = hil_state_quaternion.lon * 1e-7;
×
1070
    new_ground_truth.absolute_altitude_m = hil_state_quaternion.alt * 1e-3f;
×
1071

1072
    set_ground_truth(new_ground_truth);
×
1073

1074
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1075
    _ground_truth_subscriptions.queue(
×
1076
        ground_truth(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1077
}
×
1078

1079
void TelemetryImpl::process_extended_sys_state(const mavlink_message_t& message)
×
1080
{
1081
    mavlink_extended_sys_state_t extended_sys_state;
×
1082
    mavlink_msg_extended_sys_state_decode(&message, &extended_sys_state);
×
1083

1084
    {
1085
        Telemetry::LandedState landed_state = to_landed_state(extended_sys_state);
×
1086
        set_landed_state(landed_state);
×
1087

1088
        Telemetry::VtolState vtol_state = to_vtol_state(extended_sys_state);
×
1089
        set_vtol_state(vtol_state);
×
1090
    }
1091

1092
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1093
    _landed_state_subscriptions.queue(
×
1094
        landed_state(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1095

1096
    _vtol_state_subscriptions.queue(
×
1097
        vtol_state(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1098

1099
    if (extended_sys_state.landed_state == MAV_LANDED_STATE_IN_AIR ||
×
1100
        extended_sys_state.landed_state == MAV_LANDED_STATE_TAKEOFF ||
×
1101
        extended_sys_state.landed_state == MAV_LANDED_STATE_LANDING) {
×
1102
        set_in_air(true);
×
1103
    } else if (extended_sys_state.landed_state == MAV_LANDED_STATE_ON_GROUND) {
×
1104
        set_in_air(false);
×
1105
    }
1106
    // If landed_state is undefined, we use what we have received last.
1107

1108
    _in_air_subscriptions.queue(
×
1109
        in_air(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1110
}
×
1111
void TelemetryImpl::process_fixedwing_metrics(const mavlink_message_t& message)
×
1112
{
1113
    mavlink_vfr_hud_t vfr_hud;
×
1114
    mavlink_msg_vfr_hud_decode(&message, &vfr_hud);
×
1115

1116
    Telemetry::FixedwingMetrics new_fixedwing_metrics;
×
1117
    new_fixedwing_metrics.airspeed_m_s = vfr_hud.airspeed;
×
1118
    new_fixedwing_metrics.throttle_percentage = vfr_hud.throttle * 1e-2f;
×
1119
    new_fixedwing_metrics.climb_rate_m_s = vfr_hud.climb;
×
1120

1121
    set_fixedwing_metrics(new_fixedwing_metrics);
×
1122

1123
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1124
    _fixedwing_metrics_subscriptions.queue(
×
1125
        fixedwing_metrics(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1126
}
×
1127

1128
void TelemetryImpl::process_sys_status(const mavlink_message_t& message)
×
1129
{
1130
    mavlink_sys_status_t sys_status;
×
1131
    mavlink_msg_sys_status_decode(&message, &sys_status);
×
1132

1133
    if (!_has_bat_status) {
×
1134
        Telemetry::Battery new_battery;
×
1135
        new_battery.voltage_v = sys_status.voltage_battery * 1e-3f;
×
1136
        new_battery.remaining_percent = sys_status.battery_remaining;
×
1137

1138
        set_battery(new_battery);
×
1139

1140
        {
1141
            std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1142
            _battery_subscriptions.queue(
×
1143
                battery(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1144
        }
1145
    }
1146

1147
    const bool rc_ok =
×
1148
        sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
×
1149

1150
    set_rc_status({rc_ok}, std::nullopt);
×
1151

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

1159
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_ACCEL) {
×
1160
        set_health_accelerometer_calibration(
×
1161
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_ACCEL);
×
1162
    } else {
1163
        // If the flag is not supported yet, we fall back to the param.
1164
    }
1165

1166
    if (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_3D_MAG) {
×
1167
        set_health_magnetometer_calibration(
×
1168
            sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_SENSOR_3D_MAG);
×
1169
    } else {
1170
        // If the flag is not supported yet, we fall back to the param.
1171
    }
1172

1173
    const bool global_position_ok =
1174
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_GPS);
×
1175

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

1179
    const bool local_position_ok =
1180
        global_position_ok ||
×
1181
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW) ||
×
1182
        sys_status_present_enabled_health(sys_status, MAV_SYS_STATUS_SENSOR_VISION_POSITION);
×
1183

1184
    set_health_local_position(local_position_ok);
×
1185
    set_health_global_position(global_position_ok);
×
1186

1187
    // If any of these sensors were marked present, we don't have to fall back to check for
1188
    // satellite count.
1189
    _sys_status_used_for_position =
×
1190
        ((sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_GPS) != 0 ||
×
1191
         (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW) != 0 ||
×
1192
         (sys_status.onboard_control_sensors_present & MAV_SYS_STATUS_SENSOR_VISION_POSITION) !=
×
1193
             0) ?
1194
            SysStatusUsed::Yes :
1195
            SysStatusUsed::No;
1196

1197
    set_rc_status({rc_ok}, std::nullopt);
×
1198

1199
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1200
    _rc_status_subscriptions.queue(
×
1201
        rc_status(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1202

1203
    const bool armable = sys_status.onboard_control_sensors_health & MAV_SYS_STATUS_PREARM_CHECK;
×
1204
    set_health_armable(armable);
×
1205
    _health_all_ok_subscriptions.queue(
×
1206
        health_all_ok(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1207
}
×
1208

1209
bool TelemetryImpl::sys_status_present_enabled_health(
×
1210
    const mavlink_sys_status_t& sys_status, MAV_SYS_STATUS_SENSOR flag)
1211
{
1212
    // FIXME: it doesn't look like PX4 sets enabled for GPS
1213
    return (sys_status.onboard_control_sensors_present & flag) != 0 &&
×
1214
           // (sys_status.onboard_control_sensors_enabled & flag) != 0 &&
1215
           (sys_status.onboard_control_sensors_health & flag) != 0;
×
1216
}
1217

1218
void TelemetryImpl::process_battery_status(const mavlink_message_t& message)
×
1219
{
1220
    mavlink_battery_status_t bat_status;
×
1221
    mavlink_msg_battery_status_decode(&message, &bat_status);
×
1222

1223
    _has_bat_status = true;
×
1224

1225
    Telemetry::Battery new_battery;
×
1226
    new_battery.id = bat_status.id;
×
1227
    new_battery.temperature_degc = (bat_status.temperature == std::numeric_limits<int16_t>::max()) ?
×
1228
                                       static_cast<float>(NAN) :
1229
                                       bat_status.temperature * 1e-2f; // cdegC to degC
×
1230
    new_battery.voltage_v = 0.0f;
×
1231
    for (int i = 0; i < 10; ++i) {
×
1232
        if (bat_status.voltages[i] == std::numeric_limits<uint16_t>::max()) {
×
1233
            break;
×
1234
        }
1235
        new_battery.voltage_v += static_cast<float>(bat_status.voltages[i]) * 1e-3f;
×
1236
    }
1237

1238
    for (int i = 0; i < 4; ++i) {
×
1239
        if (bat_status.voltages_ext[i] == std::numeric_limits<uint16_t>::max()) {
×
1240
            // Some implementations out there set it to UINT16_MAX to signal invalid.
1241
            // That's not up to the spec but we can ignore it nevertheless to be backwards
1242
            // compatible.
1243
            break;
×
1244
        } else if (bat_status.voltages_ext[i] > 1) {
×
1245
            // A value of 1 means 0 mV.
1246
            new_battery.voltage_v += static_cast<float>(bat_status.voltages_ext[i]) * 1e-3f;
×
1247
        }
1248
    }
1249

1250
    new_battery.remaining_percent = bat_status.battery_remaining;
×
1251
    new_battery.current_battery_a = (bat_status.current_battery == -1) ?
×
1252
                                        static_cast<float>(NAN) :
1253
                                        bat_status.current_battery * 1e-2f; // cA to A
×
1254
    new_battery.capacity_consumed_ah = (bat_status.current_consumed == -1) ?
×
1255
                                           static_cast<float>(NAN) :
1256
                                           bat_status.current_consumed * 1e-3f; // mAh to Ah
×
1257

1258
    set_battery(new_battery);
×
1259

1260
    {
1261
        std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1262
        _battery_subscriptions.queue(
×
1263
            battery(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1264
    }
1265
}
×
1266

1267
void TelemetryImpl::process_heartbeat(const mavlink_message_t& message)
×
1268
{
1269
    if (message.compid != MAV_COMP_ID_AUTOPILOT1) {
×
1270
        return;
×
1271
    }
1272

1273
    mavlink_heartbeat_t heartbeat;
×
1274
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
×
1275

1276
    set_armed(((heartbeat.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) ? true : false));
×
1277

1278
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1279
    _armed_subscriptions.queue(
×
1280
        armed(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1281

1282
    _flight_mode_subscriptions.queue(
×
1283
        telemetry_flight_mode_from_flight_mode(_system_impl->get_flight_mode()),
×
1284
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1285

1286
    _health_subscriptions.queue(
×
1287
        health(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1288

1289
    _health_all_ok_subscriptions.queue(
×
1290
        health_all_ok(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1291
}
1292

1293
void TelemetryImpl::receive_statustext(const MavlinkStatustextHandler::Statustext& statustext)
3✔
1294
{
1295
    Telemetry::StatusText new_status_text;
6✔
1296

1297
    switch (statustext.severity) {
3✔
1298
        case MAV_SEVERITY_EMERGENCY:
×
1299
            new_status_text.type = Telemetry::StatusTextType::Emergency;
×
1300
            break;
×
1301
        case MAV_SEVERITY_ALERT:
×
1302
            new_status_text.type = Telemetry::StatusTextType::Alert;
×
1303
            break;
×
1304
        case MAV_SEVERITY_CRITICAL:
×
1305
            new_status_text.type = Telemetry::StatusTextType::Critical;
×
1306
            break;
×
1307
        case MAV_SEVERITY_ERROR:
×
1308
            new_status_text.type = Telemetry::StatusTextType::Error;
×
1309
            break;
×
1310
        case MAV_SEVERITY_WARNING:
×
1311
            new_status_text.type = Telemetry::StatusTextType::Warning;
×
1312
            break;
×
1313
        case MAV_SEVERITY_NOTICE:
×
1314
            new_status_text.type = Telemetry::StatusTextType::Notice;
×
1315
            break;
×
1316
        case MAV_SEVERITY_INFO:
3✔
1317
            new_status_text.type = Telemetry::StatusTextType::Info;
3✔
1318
            break;
3✔
1319
        case MAV_SEVERITY_DEBUG:
×
1320
            new_status_text.type = Telemetry::StatusTextType::Debug;
×
1321
            break;
×
1322
        default:
×
1323
            LogWarn() << "Unknown StatusText severity";
×
1324
            new_status_text.type = Telemetry::StatusTextType::Info;
×
1325
            break;
×
1326
    }
1327

1328
    new_status_text.text = statustext.text;
3✔
1329

1330
    set_status_text(new_status_text);
3✔
1331

1332
    std::lock_guard<std::mutex> lock(_subscription_mutex);
6✔
1333
    _status_text_subscriptions.queue(
9✔
1334
        status_text(), [this](const auto& func) { _system_impl->call_user_callback(func); });
11✔
1335
}
3✔
1336

1337
void TelemetryImpl::process_rc_channels(const mavlink_message_t& message)
×
1338
{
1339
    mavlink_rc_channels_t rc_channels;
×
1340
    mavlink_msg_rc_channels_decode(&message, &rc_channels);
×
1341

1342
    if (rc_channels.rssi != std::numeric_limits<uint8_t>::max()) {
×
1343
        set_rc_status(std::nullopt, {rc_channels.rssi});
×
1344
    }
1345

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

1350
    _system_impl->refresh_timeout_handler(_rc_channels_timeout_cookie);
×
1351
}
×
1352

1353
void TelemetryImpl::process_unix_epoch_time(const mavlink_message_t& message)
×
1354
{
1355
    mavlink_utm_global_position_t utm_global_position;
×
1356
    mavlink_msg_utm_global_position_decode(&message, &utm_global_position);
×
1357

1358
    set_unix_epoch_time_us(utm_global_position.time);
×
1359

1360
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1361
    _unix_epoch_time_subscriptions.queue(
×
1362
        unix_epoch_time(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1363

1364
    _system_impl->refresh_timeout_handler(_unix_epoch_timeout_cookie);
×
1365
}
×
1366

1367
void TelemetryImpl::process_actuator_control_target(const mavlink_message_t& message)
×
1368
{
1369
    mavlink_set_actuator_control_target_t target;
×
1370
    mavlink_msg_set_actuator_control_target_decode(&message, &target);
×
1371

1372
    uint32_t group = target.group_mlx;
×
1373
    std::vector<float> controls;
×
1374

1375
    const unsigned control_size = sizeof(target.controls) / sizeof(target.controls[0]);
×
1376
    // Can't use std::copy because target is packed.
1377
    for (std::size_t i = 0; i < control_size; ++i) {
×
1378
        controls.push_back(target.controls[i]);
×
1379
    }
1380

1381
    set_actuator_control_target(group, controls);
×
1382

1383
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1384
    _actuator_control_target_subscriptions.queue(
×
1385
        actuator_control_target(),
×
1386
        [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1387
}
×
1388

1389
void TelemetryImpl::process_actuator_output_status(const mavlink_message_t& message)
×
1390
{
1391
    mavlink_actuator_output_status_t status;
×
1392
    mavlink_msg_actuator_output_status_decode(&message, &status);
×
1393

1394
    uint32_t active = status.active;
×
1395
    std::vector<float> actuators;
×
1396

1397
    const unsigned actuators_size = sizeof(status.actuator) / sizeof(status.actuator[0]);
×
1398
    // Can't use std::copy because status is packed.
1399
    for (std::size_t i = 0; i < actuators_size; ++i) {
×
1400
        actuators.push_back(status.actuator[i]);
×
1401
    }
1402

1403
    set_actuator_output_status(active, actuators);
×
1404

1405
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1406
    _actuator_output_status_subscriptions.queue(actuator_output_status(), [this](const auto& func) {
×
1407
        _system_impl->call_user_callback(func);
×
1408
    });
×
1409
}
×
1410

1411
void TelemetryImpl::process_odometry(const mavlink_message_t& message)
×
1412
{
1413
    mavlink_odometry_t odometry_msg;
×
1414
    mavlink_msg_odometry_decode(&message, &odometry_msg);
×
1415

1416
    Telemetry::Odometry odometry_struct{};
×
1417

1418
    odometry_struct.time_usec = odometry_msg.time_usec;
×
1419
    odometry_struct.frame_id = static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.frame_id);
×
1420
    odometry_struct.child_frame_id =
×
1421
        static_cast<Telemetry::Odometry::MavFrame>(odometry_msg.child_frame_id);
×
1422

1423
    odometry_struct.position_body.x_m = odometry_msg.x;
×
1424
    odometry_struct.position_body.y_m = odometry_msg.y;
×
1425
    odometry_struct.position_body.z_m = odometry_msg.z;
×
1426

1427
    odometry_struct.q.w = odometry_msg.q[0];
×
1428
    odometry_struct.q.x = odometry_msg.q[1];
×
1429
    odometry_struct.q.y = odometry_msg.q[2];
×
1430
    odometry_struct.q.z = odometry_msg.q[3];
×
1431

1432
    odometry_struct.velocity_body.x_m_s = odometry_msg.vx;
×
1433
    odometry_struct.velocity_body.y_m_s = odometry_msg.vy;
×
1434
    odometry_struct.velocity_body.z_m_s = odometry_msg.vz;
×
1435

1436
    odometry_struct.angular_velocity_body.roll_rad_s = odometry_msg.rollspeed;
×
1437
    odometry_struct.angular_velocity_body.pitch_rad_s = odometry_msg.pitchspeed;
×
1438
    odometry_struct.angular_velocity_body.yaw_rad_s = odometry_msg.yawspeed;
×
1439

1440
    const std::size_t len_pose_covariance =
×
1441
        sizeof(odometry_msg.pose_covariance) / sizeof(odometry_msg.pose_covariance[0]);
1442
    for (std::size_t i = 0; i < len_pose_covariance; ++i) {
×
1443
        odometry_struct.pose_covariance.covariance_matrix.push_back(
×
1444
            odometry_msg.pose_covariance[i]);
×
1445
    }
1446

1447
    const std::size_t len_velocity_covariance =
×
1448
        sizeof(odometry_msg.velocity_covariance) / sizeof(odometry_msg.velocity_covariance[0]);
1449
    for (std::size_t i = 0; i < len_velocity_covariance; ++i) {
×
1450
        odometry_struct.velocity_covariance.covariance_matrix.push_back(
×
1451
            odometry_msg.velocity_covariance[i]);
×
1452
    }
1453

1454
    set_odometry(odometry_struct);
×
1455

1456
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1457
    _odometry_subscriptions.queue(
×
1458
        odometry(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1459
}
×
1460

1461
void TelemetryImpl::process_distance_sensor(const mavlink_message_t& message)
×
1462
{
1463
    mavlink_distance_sensor_t distance_sensor_msg;
×
1464
    mavlink_msg_distance_sensor_decode(&message, &distance_sensor_msg);
×
1465

1466
    Telemetry::DistanceSensor distance_sensor_struct{};
×
1467

1468
    distance_sensor_struct.minimum_distance_m =
×
1469
        static_cast<float>(distance_sensor_msg.min_distance) * 1e-2f; // cm to m
×
1470
    distance_sensor_struct.maximum_distance_m =
×
1471
        static_cast<float>(distance_sensor_msg.max_distance) * 1e-2f; // cm to m
×
1472
    distance_sensor_struct.current_distance_m =
×
1473
        static_cast<float>(distance_sensor_msg.current_distance) * 1e-2f; // cm to m
×
1474
    distance_sensor_struct.orientation = extractOrientation(distance_sensor_msg);
×
1475

1476
    set_distance_sensor(distance_sensor_struct);
×
1477

1478
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1479
    _distance_sensor_subscriptions.queue(
×
1480
        distance_sensor(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1481
}
×
1482

1483
Telemetry::EulerAngle
1484
TelemetryImpl::extractOrientation(mavlink_distance_sensor_t distance_sensor_msg)
×
1485
{
1486
    MavSensorOrientation orientation =
×
1487
        static_cast<MavSensorOrientation>(distance_sensor_msg.orientation);
×
1488

1489
    Telemetry::EulerAngle euler_angle;
×
1490
    euler_angle.roll_deg = 0;
×
1491
    euler_angle.pitch_deg = 0;
×
1492
    euler_angle.yaw_deg = 0;
×
1493

1494
    switch (orientation) {
×
1495
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_45: {
×
1496
            euler_angle.yaw_deg = 45;
×
1497
            break;
×
1498
        }
1499
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_90: {
×
1500
            euler_angle.yaw_deg = 90;
×
1501
            break;
×
1502
        }
1503
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_135: {
×
1504
            euler_angle.yaw_deg = 135;
×
1505
            break;
×
1506
        }
1507
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_180: {
×
1508
            euler_angle.yaw_deg = 180;
×
1509
            break;
×
1510
        }
1511
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_225: {
×
1512
            euler_angle.yaw_deg = 225;
×
1513
            break;
×
1514
        }
1515
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_270: {
×
1516
            euler_angle.yaw_deg = 270;
×
1517
            break;
×
1518
        }
1519
        case MavSensorOrientation::MAV_SENSOR_ROTATION_YAW_315: {
×
1520
            euler_angle.yaw_deg = 315;
×
1521
            break;
×
1522
        }
1523
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180: {
×
1524
            euler_angle.roll_deg = 180;
×
1525
            break;
×
1526
        }
1527
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_45: {
×
1528
            euler_angle.roll_deg = 180;
×
1529
            euler_angle.yaw_deg = 45;
×
1530
            break;
×
1531
        }
1532
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_90: {
×
1533
            euler_angle.roll_deg = 180;
×
1534
            euler_angle.yaw_deg = 90;
×
1535
            break;
×
1536
        }
1537
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_135: {
×
1538
            euler_angle.roll_deg = 180;
×
1539
            euler_angle.yaw_deg = 135;
×
1540
            break;
×
1541
        }
1542
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_180: {
×
1543
            euler_angle.pitch_deg = 180;
×
1544
            break;
×
1545
        }
1546
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_225: {
×
1547
            euler_angle.roll_deg = 180;
×
1548
            euler_angle.yaw_deg = 225;
×
1549
            break;
×
1550
        }
1551
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_270: {
×
1552
            euler_angle.roll_deg = 180;
×
1553
            euler_angle.yaw_deg = 270;
×
1554
            break;
×
1555
        }
1556
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_YAW_315: {
×
1557
            euler_angle.roll_deg = 180;
×
1558
            euler_angle.yaw_deg = 315;
×
1559
            break;
×
1560
        }
1561
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90: {
×
1562
            euler_angle.roll_deg = 90;
×
1563
            break;
×
1564
        }
1565
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_45: {
×
1566
            euler_angle.roll_deg = 90;
×
1567
            euler_angle.yaw_deg = 45;
×
1568
            break;
×
1569
        }
1570
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_90: {
×
1571
            euler_angle.roll_deg = 90;
×
1572
            euler_angle.yaw_deg = 90;
×
1573
            break;
×
1574
        }
1575
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_135: {
×
1576
            euler_angle.roll_deg = 90;
×
1577
            euler_angle.yaw_deg = 135;
×
1578
            break;
×
1579
        }
1580
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270: {
×
1581
            euler_angle.roll_deg = 270;
×
1582
            break;
×
1583
        }
1584
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_YAW_45: {
×
1585
            euler_angle.roll_deg = 270;
×
1586
            euler_angle.yaw_deg = 45;
×
1587
            break;
×
1588
        }
1589
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_YAW_90: {
×
1590
            euler_angle.roll_deg = 270;
×
1591
            euler_angle.yaw_deg = 90;
×
1592
            break;
×
1593
        }
1594
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_YAW_135: {
×
1595
            euler_angle.roll_deg = 270;
×
1596
            euler_angle.yaw_deg = 135;
×
1597
            break;
×
1598
        }
1599
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_90: {
×
1600
            euler_angle.pitch_deg = 90;
×
1601
            break;
×
1602
        }
1603
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_270: {
×
1604
            euler_angle.pitch_deg = 270;
×
1605
            break;
×
1606
        }
1607
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_180_YAW_90: {
×
1608
            euler_angle.pitch_deg = 180;
×
1609
            euler_angle.yaw_deg = 90;
×
1610
            break;
×
1611
        }
1612
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_180_YAW_270: {
×
1613
            euler_angle.pitch_deg = 180;
×
1614
            euler_angle.yaw_deg = 270;
×
1615
            break;
×
1616
        }
1617
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_90: {
×
1618
            euler_angle.roll_deg = 90;
×
1619
            euler_angle.pitch_deg = 90;
×
1620
            break;
×
1621
        }
1622
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_PITCH_90: {
×
1623
            euler_angle.roll_deg = 180;
×
1624
            euler_angle.pitch_deg = 90;
×
1625
            break;
×
1626
        }
1627
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_PITCH_90: {
×
1628
            euler_angle.roll_deg = 270;
×
1629
            euler_angle.pitch_deg = 90;
×
1630
            break;
×
1631
        }
1632
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_180: {
×
1633
            euler_angle.roll_deg = 90;
×
1634
            euler_angle.pitch_deg = 180;
×
1635
            break;
×
1636
        }
1637
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_PITCH_180: {
×
1638
            euler_angle.roll_deg = 270;
×
1639
            euler_angle.pitch_deg = 180;
×
1640
            break;
×
1641
        }
1642
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_270: {
×
1643
            euler_angle.roll_deg = 90;
×
1644
            euler_angle.pitch_deg = 270;
×
1645
            break;
×
1646
        }
1647
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_180_PITCH_270: {
×
1648
            euler_angle.roll_deg = 180;
×
1649
            euler_angle.pitch_deg = 270;
×
1650
            break;
×
1651
        }
1652
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_270_PITCH_270: {
×
1653
            euler_angle.roll_deg = 270;
×
1654
            euler_angle.pitch_deg = 270;
×
1655
            break;
×
1656
        }
1657
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90: {
×
1658
            euler_angle.roll_deg = 90;
×
1659
            euler_angle.pitch_deg = 180;
×
1660
            euler_angle.yaw_deg = 90;
×
1661
            break;
×
1662
        }
1663
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_YAW_270: {
×
1664
            euler_angle.roll_deg = 90;
×
1665
            euler_angle.yaw_deg = 270;
×
1666
            break;
×
1667
        }
1668
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_68_YAW_293: {
×
1669
            euler_angle.roll_deg = 90;
×
1670
            euler_angle.pitch_deg = 68;
×
1671
            euler_angle.yaw_deg = 293;
×
1672
            break;
×
1673
        }
1674
        case MavSensorOrientation::MAV_SENSOR_ROTATION_PITCH_315: {
×
1675
            euler_angle.pitch_deg = 315;
×
1676
            break;
×
1677
        }
1678
        case MavSensorOrientation::MAV_SENSOR_ROTATION_ROLL_90_PITCH_315: {
×
1679
            euler_angle.roll_deg = 90;
×
1680
            euler_angle.pitch_deg = 315;
×
1681
            break;
×
1682
        }
1683
        default: {
×
1684
            euler_angle.roll_deg = 0;
×
1685
            euler_angle.pitch_deg = 0;
×
1686
            euler_angle.yaw_deg = 0;
×
1687
        }
1688
    }
1689

1690
    return euler_angle;
×
1691
}
1692

1693
void TelemetryImpl::process_scaled_pressure(const mavlink_message_t& message)
×
1694
{
1695
    mavlink_scaled_pressure_t scaled_pressure_msg;
×
1696
    mavlink_msg_scaled_pressure_decode(&message, &scaled_pressure_msg);
×
1697

1698
    Telemetry::ScaledPressure scaled_pressure_struct{};
×
1699

1700
    scaled_pressure_struct.timestamp_us =
×
1701
        static_cast<uint64_t>(scaled_pressure_msg.time_boot_ms) * 1000;
×
1702
    scaled_pressure_struct.absolute_pressure_hpa = scaled_pressure_msg.press_abs;
×
1703
    scaled_pressure_struct.differential_pressure_hpa = scaled_pressure_msg.press_diff;
×
1704
    scaled_pressure_struct.temperature_deg =
×
1705
        static_cast<float>(scaled_pressure_msg.temperature) * 1e-2f;
×
1706
    scaled_pressure_struct.differential_pressure_temperature_deg =
×
1707
        static_cast<float>(scaled_pressure_msg.temperature_press_diff) * 1e-2f;
×
1708

1709
    set_scaled_pressure(scaled_pressure_struct);
×
1710

1711
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
1712
    _scaled_pressure_subscriptions.queue(
×
1713
        scaled_pressure(), [this](const auto& func) { _system_impl->call_user_callback(func); });
×
1714
}
×
1715

1716
Telemetry::LandedState
1717
TelemetryImpl::to_landed_state(mavlink_extended_sys_state_t extended_sys_state)
×
1718
{
1719
    switch (extended_sys_state.landed_state) {
×
1720
        case MAV_LANDED_STATE_IN_AIR:
×
1721
            return Telemetry::LandedState::InAir;
×
1722
        case MAV_LANDED_STATE_TAKEOFF:
×
1723
            return Telemetry::LandedState::TakingOff;
×
1724
        case MAV_LANDED_STATE_LANDING:
×
1725
            return Telemetry::LandedState::Landing;
×
1726
        case MAV_LANDED_STATE_ON_GROUND:
×
1727
            return Telemetry::LandedState::OnGround;
×
1728
        default:
×
1729
            return Telemetry::LandedState::Unknown;
×
1730
    }
1731
}
1732

1733
Telemetry::VtolState TelemetryImpl::to_vtol_state(mavlink_extended_sys_state_t extended_sys_state)
×
1734
{
1735
    switch (extended_sys_state.vtol_state) {
×
1736
        case MAV_VTOL_STATE::MAV_VTOL_STATE_TRANSITION_TO_FW:
×
1737
            return Telemetry::VtolState::TransitionToFw;
×
1738
        case MAV_VTOL_STATE_TRANSITION_TO_MC:
×
1739
            return Telemetry::VtolState::TransitionToMc;
×
1740
        case MAV_VTOL_STATE_MC:
×
1741
            return Telemetry::VtolState::Mc;
×
1742
        case MAV_VTOL_STATE_FW:
×
1743
            return Telemetry::VtolState::Fw;
×
1744
        default:
×
1745
            return Telemetry::VtolState::Undefined;
×
1746
    }
1747
}
1748

1749
Telemetry::FlightMode TelemetryImpl::telemetry_flight_mode_from_flight_mode(FlightMode flight_mode)
×
1750
{
1751
    switch (flight_mode) {
×
1752
        case FlightMode::Ready:
×
1753
            return Telemetry::FlightMode::Ready;
×
1754
        case FlightMode::Takeoff:
×
1755
            return Telemetry::FlightMode::Takeoff;
×
1756
        case FlightMode::Hold:
×
1757
            return Telemetry::FlightMode::Hold;
×
1758
        case FlightMode::Mission:
×
1759
            return Telemetry::FlightMode::Mission;
×
1760
        case FlightMode::ReturnToLaunch:
×
1761
            return Telemetry::FlightMode::ReturnToLaunch;
×
1762
        case FlightMode::Land:
×
1763
            return Telemetry::FlightMode::Land;
×
1764
        case FlightMode::Offboard:
×
1765
            return Telemetry::FlightMode::Offboard;
×
1766
        case FlightMode::FollowMe:
×
1767
            return Telemetry::FlightMode::FollowMe;
×
1768
        case FlightMode::Manual:
×
1769
            return Telemetry::FlightMode::Manual;
×
1770
        case FlightMode::Posctl:
×
1771
            return Telemetry::FlightMode::Posctl;
×
1772
        case FlightMode::Altctl:
×
1773
            return Telemetry::FlightMode::Altctl;
×
1774
        case FlightMode::Rattitude:
×
1775
            return Telemetry::FlightMode::Rattitude;
×
1776
        case FlightMode::Acro:
×
1777
            return Telemetry::FlightMode::Acro;
×
1778
        case FlightMode::Stabilized:
×
1779
            return Telemetry::FlightMode::Stabilized;
×
1780
        default:
×
1781
            return Telemetry::FlightMode::Unknown;
×
1782
    }
1783
}
1784

1785
void TelemetryImpl::receive_param_cal_gyro(MavlinkParameterClient::Result result, int value)
×
1786
{
1787
    if (result != MavlinkParameterClient::Result::Success) {
×
1788
        LogErr() << "Error: Param for gyro cal failed.";
×
1789
        return;
×
1790
    }
1791

1792
    bool ok = (value != 0);
×
1793
    set_health_gyrometer_calibration(ok);
×
1794
}
1795

1796
void TelemetryImpl::receive_param_cal_accel(MavlinkParameterClient::Result result, int value)
×
1797
{
1798
    if (result != MavlinkParameterClient::Result::Success) {
×
1799
        LogErr() << "Error: Param for accel cal failed.";
×
1800
        return;
×
1801
    }
1802

1803
    bool ok = (value != 0);
×
1804
    set_health_accelerometer_calibration(ok);
×
1805
}
1806

1807
void TelemetryImpl::receive_param_cal_mag(MavlinkParameterClient::Result result, int value)
×
1808
{
1809
    if (result != MavlinkParameterClient::Result::Success) {
×
1810
        LogErr() << "Error: Param for mag cal failed.";
×
1811
        return;
×
1812
    }
1813

1814
    bool ok = (value != 0);
×
1815
    set_health_magnetometer_calibration(ok);
×
1816
}
1817

1818
void TelemetryImpl::receive_param_cal_mag_offset_x(
×
1819
    MavlinkParameterClient::Result result, float value)
1820
{
1821
    if (result != MavlinkParameterClient::Result::Success) {
×
1822
        LogErr() << "Error: Param for mag offset_x failed.";
×
1823
        return;
×
1824
    }
1825

1826
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1827
    _ap_calibration.mag_offset.x = {value};
×
1828
    if (_ap_calibration.mag_offset.received_all()) {
×
1829
        set_health_magnetometer_calibration(_ap_calibration.mag_offset.calibrated());
×
1830
    }
1831
}
1832

1833
void TelemetryImpl::receive_param_cal_mag_offset_y(
×
1834
    MavlinkParameterClient::Result result, float value)
1835
{
1836
    if (result != MavlinkParameterClient::Result::Success) {
×
1837
        LogErr() << "Error: Param for mag offset_y failed.";
×
1838
        return;
×
1839
    }
1840

1841
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1842
    _ap_calibration.mag_offset.y = {value};
×
1843
    if (_ap_calibration.mag_offset.received_all()) {
×
1844
        set_health_magnetometer_calibration(_ap_calibration.mag_offset.calibrated());
×
1845
    }
1846
}
1847

1848
void TelemetryImpl::receive_param_cal_mag_offset_z(
×
1849
    MavlinkParameterClient::Result result, float value)
1850
{
1851
    if (result != MavlinkParameterClient::Result::Success) {
×
1852
        LogErr() << "Error: Param for mag offset_z failed.";
×
1853
        return;
×
1854
    }
1855

1856
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1857
    _ap_calibration.mag_offset.z = {value};
×
1858
    if (_ap_calibration.mag_offset.received_all()) {
×
1859
        set_health_magnetometer_calibration(_ap_calibration.mag_offset.calibrated());
×
1860
    }
1861
}
1862

1863
void TelemetryImpl::receive_param_cal_accel_offset_x(
×
1864
    MavlinkParameterClient::Result result, float value)
1865
{
1866
    if (result != MavlinkParameterClient::Result::Success) {
×
1867
        LogErr() << "Error: Param for accel offset_x failed.";
×
1868
        return;
×
1869
    }
1870

1871
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1872
    _ap_calibration.accel_offset.x = {value};
×
1873
    if (_ap_calibration.accel_offset.received_all()) {
×
1874
        set_health_accelerometer_calibration(_ap_calibration.accel_offset.calibrated());
×
1875
    }
1876
}
1877

1878
void TelemetryImpl::receive_param_cal_accel_offset_y(
×
1879
    MavlinkParameterClient::Result result, float value)
1880
{
1881
    if (result != MavlinkParameterClient::Result::Success) {
×
1882
        LogErr() << "Error: Param for accel offset_y failed.";
×
1883
        return;
×
1884
    }
1885

1886
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1887
    _ap_calibration.accel_offset.y = {value};
×
1888
    if (_ap_calibration.accel_offset.received_all()) {
×
1889
        set_health_accelerometer_calibration(_ap_calibration.accel_offset.calibrated());
×
1890
    }
1891
}
1892

1893
void TelemetryImpl::receive_param_cal_accel_offset_z(
×
1894
    MavlinkParameterClient::Result result, float value)
1895
{
1896
    if (result != MavlinkParameterClient::Result::Success) {
×
1897
        LogErr() << "Error: Param for accel offset_z failed.";
×
1898
        return;
×
1899
    }
1900

1901
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1902
    _ap_calibration.accel_offset.z = {value};
×
1903
    if (_ap_calibration.accel_offset.received_all()) {
×
1904
        set_health_accelerometer_calibration(_ap_calibration.accel_offset.calibrated());
×
1905
    }
1906
}
1907

1908
void TelemetryImpl::receive_param_cal_gyro_offset_x(
×
1909
    MavlinkParameterClient::Result result, float value)
1910
{
1911
    if (result != MavlinkParameterClient::Result::Success) {
×
1912
        LogErr() << "Error: Param for gyro offset_x failed.";
×
1913
        return;
×
1914
    }
1915

1916
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1917
    _ap_calibration.gyro_offset.x = {value};
×
1918
    if (_ap_calibration.gyro_offset.received_all()) {
×
1919
        set_health_gyrometer_calibration(_ap_calibration.gyro_offset.calibrated());
×
1920
    }
1921
}
1922

1923
void TelemetryImpl::receive_param_cal_gyro_offset_y(
×
1924
    MavlinkParameterClient::Result result, float value)
1925
{
1926
    if (result != MavlinkParameterClient::Result::Success) {
×
1927
        LogErr() << "Error: Param for gyro offset_y failed.";
×
1928
        return;
×
1929
    }
1930

1931
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1932
    _ap_calibration.gyro_offset.y = {value};
×
1933
    if (_ap_calibration.gyro_offset.received_all()) {
×
1934
        set_health_gyrometer_calibration(_ap_calibration.gyro_offset.calibrated());
×
1935
    }
1936
}
1937

1938
void TelemetryImpl::receive_param_cal_gyro_offset_z(
×
1939
    MavlinkParameterClient::Result result, float value)
1940
{
1941
    if (result != MavlinkParameterClient::Result::Success) {
×
1942
        LogErr() << "Error: Param for gyro offset_z failed.";
×
1943
        return;
×
1944
    }
1945

1946
    std::lock_guard<std::mutex> lock(_ap_calibration_mutex);
×
1947
    _ap_calibration.gyro_offset.z = {value};
×
1948
    if (_ap_calibration.gyro_offset.received_all()) {
×
1949
        set_health_gyrometer_calibration(_ap_calibration.gyro_offset.calibrated());
×
1950
    }
1951
}
1952

1953
void TelemetryImpl::receive_param_hitl(MavlinkParameterClient::Result result, int value)
×
1954
{
1955
    if (result != MavlinkParameterClient::Result::Success) {
×
1956
        LogErr() << "Error: Param to determine hitl failed.";
×
1957
        return;
×
1958
    }
1959

1960
    _hitl_enabled = (value > 0);
×
1961

1962
    // assume sensor calibration ok in hitl
1963
    if (_hitl_enabled) {
×
1964
        set_health_accelerometer_calibration(true);
×
1965
        set_health_gyrometer_calibration(true);
×
1966
        set_health_magnetometer_calibration(true);
×
1967
    }
1968
    _has_received_hitl_param = true;
×
1969
}
1970

1971
void TelemetryImpl::receive_gps_raw_timeout()
×
1972
{
1973
    if (_sys_status_used_for_position == SysStatusUsed::No) {
×
1974
        const bool position_ok = false;
×
1975
        set_health_local_position(position_ok);
×
1976
        set_health_global_position(position_ok);
×
1977
    }
1978
}
×
1979

1980
void TelemetryImpl::receive_unix_epoch_timeout()
×
1981
{
1982
    const uint64_t unix_epoch = 0;
×
1983
    set_unix_epoch_time_us(unix_epoch);
×
1984
}
×
1985

1986
Telemetry::PositionVelocityNed TelemetryImpl::position_velocity_ned() const
×
1987
{
1988
    std::lock_guard<std::mutex> lock(_position_velocity_ned_mutex);
×
1989
    return _position_velocity_ned;
×
1990
}
1991

1992
void TelemetryImpl::set_position_velocity_ned(Telemetry::PositionVelocityNed position_velocity_ned)
×
1993
{
1994
    std::lock_guard<std::mutex> lock(_position_velocity_ned_mutex);
×
1995
    _position_velocity_ned = position_velocity_ned;
×
1996
}
×
1997

1998
Telemetry::Position TelemetryImpl::position() const
×
1999
{
2000
    std::lock_guard<std::mutex> lock(_position_mutex);
×
2001
    return _position;
×
2002
}
2003

2004
void TelemetryImpl::set_position(Telemetry::Position position)
×
2005
{
2006
    std::lock_guard<std::mutex> lock(_position_mutex);
×
2007
    _position = position;
×
2008
}
×
2009

2010
Telemetry::Heading TelemetryImpl::heading() const
×
2011
{
2012
    std::lock_guard<std::mutex> lock(_heading_mutex);
×
2013
    return _heading;
×
2014
}
2015

2016
void TelemetryImpl::set_heading(Telemetry::Heading heading)
×
2017
{
2018
    std::lock_guard<std::mutex> lock(_heading_mutex);
×
2019
    _heading = heading;
×
2020
}
×
2021

2022
Telemetry::Altitude TelemetryImpl::altitude() const
×
2023
{
2024
    std::lock_guard<std::mutex> lock(_altitude_mutex);
×
2025
    return _altitude;
×
2026
}
2027

2028
void TelemetryImpl::set_altitude(Telemetry::Altitude altitude)
×
2029
{
2030
    std::lock_guard<std::mutex> lock(_altitude_mutex);
×
2031
    _altitude = altitude;
×
2032
}
×
2033

2034
Telemetry::Position TelemetryImpl::home() const
×
2035
{
2036
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
2037
    return _home_position;
×
2038
}
2039

2040
void TelemetryImpl::set_home_position(Telemetry::Position home_position)
×
2041
{
2042
    std::lock_guard<std::mutex> lock(_home_position_mutex);
×
2043
    _home_position = home_position;
×
2044
}
×
2045

2046
bool TelemetryImpl::armed() const
×
2047
{
2048
    return _armed;
×
2049
}
2050

2051
bool TelemetryImpl::in_air() const
×
2052
{
2053
    return _in_air;
×
2054
}
2055

2056
void TelemetryImpl::set_in_air(bool in_air_new)
×
2057
{
2058
    _in_air = in_air_new;
×
2059
}
×
2060

2061
void TelemetryImpl::set_status_text(Telemetry::StatusText status_text)
3✔
2062
{
2063
    std::lock_guard<std::mutex> lock(_status_text_mutex);
6✔
2064
    _status_text = status_text;
3✔
2065
}
3✔
2066

2067
Telemetry::StatusText TelemetryImpl::status_text() const
3✔
2068
{
2069
    std::lock_guard<std::mutex> lock(_status_text_mutex);
6✔
2070
    return _status_text;
3✔
2071
}
2072

2073
void TelemetryImpl::set_armed(bool armed_new)
×
2074
{
2075
    _armed = armed_new;
×
2076
}
×
2077

2078
Telemetry::Quaternion TelemetryImpl::attitude_quaternion() const
×
2079
{
2080
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
2081
    return _attitude_quaternion;
×
2082
}
2083

2084
Telemetry::AngularVelocityBody TelemetryImpl::attitude_angular_velocity_body() const
×
2085
{
2086
    std::lock_guard<std::mutex> lock(_attitude_angular_velocity_body_mutex);
×
2087
    return _attitude_angular_velocity_body;
×
2088
}
2089

2090
Telemetry::GroundTruth TelemetryImpl::ground_truth() const
×
2091
{
2092
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
2093
    return _ground_truth;
×
2094
}
2095

2096
Telemetry::FixedwingMetrics TelemetryImpl::fixedwing_metrics() const
×
2097
{
2098
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
2099
    return _fixedwing_metrics;
×
2100
}
2101

2102
Telemetry::EulerAngle TelemetryImpl::attitude_euler() const
×
2103
{
2104
    std::lock_guard<std::mutex> lock(_attitude_euler_mutex);
×
2105
    return _attitude_euler;
×
2106
}
2107

2108
void TelemetryImpl::set_attitude_quaternion(Telemetry::Quaternion quaternion)
×
2109
{
2110
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
2111
    _attitude_quaternion = quaternion;
×
2112
}
×
2113

2114
void TelemetryImpl::set_attitude_euler(Telemetry::EulerAngle euler)
×
2115
{
2116
    std::lock_guard<std::mutex> lock(_attitude_euler_mutex);
×
2117
    _attitude_euler = euler;
×
2118
}
×
2119

2120
void TelemetryImpl::set_attitude_angular_velocity_body(
×
2121
    Telemetry::AngularVelocityBody angular_velocity_body)
2122
{
2123
    std::lock_guard<std::mutex> lock(_attitude_quaternion_mutex);
×
2124
    _attitude_angular_velocity_body = angular_velocity_body;
×
2125
}
×
2126

2127
void TelemetryImpl::set_ground_truth(Telemetry::GroundTruth ground_truth)
×
2128
{
2129
    std::lock_guard<std::mutex> lock(_ground_truth_mutex);
×
2130
    _ground_truth = ground_truth;
×
2131
}
×
2132

2133
void TelemetryImpl::set_fixedwing_metrics(Telemetry::FixedwingMetrics fixedwing_metrics)
×
2134
{
2135
    std::lock_guard<std::mutex> lock(_fixedwing_metrics_mutex);
×
2136
    _fixedwing_metrics = fixedwing_metrics;
×
2137
}
×
2138

2139
Telemetry::Quaternion TelemetryImpl::camera_attitude_quaternion() const
×
2140
{
2141
    std::lock_guard<std::mutex> lock(_camera_attitude_euler_angle_mutex);
×
2142

NEW
2143
    auto euler_angle = EulerAngle{};
×
NEW
2144
    euler_angle.roll_deg = _camera_attitude_euler_angle.roll_deg;
×
NEW
2145
    euler_angle.pitch_deg = _camera_attitude_euler_angle.pitch_deg;
×
NEW
2146
    euler_angle.yaw_deg = _camera_attitude_euler_angle.yaw_deg;
×
2147

NEW
2148
    auto quaternion = to_quaternion_from_euler_angle(euler_angle);
×
2149

NEW
2150
    auto telemetry_quaternion = Telemetry::Quaternion{};
×
NEW
2151
    telemetry_quaternion.w = quaternion.w;
×
NEW
2152
    telemetry_quaternion.x = quaternion.x;
×
NEW
2153
    telemetry_quaternion.y = quaternion.y;
×
NEW
2154
    telemetry_quaternion.z = quaternion.z;
×
NEW
2155
    telemetry_quaternion.timestamp_us = _camera_attitude_euler_angle.timestamp_us;
×
2156

NEW
2157
    return telemetry_quaternion;
×
2158
}
2159

2160
Telemetry::EulerAngle TelemetryImpl::camera_attitude_euler() const
×
2161
{
2162
    std::lock_guard<std::mutex> lock(_camera_attitude_euler_angle_mutex);
×
2163

2164
    return _camera_attitude_euler_angle;
×
2165
}
2166

2167
void TelemetryImpl::set_camera_attitude_euler_angle(Telemetry::EulerAngle euler_angle)
×
2168
{
2169
    std::lock_guard<std::mutex> lock(_camera_attitude_euler_angle_mutex);
×
2170
    _camera_attitude_euler_angle = euler_angle;
×
2171
}
×
2172

2173
Telemetry::VelocityNed TelemetryImpl::velocity_ned() const
×
2174
{
2175
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
2176
    return _velocity_ned;
×
2177
}
2178

2179
void TelemetryImpl::set_velocity_ned(Telemetry::VelocityNed velocity_ned)
×
2180
{
2181
    std::lock_guard<std::mutex> lock(_velocity_ned_mutex);
×
2182
    _velocity_ned = velocity_ned;
×
2183
}
×
2184

2185
Telemetry::Imu TelemetryImpl::imu() const
×
2186
{
2187
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
2188
    return _imu_reading_ned;
×
2189
}
2190

2191
void TelemetryImpl::set_imu_reading_ned(Telemetry::Imu imu_reading_ned)
×
2192
{
2193
    std::lock_guard<std::mutex> lock(_imu_reading_ned_mutex);
×
2194
    _imu_reading_ned = imu_reading_ned;
×
2195
}
×
2196

2197
Telemetry::Imu TelemetryImpl::scaled_imu() const
×
2198
{
2199
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
2200
    return _scaled_imu;
×
2201
}
2202

2203
void TelemetryImpl::set_scaled_imu(Telemetry::Imu scaled_imu)
×
2204
{
2205
    std::lock_guard<std::mutex> lock(_scaled_imu_mutex);
×
2206
    _scaled_imu = scaled_imu;
×
2207
}
×
2208

2209
Telemetry::Imu TelemetryImpl::raw_imu() const
×
2210
{
2211
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
2212
    return _raw_imu;
×
2213
}
2214

2215
void TelemetryImpl::set_raw_imu(Telemetry::Imu raw_imu)
×
2216
{
2217
    std::lock_guard<std::mutex> lock(_raw_imu_mutex);
×
2218
    _raw_imu = raw_imu;
×
2219
}
×
2220

2221
Telemetry::GpsInfo TelemetryImpl::gps_info() const
×
2222
{
2223
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
×
2224
    return _gps_info;
×
2225
}
2226

2227
void TelemetryImpl::set_gps_info(Telemetry::GpsInfo gps_info)
×
2228
{
2229
    std::lock_guard<std::mutex> lock(_gps_info_mutex);
×
2230
    _gps_info = gps_info;
×
2231
}
×
2232

2233
Telemetry::RawGps TelemetryImpl::raw_gps() const
×
2234
{
2235
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
×
2236
    return _raw_gps;
×
2237
}
2238

2239
void TelemetryImpl::set_raw_gps(Telemetry::RawGps raw_gps)
×
2240
{
2241
    std::lock_guard<std::mutex> lock(_raw_gps_mutex);
×
2242
    _raw_gps = raw_gps;
×
2243
}
×
2244

2245
Telemetry::Battery TelemetryImpl::battery() const
×
2246
{
2247
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
2248
    return _battery;
×
2249
}
2250

2251
void TelemetryImpl::set_battery(Telemetry::Battery battery)
×
2252
{
2253
    std::lock_guard<std::mutex> lock(_battery_mutex);
×
2254
    _battery = battery;
×
2255
}
×
2256

2257
Telemetry::FlightMode TelemetryImpl::flight_mode() const
×
2258
{
2259
    return telemetry_flight_mode_from_flight_mode(_system_impl->get_flight_mode());
×
2260
}
2261

2262
Telemetry::Health TelemetryImpl::health() const
×
2263
{
2264
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2265
    return _health;
×
2266
}
2267

2268
bool TelemetryImpl::health_all_ok() const
×
2269
{
2270
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2271
    if (_health.is_gyrometer_calibration_ok && _health.is_accelerometer_calibration_ok &&
×
2272
        _health.is_magnetometer_calibration_ok && _health.is_local_position_ok &&
×
2273
        _health.is_global_position_ok && _health.is_home_position_ok) {
×
2274
        return true;
×
2275
    } else {
2276
        return false;
×
2277
    }
2278
}
2279

2280
Telemetry::RcStatus TelemetryImpl::rc_status() const
×
2281
{
2282
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
2283
    return _rc_status;
×
2284
}
2285

2286
uint64_t TelemetryImpl::unix_epoch_time() const
×
2287
{
2288
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
2289
    return _unix_epoch_time_us;
×
2290
}
2291

2292
Telemetry::ActuatorControlTarget TelemetryImpl::actuator_control_target() const
×
2293
{
2294
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
2295
    return _actuator_control_target;
×
2296
}
2297

2298
Telemetry::ActuatorOutputStatus TelemetryImpl::actuator_output_status() const
×
2299
{
2300
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
2301
    return _actuator_output_status;
×
2302
}
2303

2304
Telemetry::Odometry TelemetryImpl::odometry() const
×
2305
{
2306
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
2307
    return _odometry;
×
2308
}
2309

2310
Telemetry::DistanceSensor TelemetryImpl::distance_sensor() const
×
2311
{
2312
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
2313
    return _distance_sensor;
×
2314
}
2315

2316
Telemetry::ScaledPressure TelemetryImpl::scaled_pressure() const
×
2317
{
2318
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
2319
    return _scaled_pressure;
×
2320
}
2321

2322
void TelemetryImpl::set_health_local_position(bool ok)
×
2323
{
2324
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2325
    _health.is_local_position_ok = ok;
×
2326
}
×
2327

2328
void TelemetryImpl::set_health_global_position(bool ok)
×
2329
{
2330
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2331
    _health.is_global_position_ok = ok;
×
2332
}
×
2333

2334
void TelemetryImpl::set_health_home_position(bool ok)
×
2335
{
2336
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2337
    _health.is_home_position_ok = ok;
×
2338
}
×
2339

2340
void TelemetryImpl::set_health_gyrometer_calibration(bool ok)
×
2341
{
2342
    _has_received_gyro_calibration = true;
×
2343

2344
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2345
    _health.is_gyrometer_calibration_ok = (ok || _hitl_enabled);
×
2346
}
×
2347

2348
void TelemetryImpl::set_health_accelerometer_calibration(bool ok)
×
2349
{
2350
    _has_received_accel_calibration = true;
×
2351

2352
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2353
    _health.is_accelerometer_calibration_ok = (ok || _hitl_enabled);
×
2354
}
×
2355

2356
void TelemetryImpl::set_health_magnetometer_calibration(bool ok)
×
2357
{
2358
    _has_received_mag_calibration = true;
×
2359

2360
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2361
    _health.is_magnetometer_calibration_ok = (ok || _hitl_enabled);
×
2362
}
×
2363

2364
void TelemetryImpl::set_health_armable(bool ok)
×
2365
{
2366
    std::lock_guard<std::mutex> lock(_health_mutex);
×
2367
    _health.is_armable = ok;
×
2368
}
×
2369

2370
Telemetry::VtolState TelemetryImpl::vtol_state() const
×
2371
{
2372
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
2373
    return _vtol_state;
×
2374
}
2375

2376
void TelemetryImpl::set_vtol_state(Telemetry::VtolState vtol_state)
×
2377
{
2378
    std::lock_guard<std::mutex> lock(_vtol_state_mutex);
×
2379
    _vtol_state = vtol_state;
×
2380
}
×
2381

2382
Telemetry::LandedState TelemetryImpl::landed_state() const
×
2383
{
2384
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2385
    return _landed_state;
×
2386
}
2387

2388
void TelemetryImpl::set_landed_state(Telemetry::LandedState landed_state)
×
2389
{
2390
    std::lock_guard<std::mutex> lock(_landed_state_mutex);
×
2391
    _landed_state = landed_state;
×
2392
}
×
2393

2394
void TelemetryImpl::set_rc_status(
×
2395
    std::optional<bool> maybe_available, std::optional<float> maybe_signal_strength_percent)
2396
{
2397
    std::lock_guard<std::mutex> lock(_rc_status_mutex);
×
2398

2399
    if (maybe_available) {
×
2400
        _rc_status.is_available = maybe_available.value();
×
2401
        if (maybe_available.value()) {
×
2402
            _rc_status.was_available_once = true;
×
2403
        }
2404
    }
2405

2406
    if (maybe_signal_strength_percent) {
×
2407
        _rc_status.signal_strength_percent = maybe_signal_strength_percent.value();
×
2408
    }
2409
}
×
2410

2411
void TelemetryImpl::set_unix_epoch_time_us(uint64_t time_us)
×
2412
{
2413
    std::lock_guard<std::mutex> lock(_unix_epoch_time_mutex);
×
2414
    _unix_epoch_time_us = time_us;
×
2415
}
×
2416

2417
void TelemetryImpl::set_actuator_control_target(uint8_t group, const std::vector<float>& controls)
×
2418
{
2419
    std::lock_guard<std::mutex> lock(_actuator_control_target_mutex);
×
2420
    _actuator_control_target.group = group;
×
2421
    _actuator_control_target.controls = controls;
×
2422
}
×
2423

2424
void TelemetryImpl::set_actuator_output_status(uint32_t active, const std::vector<float>& actuators)
×
2425
{
2426
    std::lock_guard<std::mutex> lock(_actuator_output_status_mutex);
×
2427
    _actuator_output_status.active = active;
×
2428
    _actuator_output_status.actuator = actuators;
×
2429
}
×
2430

2431
void TelemetryImpl::set_odometry(Telemetry::Odometry& odometry)
×
2432
{
2433
    std::lock_guard<std::mutex> lock(_odometry_mutex);
×
2434
    _odometry = odometry;
×
2435
}
×
2436

2437
void TelemetryImpl::set_distance_sensor(Telemetry::DistanceSensor& distance_sensor)
×
2438
{
2439
    std::lock_guard<std::mutex> lock(_distance_sensor_mutex);
×
2440
    _distance_sensor = distance_sensor;
×
2441
}
×
2442

2443
void TelemetryImpl::set_scaled_pressure(Telemetry::ScaledPressure& scaled_pressure)
×
2444
{
2445
    std::lock_guard<std::mutex> lock(_scaled_pressure_mutex);
×
2446
    _scaled_pressure = scaled_pressure;
×
2447
}
×
2448

2449
Telemetry::PositionVelocityNedHandle TelemetryImpl::subscribe_position_velocity_ned(
×
2450
    const Telemetry::PositionVelocityNedCallback& callback)
2451
{
2452
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2453
    return _position_velocity_ned_subscriptions.subscribe(callback);
×
2454
}
2455

2456
void TelemetryImpl::unsubscribe_position_velocity_ned(Telemetry::PositionVelocityNedHandle handle)
×
2457
{
2458
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2459
    _position_velocity_ned_subscriptions.unsubscribe(handle);
×
2460
}
×
2461

2462
Telemetry::PositionHandle
2463
TelemetryImpl::subscribe_position(const Telemetry::PositionCallback& callback)
×
2464
{
2465
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2466
    return _position_subscriptions.subscribe(callback);
×
2467
}
2468

2469
void TelemetryImpl::unsubscribe_position(Telemetry::PositionHandle handle)
×
2470
{
2471
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2472
    _position_subscriptions.unsubscribe(handle);
×
2473
}
×
2474

2475
Telemetry::HomeHandle TelemetryImpl::subscribe_home(const Telemetry::PositionCallback& callback)
×
2476
{
2477
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2478
    return _home_position_subscriptions.subscribe(callback);
×
2479
}
2480

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

2487
Telemetry::InAirHandle TelemetryImpl::subscribe_in_air(const Telemetry::InAirCallback& callback)
×
2488
{
2489
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2490
    return _in_air_subscriptions.subscribe(callback);
×
2491
}
2492

2493
void TelemetryImpl::unsubscribe_in_air(Telemetry::InAirHandle handle)
×
2494
{
2495
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2496
    return _in_air_subscriptions.unsubscribe(handle);
×
2497
}
2498

2499
Telemetry::StatusTextHandle
2500
TelemetryImpl::subscribe_status_text(const Telemetry::StatusTextCallback& callback)
2✔
2501
{
2502
    std::lock_guard<std::mutex> lock(_subscription_mutex);
4✔
2503
    return _status_text_subscriptions.subscribe(callback);
2✔
2504
}
2505

2506
void TelemetryImpl::unsubscribe_status_text(Handle<Telemetry::StatusText> handle)
1✔
2507
{
2508
    std::lock_guard<std::mutex> lock(_subscription_mutex);
2✔
2509
    _status_text_subscriptions.unsubscribe(handle);
1✔
2510
}
1✔
2511

2512
Telemetry::ArmedHandle TelemetryImpl::subscribe_armed(const Telemetry::ArmedCallback& callback)
×
2513
{
2514
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2515
    return _armed_subscriptions.subscribe(callback);
×
2516
}
2517

2518
void TelemetryImpl::unsubscribe_armed(Telemetry::ArmedHandle handle)
×
2519
{
2520
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2521
    _armed_subscriptions.unsubscribe(handle);
×
2522
}
×
2523

2524
Telemetry::AttitudeQuaternionHandle
2525
TelemetryImpl::subscribe_attitude_quaternion(const Telemetry::AttitudeQuaternionCallback& callback)
×
2526
{
2527
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2528
    return _attitude_quaternion_angle_subscriptions.subscribe(callback);
×
2529
}
2530

2531
void TelemetryImpl::unsubscribe_attitude_quaternion(Telemetry::AttitudeQuaternionHandle handle)
×
2532
{
2533
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2534
    _attitude_quaternion_angle_subscriptions.unsubscribe(handle);
×
2535
}
×
2536

2537
Telemetry::AttitudeEulerHandle
2538
TelemetryImpl::subscribe_attitude_euler(const Telemetry::AttitudeEulerCallback& callback)
×
2539
{
2540
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2541
    return _attitude_euler_angle_subscriptions.subscribe(callback);
×
2542
}
2543

2544
void TelemetryImpl::unsubscribe_attitude_euler(Telemetry::AttitudeEulerHandle handle)
×
2545
{
2546
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2547
    _attitude_euler_angle_subscriptions.unsubscribe(handle);
×
2548
}
×
2549

2550
Telemetry::AttitudeAngularVelocityBodyHandle
2551
TelemetryImpl::subscribe_attitude_angular_velocity_body(
×
2552
    const Telemetry::AttitudeAngularVelocityBodyCallback& callback)
2553
{
2554
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2555
    return _attitude_angular_velocity_body_subscriptions.subscribe(callback);
×
2556
}
2557

2558
void TelemetryImpl::unsubscribe_attitude_angular_velocity_body(
×
2559
    Telemetry::AttitudeAngularVelocityBodyHandle handle)
2560
{
2561
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2562
    _attitude_angular_velocity_body_subscriptions.unsubscribe(handle);
×
2563
}
×
2564

2565
Telemetry::FixedwingMetricsHandle
2566
TelemetryImpl::subscribe_fixedwing_metrics(const Telemetry::FixedwingMetricsCallback& callback)
×
2567
{
2568
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2569
    return _fixedwing_metrics_subscriptions.subscribe(callback);
×
2570
}
2571

2572
void TelemetryImpl::unsubscribe_fixedwing_metrics(Telemetry::FixedwingMetricsHandle handle)
×
2573
{
2574
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2575
    _fixedwing_metrics_subscriptions.unsubscribe(handle);
×
2576
}
×
2577

2578
Telemetry::GroundTruthHandle
2579
TelemetryImpl::subscribe_ground_truth(const Telemetry::GroundTruthCallback& callback)
×
2580
{
2581
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2582
    return _ground_truth_subscriptions.subscribe(callback);
×
2583
}
2584

2585
void TelemetryImpl::unsubscribe_ground_truth(Telemetry::GroundTruthHandle handle)
×
2586
{
2587
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2588
    _ground_truth_subscriptions.unsubscribe(handle);
×
2589
}
×
2590

2591
Telemetry::AttitudeQuaternionHandle TelemetryImpl::subscribe_camera_attitude_quaternion(
×
2592
    const Telemetry::AttitudeQuaternionCallback& callback)
2593
{
2594
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2595
    return _camera_attitude_quaternion_subscriptions.subscribe(callback);
×
2596
}
2597

2598
void TelemetryImpl::unsubscribe_camera_attitude_quaternion(
×
2599
    Telemetry::AttitudeQuaternionHandle handle)
2600
{
2601
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2602
    _camera_attitude_quaternion_subscriptions.unsubscribe(handle);
×
2603
}
×
2604

2605
Telemetry::AttitudeEulerHandle
2606
TelemetryImpl::subscribe_camera_attitude_euler(const Telemetry::AttitudeEulerCallback& callback)
×
2607
{
2608
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2609
    return _camera_attitude_euler_angle_subscriptions.subscribe(callback);
×
2610
}
2611

2612
void TelemetryImpl::unsubscribe_camera_attitude_euler(Telemetry::AttitudeEulerHandle handle)
×
2613
{
2614
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2615
    _camera_attitude_euler_angle_subscriptions.unsubscribe(handle);
×
2616
}
×
2617

2618
Telemetry::VelocityNedHandle
2619
TelemetryImpl::subscribe_velocity_ned(const Telemetry::VelocityNedCallback& callback)
×
2620
{
2621
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2622
    return _velocity_ned_subscriptions.subscribe(callback);
×
2623
}
2624

2625
void TelemetryImpl::unsubscribe_velocity_ned(Telemetry::VelocityNedHandle handle)
×
2626
{
2627
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2628
    _velocity_ned_subscriptions.unsubscribe(handle);
×
2629
}
×
2630

2631
Telemetry::ImuHandle TelemetryImpl::subscribe_imu(const Telemetry::ImuCallback& callback)
×
2632
{
2633
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2634
    return _imu_reading_ned_subscriptions.subscribe(callback);
×
2635
}
2636

2637
void TelemetryImpl::unsubscribe_imu(Telemetry::ImuHandle handle)
×
2638
{
2639
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2640
    return _imu_reading_ned_subscriptions.unsubscribe(handle);
×
2641
}
2642

2643
Telemetry::ScaledImuHandle
2644
TelemetryImpl::subscribe_scaled_imu(const Telemetry::ScaledImuCallback& callback)
×
2645
{
2646
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2647
    return _scaled_imu_subscriptions.subscribe(callback);
×
2648
}
2649

2650
void TelemetryImpl::unsubscribe_scaled_imu(Telemetry::ScaledImuHandle handle)
×
2651
{
2652
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2653
    _scaled_imu_subscriptions.unsubscribe(handle);
×
2654
}
×
2655

2656
Telemetry::RawImuHandle TelemetryImpl::subscribe_raw_imu(const Telemetry::RawImuCallback& callback)
×
2657
{
2658
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2659
    return _raw_imu_subscriptions.subscribe(callback);
×
2660
}
2661

2662
void TelemetryImpl::unsubscribe_raw_imu(Telemetry::RawImuHandle handle)
×
2663
{
2664
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2665
    _raw_imu_subscriptions.unsubscribe(handle);
×
2666
}
×
2667

2668
Telemetry::GpsInfoHandle
2669
TelemetryImpl::subscribe_gps_info(const Telemetry::GpsInfoCallback& callback)
×
2670
{
2671
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2672
    return _gps_info_subscriptions.subscribe(callback);
×
2673
}
2674

2675
void TelemetryImpl::unsubscribe_gps_info(Telemetry::GpsInfoHandle handle)
×
2676
{
2677
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2678
    _gps_info_subscriptions.unsubscribe(handle);
×
2679
}
×
2680

2681
Telemetry::RawGpsHandle TelemetryImpl::subscribe_raw_gps(const Telemetry::RawGpsCallback& callback)
×
2682
{
2683
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2684
    return _raw_gps_subscriptions.subscribe(callback);
×
2685
}
2686

2687
void TelemetryImpl::unsubscribe_raw_gps(Telemetry::RawGpsHandle handle)
×
2688
{
2689
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2690
    _raw_gps_subscriptions.unsubscribe(handle);
×
2691
}
×
2692

2693
Telemetry::BatteryHandle
2694
TelemetryImpl::subscribe_battery(const Telemetry::BatteryCallback& callback)
×
2695
{
2696
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2697
    return _battery_subscriptions.subscribe(callback);
×
2698
}
2699

2700
void TelemetryImpl::unsubscribe_battery(Telemetry::BatteryHandle handle)
×
2701
{
2702
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2703
    _battery_subscriptions.unsubscribe(handle);
×
2704
}
×
2705

2706
Telemetry::FlightModeHandle
2707
TelemetryImpl::subscribe_flight_mode(const Telemetry::FlightModeCallback& callback)
×
2708
{
2709
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2710
    return _flight_mode_subscriptions.subscribe(callback);
×
2711
}
2712

2713
void TelemetryImpl::unsubscribe_flight_mode(Telemetry::FlightModeHandle handle)
×
2714
{
2715
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2716
    _flight_mode_subscriptions.unsubscribe(handle);
×
2717
}
×
2718

2719
Telemetry::HealthHandle TelemetryImpl::subscribe_health(const Telemetry::HealthCallback& callback)
×
2720
{
2721
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2722
    return _health_subscriptions.subscribe(callback);
×
2723
}
2724

2725
void TelemetryImpl::unsubscribe_health(Telemetry::HealthHandle handle)
×
2726
{
2727
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2728
    _health_subscriptions.unsubscribe(handle);
×
2729
}
×
2730

2731
Telemetry::HealthAllOkHandle
2732
TelemetryImpl::subscribe_health_all_ok(const Telemetry::HealthAllOkCallback& callback)
×
2733
{
2734
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2735
    return _health_all_ok_subscriptions.subscribe(callback);
×
2736
}
2737

2738
void TelemetryImpl::unsubscribe_health_all_ok(Telemetry::HealthAllOkHandle handle)
×
2739
{
2740
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2741
    _health_all_ok_subscriptions.unsubscribe(handle);
×
2742
}
×
2743

2744
Telemetry::VtolStateHandle
2745
TelemetryImpl::subscribe_vtol_state(const Telemetry::VtolStateCallback& callback)
×
2746
{
2747
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2748
    return _vtol_state_subscriptions.subscribe(callback);
×
2749
}
2750

2751
void TelemetryImpl::unsubscribe_vtol_state(Telemetry::VtolStateHandle handle)
×
2752
{
2753
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2754
    _vtol_state_subscriptions.unsubscribe(handle);
×
2755
}
×
2756

2757
Telemetry::LandedStateHandle
2758
TelemetryImpl::subscribe_landed_state(const Telemetry::LandedStateCallback& callback)
×
2759
{
2760
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2761
    return _landed_state_subscriptions.subscribe(callback);
×
2762
}
2763

2764
void TelemetryImpl::unsubscribe_landed_state(Telemetry::LandedStateHandle handle)
×
2765
{
2766
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2767
    _landed_state_subscriptions.unsubscribe(handle);
×
2768
}
×
2769

2770
Telemetry::RcStatusHandle
2771
TelemetryImpl::subscribe_rc_status(const Telemetry::RcStatusCallback& callback)
×
2772
{
2773
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2774
    return _rc_status_subscriptions.subscribe(callback);
×
2775
}
2776

2777
void TelemetryImpl::unsubscribe_rc_status(Telemetry::RcStatusHandle handle)
×
2778
{
2779
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2780
    _rc_status_subscriptions.unsubscribe(handle);
×
2781
}
×
2782

2783
Telemetry::UnixEpochTimeHandle
2784
TelemetryImpl::subscribe_unix_epoch_time(const Telemetry::UnixEpochTimeCallback& callback)
×
2785
{
2786
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2787
    return _unix_epoch_time_subscriptions.subscribe(callback);
×
2788
}
2789

2790
void TelemetryImpl::unsubscribe_unix_epoch_time(Telemetry::UnixEpochTimeHandle handle)
×
2791
{
2792
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2793
    _unix_epoch_time_subscriptions.unsubscribe(handle);
×
2794
}
×
2795

2796
Telemetry::ActuatorControlTargetHandle TelemetryImpl::subscribe_actuator_control_target(
×
2797
    const Telemetry::ActuatorControlTargetCallback& callback)
2798
{
2799
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2800
    return _actuator_control_target_subscriptions.subscribe(callback);
×
2801
}
2802

2803
void TelemetryImpl::unsubscribe_actuator_control_target(
×
2804
    Telemetry::ActuatorControlTargetHandle handle)
2805
{
2806
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2807
    _actuator_control_target_subscriptions.unsubscribe(handle);
×
2808
}
×
2809

2810
Telemetry::ActuatorOutputStatusHandle TelemetryImpl::subscribe_actuator_output_status(
×
2811
    const Telemetry::ActuatorOutputStatusCallback& callback)
2812
{
2813
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2814
    return _actuator_output_status_subscriptions.subscribe(callback);
×
2815
}
2816

2817
void TelemetryImpl::unsubscribe_actuator_output_status(Telemetry::ActuatorOutputStatusHandle handle)
×
2818
{
2819
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2820
    _actuator_output_status_subscriptions.unsubscribe(handle);
×
2821
}
×
2822

2823
Telemetry::OdometryHandle
2824
TelemetryImpl::subscribe_odometry(const Telemetry::OdometryCallback& callback)
×
2825
{
2826
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2827
    return _odometry_subscriptions.subscribe(callback);
×
2828
}
2829

2830
void TelemetryImpl::unsubscribe_odometry(Telemetry::OdometryHandle handle)
×
2831
{
2832
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2833
    _odometry_subscriptions.unsubscribe(handle);
×
2834
}
×
2835

2836
Telemetry::DistanceSensorHandle
2837
TelemetryImpl::subscribe_distance_sensor(const Telemetry::DistanceSensorCallback& callback)
×
2838
{
2839
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2840
    return _distance_sensor_subscriptions.subscribe(callback);
×
2841
}
2842

2843
void TelemetryImpl::unsubscribe_distance_sensor(Telemetry::DistanceSensorHandle handle)
×
2844
{
2845
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2846
    _distance_sensor_subscriptions.unsubscribe(handle);
×
2847
}
×
2848

2849
Telemetry::ScaledPressureHandle
2850
TelemetryImpl::subscribe_scaled_pressure(const Telemetry::ScaledPressureCallback& callback)
×
2851
{
2852
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2853
    return _scaled_pressure_subscriptions.subscribe(callback);
×
2854
}
2855

2856
void TelemetryImpl::unsubscribe_scaled_pressure(Telemetry::ScaledPressureHandle handle)
×
2857
{
2858
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2859
    _scaled_pressure_subscriptions.unsubscribe(handle);
×
2860
}
×
2861

2862
Telemetry::HeadingHandle
2863
TelemetryImpl::subscribe_heading(const Telemetry::HeadingCallback& callback)
×
2864
{
2865
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2866
    return _heading_subscriptions.subscribe(callback);
×
2867
}
2868

2869
void TelemetryImpl::unsubscribe_heading(Telemetry::HeadingHandle handle)
×
2870
{
2871
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2872
    _heading_subscriptions.unsubscribe(handle);
×
2873
}
×
2874

2875
Telemetry::AltitudeHandle
2876
TelemetryImpl::subscribe_altitude(const Telemetry::AltitudeCallback& callback)
×
2877
{
2878
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2879
    return _altitude_subscriptions.subscribe(callback);
×
2880
}
2881

2882
void TelemetryImpl::unsubscribe_altitude(Telemetry::AltitudeHandle handle)
×
2883
{
2884
    std::lock_guard<std::mutex> lock(_subscription_mutex);
×
2885
    _altitude_subscriptions.unsubscribe(handle);
×
2886
}
×
2887

2888
void TelemetryImpl::request_home_position_async()
1✔
2889
{
2890
    MavlinkCommandSender::CommandLong command_request_message{};
1✔
2891
    command_request_message.command = MAV_CMD_REQUEST_MESSAGE;
1✔
2892
    command_request_message.target_component_id = MAV_COMP_ID_AUTOPILOT1;
1✔
2893
    command_request_message.params.maybe_param1 = static_cast<float>(MAVLINK_MSG_ID_HOME_POSITION);
1✔
2894
    _system_impl->send_command_async(command_request_message, nullptr);
1✔
2895
}
1✔
2896

2897
void TelemetryImpl::get_gps_global_origin_async(
×
2898
    const Telemetry::GetGpsGlobalOriginCallback callback)
2899
{
2900
    _system_impl->request_message().request(
×
2901
        MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN,
2902
        MAV_COMP_ID_AUTOPILOT1,
2903
        [this, callback](MavlinkCommandSender::Result result, const mavlink_message_t& message) {
×
2904
            if (result == MavlinkCommandSender::Result::Success) {
×
2905
                mavlink_gps_global_origin_t mavlink_gps_global_origin;
×
2906
                mavlink_msg_gps_global_origin_decode(&message, &mavlink_gps_global_origin);
×
2907

2908
                Telemetry::GpsGlobalOrigin gps_global_origin;
×
2909
                gps_global_origin.latitude_deg = mavlink_gps_global_origin.latitude * 1e-7;
×
2910
                gps_global_origin.longitude_deg = mavlink_gps_global_origin.longitude * 1e-7;
×
2911
                gps_global_origin.altitude_m = mavlink_gps_global_origin.altitude * 1e-3f;
×
2912
                _system_impl->call_user_callback([callback, gps_global_origin]() {
×
2913
                    callback(Telemetry::Result::Success, gps_global_origin);
2914
                });
2915

2916
            } else {
2917
                _system_impl->call_user_callback([callback, result]() {
×
2918
                    callback(telemetry_result_from_command_result(result), {});
2919
                });
2920
            }
2921
        });
×
2922
}
×
2923

2924
std::pair<Telemetry::Result, Telemetry::GpsGlobalOrigin> TelemetryImpl::get_gps_global_origin()
×
2925
{
2926
    auto prom = std::promise<std::pair<Telemetry::Result, Telemetry::GpsGlobalOrigin>>();
×
2927
    auto fut = prom.get_future();
×
2928

2929
    get_gps_global_origin_async(
×
2930
        [&prom](Telemetry::Result result, Telemetry::GpsGlobalOrigin gps_global_origin) {
×
2931
            prom.set_value(std::make_pair(result, gps_global_origin));
×
2932
        });
×
2933
    return fut.get();
×
2934
}
2935

2936
void TelemetryImpl::check_calibration()
1✔
2937
{
2938
    {
2939
        std::lock_guard<std::mutex> lock(_health_mutex);
1✔
2940
        if ((_has_received_gyro_calibration && _has_received_accel_calibration &&
1✔
2941
             _has_received_mag_calibration) ||
2✔
2942
            _hitl_enabled) {
1✔
2943
            _system_impl->remove_call_every(_calibration_cookie);
×
2944
            return;
×
2945
        }
2946
    }
2947
    if (_system_impl->has_autopilot()) {
1✔
2948
        if (_system_impl->autopilot() == Autopilot::ArduPilot) {
1✔
2949
            // We need to ask for the home position from ArduPilot
2950
            request_home_position_async();
×
2951

2952
            // ArduPilot calibration sets the offsets,
2953
            // if any offset is 0 the calibration is not complete/unhealthy.
2954
            _system_impl->get_param_float_async(
×
2955
                std::string("INS_GYROFFS_X"),
×
2956
                [this](MavlinkParameterClient::Result result, float value) {
×
2957
                    receive_param_cal_gyro_offset_x(result, value);
×
2958
                },
×
2959
                this);
2960

2961
            _system_impl->get_param_float_async(
×
2962
                std::string("INS_GYROFFS_Y"),
×
2963
                [this](MavlinkParameterClient::Result result, float value) {
×
2964
                    receive_param_cal_gyro_offset_y(result, value);
×
2965
                },
×
2966
                this);
2967

2968
            _system_impl->get_param_float_async(
×
2969
                std::string("INS_GYROFFS_Z"),
×
2970
                [this](MavlinkParameterClient::Result result, float value) {
×
2971
                    receive_param_cal_gyro_offset_z(result, value);
×
2972
                },
×
2973
                this);
2974

2975
            _system_impl->get_param_float_async(
×
2976
                std::string("INS_ACCOFFS_X"),
×
2977
                [this](MavlinkParameterClient::Result result, float value) {
×
2978
                    receive_param_cal_accel_offset_x(result, value);
×
2979
                },
×
2980
                this);
2981

2982
            _system_impl->get_param_float_async(
×
2983
                std::string("INS_ACCOFFS_Y"),
×
2984
                [this](MavlinkParameterClient::Result result, float value) {
×
2985
                    receive_param_cal_accel_offset_y(result, value);
×
2986
                },
×
2987
                this);
2988

2989
            _system_impl->get_param_float_async(
×
2990
                std::string("INS_ACCOFFS_Z"),
×
2991
                [this](MavlinkParameterClient::Result result, float value) {
×
2992
                    receive_param_cal_accel_offset_z(result, value);
×
2993
                },
×
2994
                this);
2995

2996
            _system_impl->get_param_float_async(
×
2997
                std::string("COMPASS_OFS_X"),
×
2998
                [this](MavlinkParameterClient::Result result, float value) {
×
2999
                    receive_param_cal_mag_offset_x(result, value);
×
3000
                },
×
3001
                this);
3002

3003
            _system_impl->get_param_float_async(
×
3004
                std::string("COMPASS_OFS_Y"),
×
3005
                [this](MavlinkParameterClient::Result result, float value) {
×
3006
                    receive_param_cal_mag_offset_y(result, value);
×
3007
                },
×
3008
                this);
3009

3010
            _system_impl->get_param_float_async(
×
3011
                std::string("COMPASS_OFS_Z"),
×
3012
                [this](MavlinkParameterClient::Result result, float value) {
×
3013
                    receive_param_cal_mag_offset_z(result, value);
×
3014
                },
×
3015
                this);
3016

3017
        } else {
3018
            _system_impl->get_param_int_async(
3✔
3019
                std::string("CAL_GYRO0_ID"),
2✔
3020
                [this](MavlinkParameterClient::Result result, int32_t value) {
×
3021
                    receive_param_cal_gyro(result, value);
×
3022
                },
×
3023
                this);
3024

3025
            _system_impl->get_param_int_async(
3✔
3026
                std::string("CAL_ACC0_ID"),
2✔
3027
                [this](MavlinkParameterClient::Result result, int32_t value) {
×
3028
                    receive_param_cal_accel(result, value);
×
3029
                },
×
3030
                this);
3031

3032
            _system_impl->get_param_int_async(
3✔
3033
                std::string("CAL_MAG0_ID"),
2✔
3034
                [this](MavlinkParameterClient::Result result, int32_t value) {
×
3035
                    receive_param_cal_mag(result, value);
×
3036
                },
×
3037
                this);
3038

3039
            _system_impl->get_param_int_async(
3✔
3040
                std::string("SYS_HITL"),
2✔
3041
                [this](MavlinkParameterClient::Result result, int32_t value) {
×
3042
                    receive_param_hitl(result, value);
×
3043
                },
×
3044
                this);
3045
        }
3046
    }
3047
}
3048

3049
void TelemetryImpl::process_parameter_update(const std::string& name)
×
3050
{
3051
    if (_system_impl->autopilot() == Autopilot::ArduPilot) {
×
3052
        if (name.compare("INS_GYROFFS_X") == 0) {
×
3053
            _system_impl->get_param_float_async(
×
3054
                std::string("INS_GYROFFS_X"),
×
3055
                [this](MavlinkParameterClient::Result result, float value) {
×
3056
                    receive_param_cal_gyro_offset_x(result, value);
×
3057
                },
×
3058
                this);
3059
        } else if (name.compare("INS_GYROFFS_Y") == 0) {
×
3060
            _system_impl->get_param_float_async(
×
3061
                std::string("INS_GYROFFS_Y"),
×
3062
                [this](MavlinkParameterClient::Result result, float value) {
×
3063
                    receive_param_cal_gyro_offset_y(result, value);
×
3064
                },
×
3065
                this);
3066
        } else if (name.compare("INS_GYROFFS_Z") == 0) {
×
3067
            _system_impl->get_param_float_async(
×
3068
                std::string("INS_GYROFFS_Z"),
×
3069
                [this](MavlinkParameterClient::Result result, float value) {
×
3070
                    receive_param_cal_gyro_offset_z(result, value);
×
3071
                },
×
3072
                this);
3073
        } else if (name.compare("INS_ACCOFFS_X") == 0) {
×
3074
            _system_impl->get_param_float_async(
×
3075
                std::string("INS_ACCOFFS_X"),
×
3076
                [this](MavlinkParameterClient::Result result, float value) {
×
3077
                    receive_param_cal_accel_offset_x(result, value);
×
3078
                },
×
3079
                this);
3080
        } else if (name.compare("INS_ACCOFFS_Y") == 0) {
×
3081
            _system_impl->get_param_float_async(
×
3082
                std::string("INS_ACCOFFS_Y"),
×
3083
                [this](MavlinkParameterClient::Result result, float value) {
×
3084
                    receive_param_cal_accel_offset_y(result, value);
×
3085
                },
×
3086
                this);
3087
        } else if (name.compare("INS_ACCOFFS_Z") == 0) {
×
3088
            _system_impl->get_param_float_async(
×
3089
                std::string("INS_ACCOFFS_Z"),
×
3090
                [this](MavlinkParameterClient::Result result, float value) {
×
3091
                    receive_param_cal_accel_offset_z(result, value);
×
3092
                },
×
3093
                this);
3094
        } else if (name.compare("COMPASS_OFS_X") == 0) {
×
3095
            _system_impl->get_param_float_async(
×
3096
                std::string("COMPASS_OFS_X"),
×
3097
                [this](MavlinkParameterClient::Result result, float value) {
×
3098
                    receive_param_cal_mag_offset_x(result, value);
×
3099
                },
×
3100
                this);
3101
        } else if (name.compare("COMPASS_OFS_Y") == 0) {
×
3102
            _system_impl->get_param_float_async(
×
3103
                std::string("COMPASS_OFS_Y"),
×
3104
                [this](MavlinkParameterClient::Result result, float value) {
×
3105
                    receive_param_cal_mag_offset_y(result, value);
×
3106
                },
×
3107
                this);
3108
        } else if (name.compare("COMPASS_OFS_Z") == 0) {
×
3109
            _system_impl->get_param_float_async(
×
3110
                std::string("COMPASS_OFS_Z"),
×
3111
                [this](MavlinkParameterClient::Result result, float value) {
×
3112
                    receive_param_cal_mag_offset_z(result, value);
×
3113
                },
×
3114
                this);
3115
        }
3116
    } else {
3117
        if (name.compare("CAL_GYRO0_ID") == 0) {
×
3118
            _system_impl->get_param_int_async(
×
3119
                std::string("CAL_GYRO0_ID"),
×
3120
                [this](MavlinkParameterClient::Result result, int32_t value) {
×
3121
                    receive_param_cal_gyro(result, value);
×
3122
                },
×
3123
                this);
3124

3125
        } else if (name.compare("CAL_ACC0_ID") == 0) {
×
3126
            _system_impl->get_param_int_async(
×
3127
                std::string("CAL_ACC0_ID"),
×
3128
                [this](MavlinkParameterClient::Result result, int32_t value) {
×
3129
                    receive_param_cal_accel(result, value);
×
3130
                },
×
3131
                this);
3132
        } else if (name.compare("CAL_MAG0_ID") == 0) {
×
3133
            _system_impl->get_param_int_async(
×
3134
                std::string("CAL_MAG0_ID"),
×
3135
                [this](MavlinkParameterClient::Result result, int32_t value) {
×
3136
                    receive_param_cal_mag(result, value);
×
3137
                },
×
3138
                this);
3139

3140
        } else if (name.compare("SYS_HITL") == 0) {
×
3141
            _system_impl->get_param_int_async(
×
3142
                std::string("SYS_HITL"),
×
3143
                [this](MavlinkParameterClient::Result result, int32_t value) {
×
3144
                    receive_param_hitl(result, value);
×
3145
                },
×
3146
                this);
3147
        }
3148
    }
3149
}
×
3150

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

© 2025 Coveralls, Inc