-
Notifications
You must be signed in to change notification settings - Fork 15.3k
Expand file tree
/
Copy pathlogged_topics.cpp
More file actions
595 lines (514 loc) · 19.2 KB
/
logged_topics.cpp
File metadata and controls
595 lines (514 loc) · 19.2 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
/****************************************************************************
*
* Copyright (c) 2019-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "logged_topics.h"
#include "messages.h"
#include <parameters/param.h>
#include <px4_platform_common/log.h>
#include <px4_platform_common/px4_config.h>
#include <uORB/topics/uORBTopics.hpp>
#include <string.h>
using namespace px4::logger;
void LoggedTopics::add_default_topics()
{
add_topic("action_request");
add_topic("actuator_armed");
add_optional_topic("actuator_controls_status_0", 300);
add_topic("airspeed", 1000);
add_optional_topic("airspeed_validated", 200);
add_optional_topic("autotune_attitude_control_status", 100);
add_topic_multi("battery_info", 5000, 2);
add_optional_topic("camera_capture");
add_optional_topic("camera_trigger");
add_topic("cellular_status", 200);
add_topic("commander_state");
add_topic("config_overrides");
add_topic("cpuload");
add_topic("distance_sensor_mode_change_request");
add_optional_topic("external_ins_attitude");
add_optional_topic("external_ins_global_position");
add_optional_topic("external_ins_local_position");
// add_optional_topic("esc_status", 250);
add_topic("esc_status");
add_topic("failure_detector_status", 100);
add_topic("failsafe_flags");
add_optional_topic("follow_target", 500);
add_optional_topic("follow_target_estimator", 200);
add_optional_topic("follow_target_status", 400);
add_optional_topic("flaps_setpoint", 1000);
add_optional_topic("flight_phase_estimation", 1000);
add_optional_topic("fuel_tank_status", 10);
add_topic("gimbal_manager_set_attitude", 500);
add_optional_topic("generator_status");
add_optional_topic("gps_dump");
add_optional_topic("gimbal_controls", 200);
add_optional_topic("gripper");
add_optional_topic("heater_status");
add_topic("home_position");
add_topic("hover_thrust_estimate", 100);
add_topic("input_rc", 500);
add_optional_topic("internal_combustion_engine_control", 10);
add_optional_topic("internal_combustion_engine_status", 10);
add_optional_topic("iridiumsbd_status", 1000);
add_optional_topic("irlock_report", 1000);
add_optional_topic("landing_gear", 200);
add_optional_topic("landing_gear_wheel", 100);
add_optional_topic("landing_target_pose", 1000);
add_optional_topic("launch_detection_status", 200);
add_optional_topic("magnetometer_bias_estimate", 200);
add_topic("manual_control_setpoint", 200);
add_topic("manual_control_switches");
add_topic("mission_result");
add_topic("navigator_mission_item");
add_topic("navigator_status");
add_topic("offboard_control_mode", 100);
add_topic("onboard_computer_status", 10);
add_topic("parameter_update");
add_topic("position_controller_status", 500);
add_topic("position_controller_landing_status", 100);
add_optional_topic("pure_pursuit_status", 100);
add_topic("goto_setpoint", 200);
add_topic("position_setpoint_triplet", 200);
add_optional_topic("px4io_status");
add_topic("radio_status");
add_optional_topic("rover_attitude_setpoint", 100);
add_optional_topic("rover_attitude_status", 100);
add_optional_topic("rover_position_setpoint", 100);
add_optional_topic("rover_rate_setpoint", 100);
add_optional_topic("rover_rate_status", 100);
add_optional_topic("rover_steering_setpoint", 100);
add_optional_topic("rover_throttle_setpoint", 100);
add_optional_topic("rover_velocity_setpoint", 100);
add_optional_topic("rover_velocity_status", 100);
add_topic("rtl_time_estimate", 1000);
add_topic("rtl_status", 2000);
add_optional_topic("sensor_airflow", 100);
add_topic("sensor_combined");
add_optional_topic("sensor_correction");
add_optional_topic("sensor_gyro_fft", 50);
add_topic("sensor_selection");
add_topic("sensors_status_imu", 200);
add_optional_topic("spoilers_setpoint", 1000);
add_topic("system_power", 500);
add_optional_topic("takeoff_status", 1000);
add_optional_topic("tecs_status", 200);
add_optional_topic("tiltrotor_extra_controls", 100);
add_topic("trajectory_setpoint", 200);
add_topic("transponder_report");
add_topic("vehicle_acceleration", 50);
add_topic("vehicle_air_data", 200);
add_topic("vehicle_angular_velocity", 20);
add_topic("vehicle_attitude", 50);
add_topic("vehicle_attitude_setpoint", 50);
add_topic("vehicle_command");
add_topic("vehicle_command_ack");
add_topic("vehicle_constraints", 1000);
add_topic("vehicle_control_mode");
add_topic("vehicle_global_position", 200);
add_topic("vehicle_gps_position", 100);
add_topic("vehicle_land_detected");
add_topic("vehicle_local_position", 100);
add_topic("vehicle_local_position_setpoint", 100);
add_topic("vehicle_magnetometer", 200);
add_topic("vehicle_rates_setpoint", 20);
add_topic("vehicle_roi", 1000);
add_topic("vehicle_status");
add_optional_topic("vtol_vehicle_status", 200);
add_topic("wind", 1000);
add_topic("fixed_wing_lateral_setpoint");
add_topic("fixed_wing_longitudinal_setpoint");
add_topic("longitudinal_control_configuration");
add_topic("lateral_control_configuration");
add_optional_topic("fixed_wing_lateral_guidance_status", 100);
add_optional_topic("fixed_wing_lateral_status", 100);
add_optional_topic("fixed_wing_runway_control", 100);
// multi topics
add_optional_topic_multi("actuator_outputs", 100, 3);
add_optional_topic_multi("airspeed_wind", 1000, 4);
add_optional_topic_multi("control_allocator_status", 200, 2);
add_optional_topic_multi("rate_ctrl_status", 200, 2);
add_optional_topic_multi("sensor_hygrometer", 500, 4);
add_optional_topic_multi("rpm", 200);
add_topic_multi("timesync_status", 1000, 3);
add_optional_topic_multi("telemetry_status", 1000, 4);
// EKF multi topics
{
// optionally log all estimator* topics at minimal rate
const uint16_t kEKFVerboseIntervalMilliseconds = 500; // 2 Hz
const struct orb_metadata *const *topic_list = orb_get_topics();
for (size_t i = 0; i < orb_topics_count(); i++) {
if (strncmp(topic_list[i]->o_name, "estimator", 9) == 0) {
add_optional_topic_multi(topic_list[i]->o_name, kEKFVerboseIntervalMilliseconds);
}
}
}
// important EKF topics (higher rate)
add_optional_topic("estimator_selector_status", 10);
add_optional_topic_multi("estimator_event_flags", 10);
add_optional_topic_multi("estimator_optical_flow_vel", 200);
add_optional_topic_multi("estimator_sensor_bias", 1000);
add_optional_topic_multi("estimator_status", 200);
add_optional_topic_multi("estimator_status_flags", 10);
add_optional_topic_multi("yaw_estimator_status", 1000);
// log all raw sensors at minimal rate (at least 1 Hz)
add_topic_multi("battery_status", 200, 2);
add_topic_multi("differential_pressure", 1000, 2);
add_topic_multi("distance_sensor", 1000, 2);
add_optional_topic_multi("sensor_accel", 1000, 4);
add_optional_topic_multi("sensor_baro", 1000, 4);
add_topic_multi("sensor_gps", 1000, 2);
add_topic_multi("sensor_gnss_relative", 1000, 1);
add_optional_topic_multi("sensor_gyro", 1000, 4);
add_topic_multi("sensor_mag", 1000, 4);
add_topic_multi("sensor_optical_flow", 1000, 2);
add_topic_multi("vehicle_imu", 500, 4);
add_topic_multi("vehicle_imu_status", 1000, 4);
add_optional_topic_multi("vehicle_magnetometer", 500, 4);
add_topic("vehicle_optical_flow", 500);
add_topic("aux_global_position", 500);
//add_optional_topic("vehicle_optical_flow_vel", 100);
add_optional_topic("pps_capture");
// additional control allocation logging
add_topic("actuator_motors", 100);
add_topic("actuator_servos", 100);
add_topic_multi("vehicle_thrust_setpoint", 20, 2);
add_topic_multi("vehicle_torque_setpoint", 20, 2);
add_topic("indi_adaptation_status", 100);
// SYS_HITL: default ground truth logging for simulation
int32_t sys_hitl = 0;
param_get(param_find("SYS_HITL"), &sys_hitl);
if (sys_hitl >= 1) {
add_topic("vehicle_angular_velocity_groundtruth", 10);
add_topic("vehicle_attitude_groundtruth", 10);
add_topic("vehicle_global_position_groundtruth", 100);
add_topic("vehicle_local_position_groundtruth", 20);
}
#ifdef CONFIG_ARCH_BOARD_PX4_SITL
add_topic("fw_virtual_attitude_setpoint");
add_topic("mc_virtual_attitude_setpoint");
add_optional_topic("vehicle_torque_setpoint_virtual_mc");
add_optional_topic("vehicle_torque_setpoint_virtual_fw");
add_optional_topic("vehicle_thrust_setpoint_virtual_mc");
add_optional_topic("vehicle_thrust_setpoint_virtual_fw");
add_topic("time_offset");
add_topic("vehicle_angular_velocity", 10);
add_topic("vehicle_angular_velocity_groundtruth", 10);
add_topic("vehicle_attitude_groundtruth", 10);
add_topic("vehicle_global_position_groundtruth", 100);
add_topic("vehicle_local_position_groundtruth", 20);
// EKF replay
{
// optionally log all estimator* topics at minimal rate
const uint16_t kEKFVerboseIntervalMilliseconds = 10; // 100 Hz
const struct orb_metadata *const *topic_list = orb_get_topics();
for (size_t i = 0; i < orb_topics_count(); i++) {
if (strncmp(topic_list[i]->o_name, "estimator", 9) == 0) {
add_optional_topic_multi(topic_list[i]->o_name, kEKFVerboseIntervalMilliseconds);
}
}
}
add_topic("vehicle_attitude");
add_topic("vehicle_global_position");
add_topic("vehicle_local_position");
add_topic("wind");
add_optional_topic_multi("yaw_estimator_status");
#endif /* CONFIG_ARCH_BOARD_PX4_SITL */
#ifdef CONFIG_BOARD_UAVCAN_INTERFACES
add_topic_multi("can_interface_status", 100, CONFIG_BOARD_UAVCAN_INTERFACES);
#endif
}
void LoggedTopics::add_high_rate_topics()
{
// maximum rate to analyze fast maneuvers (e.g. for racing)
add_topic("manual_control_setpoint");
add_topic_multi("rate_ctrl_status", 20, 2);
add_topic("sensor_combined");
add_topic("vehicle_angular_velocity");
add_topic("vehicle_attitude");
add_topic("vehicle_attitude_setpoint");
add_topic("vehicle_rates_setpoint");
add_topic("esc_status", 5);
add_topic("actuator_motors");
add_topic("actuator_outputs_debug");
add_topic("actuator_servos");
add_topic_multi("vehicle_thrust_setpoint", 0, 2);
add_topic_multi("vehicle_torque_setpoint", 0, 2);
}
void LoggedTopics::add_debug_topics()
{
add_topic("debug_array");
add_topic("debug_key_value");
add_topic("debug_value");
add_topic("debug_vect");
add_topic_multi("satellite_info", 1000, 2);
add_topic("mag_worker_data");
add_topic("sensor_preflight_mag", 500);
add_topic("actuator_test", 500);
}
void LoggedTopics::add_estimator_replay_topics()
{
// for estimator replay (need to be at full rate)
add_topic("ekf2_timestamps");
// current EKF2 subscriptions
add_topic("airspeed");
add_topic("airspeed_validated");
add_topic("vehicle_optical_flow");
add_topic("sensor_combined");
add_topic("sensor_selection");
add_topic("vehicle_air_data");
add_topic("vehicle_gps_position");
add_topic("vehicle_land_detected");
add_topic("vehicle_magnetometer");
add_topic("vehicle_status");
add_topic("vehicle_visual_odometry");
add_topic("aux_global_position");
add_topic_multi("distance_sensor");
}
void LoggedTopics::add_thermal_calibration_topics()
{
add_topic_multi("sensor_accel", 100, 4);
add_topic_multi("sensor_baro", 100, 4);
add_topic_multi("sensor_gyro", 100, 4);
add_topic_multi("sensor_mag", 100, 4);
}
void LoggedTopics::add_sensor_comparison_topics()
{
add_topic_multi("sensor_accel", 100, 4);
add_topic_multi("sensor_baro", 100, 4);
add_topic_multi("sensor_gyro", 100, 4);
add_topic_multi("sensor_mag", 100, 4);
}
void LoggedTopics::add_vision_and_avoidance_topics()
{
add_topic("collision_constraints");
add_topic_multi("distance_sensor");
add_topic("obstacle_distance_fused");
add_topic("obstacle_distance");
add_topic("vehicle_mocap_odometry", 30);
add_topic("vehicle_visual_odometry", 30);
}
void LoggedTopics::add_raw_imu_gyro_fifo()
{
add_topic("sensor_gyro_fifo");
}
void LoggedTopics::add_raw_imu_accel_fifo()
{
add_topic("sensor_accel_fifo");
}
void LoggedTopics::add_system_identification_topics()
{
// for system id need to log imu and controls at full rate
add_topic("sensor_combined");
add_topic("vehicle_angular_velocity");
add_topic("vehicle_torque_setpoint");
add_topic("vehicle_acceleration");
add_topic("actuator_motors");
}
void LoggedTopics::add_high_rate_sensors_topics()
{
add_topic_multi("distance_sensor", 0, 4);
add_topic_multi("sensor_optical_flow", 0, 2);
add_topic_multi("sensor_gps", 0, 4);
add_topic_multi("sensor_mag", 0, 4);
}
void LoggedTopics::add_mavlink_tunnel()
{
add_topic("mavlink_tunnel");
}
int LoggedTopics::add_topics_from_file(const char *fname)
{
int ntopics = 0;
/* open the topic list file */
FILE *fp = fopen(fname, "r");
if (fp == nullptr) {
return -1;
}
/* call add_topic for each topic line in the file */
for (;;) {
/* get a line, bail on error/EOF */
char line[80];
line[0] = '\0';
if (fgets(line, sizeof(line), fp) == nullptr) {
break;
}
/* skip comment lines */
if ((strlen(line) < 2) || (line[0] == '#')) {
continue;
}
// read line with format: <topic_name>[ <interval>[ <instance>]]
char topic_name[80];
uint32_t interval_ms = 0;
uint32_t instance = 0;
int nfields = sscanf(line, "%s %" PRIu32 " %" PRIu32, topic_name, &interval_ms, &instance);
if (nfields > 0) {
int name_len = strlen(topic_name);
if (name_len > 0 && topic_name[name_len - 1] == ',') {
topic_name[name_len - 1] = '\0';
}
/* add topic with specified interval_ms */
if ((nfields > 2 && add_topic(topic_name, interval_ms, instance))
|| add_topic_multi(topic_name, interval_ms)) {
ntopics++;
} else {
PX4_ERR("Failed to add topic %s", topic_name);
}
}
}
fclose(fp);
return ntopics;
}
void LoggedTopics::initialize_mission_topics(MissionLogType mission_log_type)
{
if (mission_log_type == MissionLogType::Complete) {
add_mission_topic("camera_capture");
add_mission_topic("mission_result");
add_mission_topic("vehicle_global_position", 1000);
add_mission_topic("vehicle_status", 1000);
} else if (mission_log_type == MissionLogType::Geotagging) {
add_mission_topic("camera_capture");
}
}
void LoggedTopics::add_mission_topic(const char *name, uint16_t interval_ms)
{
if (add_topic(name, interval_ms)) {
++_num_mission_subs;
}
}
bool LoggedTopics::add_topic(const orb_metadata *topic, uint16_t interval_ms, uint8_t instance, bool optional)
{
if (_subscriptions.count >= MAX_TOPICS_NUM) {
PX4_WARN("Too many subscriptions, failed to add: %s %" PRIu8, topic->o_name, instance);
return false;
}
if (optional && orb_exists(topic, instance) != 0) {
PX4_DEBUG("Not adding non-existing optional topic %s %i", topic->o_name, instance);
if (instance == 0 && _subscriptions.num_excluded_optional_topic_ids < MAX_EXCLUDED_OPTIONAL_TOPICS_NUM) {
_subscriptions.excluded_optional_topic_ids[_subscriptions.num_excluded_optional_topic_ids++] = topic->o_id;
}
return false;
}
RequestedSubscription &sub = _subscriptions.sub[_subscriptions.count++];
sub.interval_ms = interval_ms;
sub.instance = instance;
sub.id = static_cast<ORB_ID>(topic->o_id);
return true;
}
bool LoggedTopics::add_topic(const char *name, uint16_t interval_ms, uint8_t instance, bool optional)
{
interval_ms /= _rate_factor;
const orb_metadata *const *topics = orb_get_topics();
bool success = false;
for (size_t i = 0; i < orb_topics_count(); i++) {
if (strcmp(name, topics[i]->o_name) == 0) {
bool already_added = false;
// check if already added: if so, only update the interval
for (int j = 0; j < _subscriptions.count; ++j) {
if (_subscriptions.sub[j].id == static_cast<ORB_ID>(topics[i]->o_id) &&
_subscriptions.sub[j].instance == instance) {
PX4_DEBUG("logging topic %s(%" PRIu8 "), interval: %" PRIu16 ", already added, only setting interval",
topics[i]->o_name, instance, interval_ms);
_subscriptions.sub[j].interval_ms = interval_ms;
success = true;
already_added = true;
break;
}
}
if (!already_added) {
success = add_topic(topics[i], interval_ms, instance, optional);
if (success) {
PX4_DEBUG("logging topic: %s(%" PRIu8 "), interval: %" PRIu16, topics[i]->o_name, instance, interval_ms);
}
break;
}
}
}
return success;
}
bool LoggedTopics::add_topic_multi(const char *name, uint16_t interval_ms, uint8_t max_num_instances, bool optional)
{
// add all possible instances
for (uint8_t instance = 0; instance < max_num_instances; instance++) {
add_topic(name, interval_ms, instance, optional);
}
return true;
}
bool LoggedTopics::initialize_logged_topics(SDLogProfileMask profile)
{
int ntopics = add_topics_from_file(PX4_STORAGEDIR "/etc/logging/logger_topics.txt");
if (ntopics > 0) {
PX4_INFO("logging %d topics from logger_topics.txt", ntopics);
} else {
initialize_configured_topics(profile);
}
return _subscriptions.count > 0;
}
void LoggedTopics::initialize_configured_topics(SDLogProfileMask profile)
{
// load appropriate topics for profile
// the order matters: if several profiles add the same topic, the logging rate of the last one will be used
if (profile & SDLogProfileMask::DEFAULT) {
add_default_topics();
}
if (profile & SDLogProfileMask::ESTIMATOR_REPLAY) {
add_estimator_replay_topics();
}
if (profile & SDLogProfileMask::THERMAL_CALIBRATION) {
add_thermal_calibration_topics();
}
if (profile & SDLogProfileMask::SYSTEM_IDENTIFICATION) {
add_system_identification_topics();
}
if (profile & SDLogProfileMask::HIGH_RATE) {
add_high_rate_topics();
}
if (profile & SDLogProfileMask::DEBUG_TOPICS) {
add_debug_topics();
}
if (profile & SDLogProfileMask::SENSOR_COMPARISON) {
add_sensor_comparison_topics();
}
if (profile & SDLogProfileMask::VISION_AND_AVOIDANCE) {
add_vision_and_avoidance_topics();
}
if (profile & SDLogProfileMask::RAW_IMU_GYRO_FIFO) {
add_raw_imu_gyro_fifo();
}
if (profile & SDLogProfileMask::RAW_IMU_ACCEL_FIFO) {
add_raw_imu_accel_fifo();
}
if (profile & SDLogProfileMask::MAVLINK_TUNNEL) {
add_mavlink_tunnel();
}
if (profile & SDLogProfileMask::HIGH_RATE_SENSORS) {
add_high_rate_sensors_topics();
}
}