-
Notifications
You must be signed in to change notification settings - Fork 20.7k
Expand file tree
/
Copy pathAP_DDS_Client.cpp
More file actions
1935 lines (1721 loc) · 75.1 KB
/
AP_DDS_Client.cpp
File metadata and controls
1935 lines (1721 loc) · 75.1 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
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#include <AP_HAL/AP_HAL_Boards.h>
#include <cstdio>
#include "AP_DDS_config.h"
#if AP_DDS_ENABLED
#include <uxr/client/util/ping.h>
#if AP_DDS_NEEDS_GPS
#include <AP_GPS/AP_GPS.h>
#endif // AP_DDS_NEEDS_GPS
#include <AP_HAL/AP_HAL.h>
#include <RC_Channel/RC_Channel.h>
#include <AP_RTC/AP_RTC.h>
#include <AP_Math/AP_Math.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_AHRS/AP_AHRS.h>
#if AP_DDS_ARM_SERVER_ENABLED
#include <AP_Arming/AP_Arming.h>
# endif // AP_DDS_ARM_SERVER_ENABLED
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_Common/AP_FWVersion.h>
#include <AP_ExternalControl/AP_ExternalControl_config.h>
#if AP_DDS_ARM_SERVER_ENABLED
#include "ardupilot_msgs/srv/ArmMotors.h"
#endif // AP_DDS_ARM_SERVER_ENABLED
#if AP_DDS_MODE_SWITCH_SERVER_ENABLED
#include "ardupilot_msgs/srv/ModeSwitch.h"
#endif // AP_DDS_MODE_SWITCH_SERVER_ENABLED
#if AP_DDS_ARM_CHECK_SERVER_ENABLED
#include "std_srvs/srv/Trigger.h"
#endif // AP_DDS_ARM_CHECK_SERVER_ENABLED
#if AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED
#include "ardupilot_msgs/srv/Takeoff.h"
#endif // AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED
#if AP_DDS_RC_PUB_ENABLED
#include "AP_RSSI/AP_RSSI.h"
#endif // AP_DDS_RC_PUB_ENABLED
#if AP_EXTERNAL_CONTROL_ENABLED
#include "AP_DDS_ExternalControl.h"
#endif // AP_EXTERNAL_CONTROL_ENABLED
#include "AP_DDS_Frames.h"
#include "AP_DDS_Client.h"
#include "AP_DDS_Topic_Table.h"
#include "AP_DDS_Service_Table.h"
#include "AP_DDS_External_Odom.h"
#define STRCPY(D,S) strncpy(D, S, ARRAY_SIZE(D))
// Enable DDS at runtime by default
static constexpr uint8_t ENABLED_BY_DEFAULT = 1;
#if AP_DDS_TIME_PUB_ENABLED
static constexpr uint16_t DELAY_TIME_TOPIC_MS = AP_DDS_DELAY_TIME_TOPIC_MS;
#endif // AP_DDS_TIME_PUB_ENABLED
#if AP_DDS_BATTERY_STATE_PUB_ENABLED
static constexpr uint16_t DELAY_BATTERY_STATE_TOPIC_MS = AP_DDS_DELAY_BATTERY_STATE_TOPIC_MS;
#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED
#if AP_DDS_IMU_PUB_ENABLED
static constexpr uint16_t DELAY_IMU_TOPIC_MS = AP_DDS_DELAY_IMU_TOPIC_MS;
#endif // AP_DDS_IMU_PUB_ENABLED
#if AP_DDS_LOCAL_POSE_PUB_ENABLED
static constexpr uint16_t DELAY_LOCAL_POSE_TOPIC_MS = AP_DDS_DELAY_LOCAL_POSE_TOPIC_MS;
#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED
#if AP_DDS_LOCAL_VEL_PUB_ENABLED
static constexpr uint16_t DELAY_LOCAL_VELOCITY_TOPIC_MS = AP_DDS_DELAY_LOCAL_VELOCITY_TOPIC_MS;
#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED
#if AP_DDS_AIRSPEED_PUB_ENABLED
static constexpr uint16_t DELAY_AIRSPEED_TOPIC_MS = AP_DDS_DELAY_AIRSPEED_TOPIC_MS;
#endif // AP_DDS_AIRSPEED_PUB_ENABLED
#if AP_DDS_RC_PUB_ENABLED
static constexpr uint16_t DELAY_RC_TOPIC_MS = AP_DDS_DELAY_RC_TOPIC_MS;
#endif // AP_DDS_RC_PUB_ENABLED
#if AP_DDS_GEOPOSE_PUB_ENABLED
static constexpr uint16_t DELAY_GEO_POSE_TOPIC_MS = AP_DDS_DELAY_GEO_POSE_TOPIC_MS;
#endif // AP_DDS_GEOPOSE_PUB_ENABLED
#if AP_DDS_GOAL_PUB_ENABLED
static constexpr uint16_t DELAY_GOAL_TOPIC_MS = AP_DDS_DELAY_GOAL_TOPIC_MS ;
#endif // AP_DDS_GOAL_PUB_ENABLED
#if AP_DDS_CLOCK_PUB_ENABLED
static constexpr uint16_t DELAY_CLOCK_TOPIC_MS =AP_DDS_DELAY_CLOCK_TOPIC_MS;
#endif // AP_DDS_CLOCK_PUB_ENABLED
#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
static constexpr uint16_t DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS = AP_DDS_DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS;
#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
static constexpr uint16_t DELAY_PING_MS = 500;
#if AP_DDS_STATUS_PUB_ENABLED
static constexpr uint16_t DELAY_STATUS_TOPIC_MS = AP_DDS_DELAY_STATUS_TOPIC_MS;
#endif // AP_DDS_STATUS_PUB_ENABLED
// Define the subscriber data members, which are static class scope.
// If these are created on the stack in the subscriber,
// the AP_DDS_Client::on_topic frame size is exceeded.
#if AP_DDS_JOY_SUB_ENABLED
sensor_msgs_msg_Joy AP_DDS_Client::rx_joy_topic {};
#endif // AP_DDS_JOY_SUB_ENABLED
#if AP_DDS_DYNAMIC_TF_SUB_ENABLED
tf2_msgs_msg_TFMessage AP_DDS_Client::rx_dynamic_transforms_topic {};
#endif // AP_DDS_DYNAMIC_TF_SUB_ENABLED
#if AP_DDS_VEL_CTRL_ENABLED
geometry_msgs_msg_TwistStamped AP_DDS_Client::rx_velocity_control_topic {};
#endif // AP_DDS_VEL_CTRL_ENABLED
#if AP_DDS_GLOBAL_POS_CTRL_ENABLED
ardupilot_msgs_msg_GlobalPosition AP_DDS_Client::rx_global_position_control_topic {};
#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED
// Define the parameter server data members, which are static class scope.
// If these are created on the stack, then the AP_DDS_Client::on_request
// frame size is exceeded.
#if AP_DDS_PARAMETER_SERVER_ENABLED
rcl_interfaces_srv_SetParameters_Request AP_DDS_Client::set_parameter_request {};
rcl_interfaces_srv_SetParameters_Response AP_DDS_Client::set_parameter_response {};
rcl_interfaces_srv_GetParameters_Request AP_DDS_Client::get_parameters_request {};
rcl_interfaces_srv_GetParameters_Response AP_DDS_Client::get_parameters_response {};
rcl_interfaces_msg_Parameter AP_DDS_Client::param {};
#endif
const AP_Param::GroupInfo AP_DDS_Client::var_info[] {
// @Param: _ENABLE
// @DisplayName: DDS enable
// @Description: Enable DDS subsystem
// @Values: 0:Disabled,1:Enabled
// @RebootRequired: True
// @User: Advanced
AP_GROUPINFO_FLAGS("_ENABLE", 1, AP_DDS_Client, enabled, ENABLED_BY_DEFAULT, AP_PARAM_FLAG_ENABLE),
#if AP_DDS_UDP_ENABLED
// @Param: _UDP_PORT
// @DisplayName: DDS UDP port
// @Description: UDP port number for DDS
// @Range: 1 65535
// @RebootRequired: True
// @User: Standard
AP_GROUPINFO("_UDP_PORT", 2, AP_DDS_Client, udp.port, 2019),
// @Group: _IP
// @Path: ../AP_Networking/AP_Networking_address.cpp
AP_SUBGROUPINFO(udp.ip, "_IP", 3, AP_DDS_Client, AP_Networking_IPV4),
#endif
// @Param: _DOMAIN_ID
// @DisplayName: DDS DOMAIN ID
// @Description: Set the ROS_DOMAIN_ID
// @Range: 0 232
// @RebootRequired: True
// @User: Standard
AP_GROUPINFO("_DOMAIN_ID", 4, AP_DDS_Client, domain_id, 0),
// @Param: _TIMEOUT_MS
// @DisplayName: DDS ping timeout
// @Description: The time in milliseconds the DDS client will wait for a response from the XRCE agent before reattempting.
// @Units: ms
// @Range: 1 10000
// @RebootRequired: True
// @Increment: 1
// @User: Standard
AP_GROUPINFO("_TIMEOUT_MS", 5, AP_DDS_Client, ping_timeout_ms, 1000),
// @Param: _MAX_RETRY
// @DisplayName: DDS ping max attempts
// @Description: The maximum number of times the DDS client will attempt to ping the XRCE agent before exiting. Set to 0 to allow unlimited retries.
// @Range: 0 100
// @RebootRequired: True
// @Increment: 1
// @User: Standard
AP_GROUPINFO("_MAX_RETRY", 6, AP_DDS_Client, ping_max_retry, 10),
// @Param: _USE_NS
// @DisplayName: DDS namespace
// @Description: When enabled, ROS 2 topic and service names include a v<MAV_SYSID> segment
// @Values: 0:Disabled,1:Enabled
// @RebootRequired: True
// @User: Standard
AP_GROUPINFO("_USE_NS", 7, AP_DDS_Client, use_ns, 0),
AP_GROUPEND
};
#if AP_DDS_STATIC_TF_PUB_ENABLED | AP_DDS_LOCAL_POSE_PUB_ENABLED | AP_DDS_GEOPOSE_PUB_ENABLED | AP_DDS_IMU_PUB_ENABLED
static void initialize(geometry_msgs_msg_Quaternion& q)
{
q.x = 0.0;
q.y = 0.0;
q.z = 0.0;
q.w = 1.0;
}
#endif // AP_DDS_STATIC_TF_PUB_ENABLED | AP_DDS_LOCAL_POSE_PUB_ENABLED | AP_DDS_GEOPOSE_PUB_ENABLED | AP_DDS_IMU_PUB_ENABLED
AP_DDS_Client::~AP_DDS_Client()
{
// close transport
if (is_using_serial) {
uxr_close_custom_transport(&serial.transport);
} else {
#if AP_DDS_UDP_ENABLED
uxr_close_custom_transport(&udp.transport);
#endif
}
}
#if AP_DDS_TIME_PUB_ENABLED
void AP_DDS_Client::update_topic(builtin_interfaces_msg_Time& msg)
{
uint64_t utc_usec;
if (!AP::rtc().get_utc_usec(utc_usec)) {
utc_usec = AP_HAL::micros64();
}
msg.sec = utc_usec / 1000000ULL;
msg.nanosec = (utc_usec % 1000000ULL) * 1000UL;
}
#endif // AP_DDS_TIME_PUB_ENABLED
#if AP_DDS_NAVSATFIX_PUB_ENABLED
bool AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t instance)
{
// Add a lambda that takes in navsatfix msg and populates the cov
// Make it constexpr if possible
// https://www.fluentcpp.com/2021/12/13/the-evolutions-of-lambdas-in-c14-c17-and-c20/
// constexpr auto times2 = [] (sensor_msgs_msg_NavSatFix* msg) { return n * 2; };
auto &gps = AP::gps();
WITH_SEMAPHORE(gps.get_semaphore());
if (!gps.is_healthy(instance)) {
msg.status.status = -1; // STATUS_NO_FIX
msg.status.service = 0; // No services supported
msg.position_covariance_type = 0; // COVARIANCE_TYPE_UNKNOWN
return false;
}
// No update is needed
const auto last_fix_time_ms = gps.last_fix_time_ms(instance);
if (last_nav_sat_fix_time_ms[instance] == last_fix_time_ms) {
return false;
} else {
last_nav_sat_fix_time_ms[instance] = last_fix_time_ms;
}
update_topic(msg.header.stamp);
static_assert(GPS_MAX_INSTANCES <= 9, "GPS_MAX_INSTANCES is greater than 9");
hal.util->snprintf(msg.header.frame_id, 2, "%u", instance);
msg.status.service = 0; // SERVICE_GPS
msg.status.status = -1; // STATUS_NO_FIX
//! @todo What about glonass, compass, galileo?
//! This will be properly designed and implemented to spec in #23277
msg.status.service = 1; // SERVICE_GPS
const auto status = gps.status(instance);
switch (status) {
case AP_GPS_FixType::NO_GPS:
case AP_GPS_FixType::NONE:
msg.status.status = -1; // STATUS_NO_FIX
msg.position_covariance_type = 0; // COVARIANCE_TYPE_UNKNOWN
return true;
case AP_GPS_FixType::FIX_2D:
case AP_GPS_FixType::FIX_3D:
msg.status.status = 0; // STATUS_FIX
break;
case AP_GPS_FixType::DGPS:
msg.status.status = 1; // STATUS_SBAS_FIX
break;
case AP_GPS_FixType::RTK_FLOAT:
case AP_GPS_FixType::RTK_FIXED:
msg.status.status = 2; // STATUS_SBAS_FIX
break;
default:
//! @todo Can we not just use an enum class and not worry about this condition?
break;
}
const auto loc = gps.location(instance);
msg.latitude = loc.lat * 1E-7;
msg.longitude = loc.lng * 1E-7;
int32_t alt_cm;
if (!loc.get_alt_cm(Location::AltFrame::ABSOLUTE, alt_cm)) {
// With absolute frame, this condition is unlikely
msg.status.status = -1; // STATUS_NO_FIX
msg.position_covariance_type = 0; // COVARIANCE_TYPE_UNKNOWN
return true;
}
msg.altitude = alt_cm * 0.01;
// ROS allows double precision, ArduPilot exposes float precision today
Matrix3f cov;
msg.position_covariance_type = (uint8_t)gps.position_covariance(instance, cov);
msg.position_covariance[0] = cov[0][0];
msg.position_covariance[1] = cov[0][1];
msg.position_covariance[2] = cov[0][2];
msg.position_covariance[3] = cov[1][0];
msg.position_covariance[4] = cov[1][1];
msg.position_covariance[5] = cov[1][2];
msg.position_covariance[6] = cov[2][0];
msg.position_covariance[7] = cov[2][1];
msg.position_covariance[8] = cov[2][2];
return true;
}
#endif // AP_DDS_NAVSATFIX_PUB_ENABLED
#if AP_DDS_STATIC_TF_PUB_ENABLED
void AP_DDS_Client::populate_static_transforms(tf2_msgs_msg_TFMessage& msg)
{
msg.transforms_size = 0;
auto &gps = AP::gps();
for (uint8_t i = 0; i < GPS_MAX_INSTANCES; i++) {
const auto gps_type = gps.get_type(i);
if (gps_type == AP_GPS::GPS_Type::GPS_TYPE_NONE) {
continue;
}
update_topic(msg.transforms[i].header.stamp);
char gps_frame_id[16];
//! @todo should GPS frame ID's be 0 or 1 indexed in ROS?
hal.util->snprintf(gps_frame_id, sizeof(gps_frame_id), "GPS_%u", i);
STRCPY(msg.transforms[i].header.frame_id, BASE_LINK_FRAME_ID);
STRCPY(msg.transforms[i].child_frame_id, gps_frame_id);
// The body-frame offsets
// X - Forward
// Y - Right
// Z - Down
// https://ardupilot.org/copter/docs/common-sensor-offset-compensation.html#sensor-position-offset-compensation
const auto offset = gps.get_antenna_offset(i);
// In ROS REP 103, it follows this convention
// X - Forward
// Y - Left
// Z - Up
// https://www.ros.org/reps/rep-0103.html#axis-orientation
msg.transforms[i].transform.translation.x = offset[0];
msg.transforms[i].transform.translation.y = -1 * offset[1];
msg.transforms[i].transform.translation.z = -1 * offset[2];
// Ensure rotation is initialized.
initialize(msg.transforms[i].transform.rotation);
msg.transforms_size++;
}
}
#endif // AP_DDS_STATIC_TF_PUB_ENABLED
#if AP_DDS_BATTERY_STATE_PUB_ENABLED
void AP_DDS_Client::update_topic(sensor_msgs_msg_BatteryState& msg, const uint8_t instance)
{
if (instance >= AP_BATT_MONITOR_MAX_INSTANCES) {
return;
}
static_assert(AP_BATT_MONITOR_MAX_INSTANCES <= 99, "AP_BATT_MONITOR_MAX_INSTANCES is greater than 99");
update_topic(msg.header.stamp);
hal.util->snprintf(msg.header.frame_id, 2, "%u", instance);
auto &battery = AP::battery();
if (!battery.healthy(instance)) {
msg.power_supply_status = 3; //POWER_SUPPLY_HEALTH_DEAD
msg.present = false;
return;
}
msg.present = true;
msg.voltage = battery.voltage(instance);
float temperature;
msg.temperature = (battery.get_temperature(temperature, instance)) ? temperature : NAN;
float current;
msg.current = (battery.current_amps(current, instance)) ? -1 * current : NAN;
const float design_capacity = (float)battery.pack_capacity_mah(instance) * 0.001;
msg.design_capacity = design_capacity;
uint8_t percentage;
if (battery.capacity_remaining_pct(percentage, instance)) {
msg.percentage = percentage * 0.01;
msg.charge = (percentage * design_capacity) * 0.01;
} else {
msg.percentage = NAN;
msg.charge = NAN;
}
msg.capacity = NAN;
if (battery.current_amps(current, instance)) {
if (percentage == 100) {
msg.power_supply_status = 4; //POWER_SUPPLY_STATUS_FULL
} else if (is_negative(current)) {
msg.power_supply_status = 1; //POWER_SUPPLY_STATUS_CHARGING
} else if (is_positive(current)) {
msg.power_supply_status = 2; //POWER_SUPPLY_STATUS_DISCHARGING
} else {
msg.power_supply_status = 3; //POWER_SUPPLY_STATUS_NOT_CHARGING
}
} else {
msg.power_supply_status = 0; //POWER_SUPPLY_STATUS_UNKNOWN
}
msg.power_supply_health = (battery.overpower_detected(instance)) ? 4 : 1; //POWER_SUPPLY_HEALTH_OVERVOLTAGE or POWER_SUPPLY_HEALTH_GOOD
msg.power_supply_technology = 0; //POWER_SUPPLY_TECHNOLOGY_UNKNOWN
if (battery.has_cell_voltages(instance)) {
const auto &cells = battery.get_cell_voltages(instance);
const uint8_t ncells_max = MIN(ARRAY_SIZE(msg.cell_voltage), ARRAY_SIZE(cells.cells));
for (uint8_t i=0; i< ncells_max; i++) {
msg.cell_voltage[i] = cells.cells[i] * 0.001;
}
}
}
#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED
#if AP_DDS_LOCAL_POSE_PUB_ENABLED
void AP_DDS_Client::update_topic(geometry_msgs_msg_PoseStamped& msg)
{
update_topic(msg.header.stamp);
STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID);
auto &ahrs = AP::ahrs();
WITH_SEMAPHORE(ahrs.get_semaphore());
// ROS REP 103 uses the ENU convention:
// X - East
// Y - North
// Z - Up
// https://www.ros.org/reps/rep-0103.html#axis-orientation
// AP_AHRS uses the NED convention
// X - North
// Y - East
// Z - Down
// As a consequence, to follow ROS REP 103, it is necessary to switch X and Y,
// as well as invert Z
Vector3f position;
if (ahrs.get_relative_position_NED_home(position)) {
msg.pose.position.x = position[1];
msg.pose.position.y = position[0];
msg.pose.position.z = -position[2];
}
// In ROS REP 103, axis orientation uses the following convention:
// X - Forward
// Y - Left
// Z - Up
// https://www.ros.org/reps/rep-0103.html#axis-orientation
// As a consequence, to follow ROS REP 103, it is necessary to switch X and Y,
// as well as invert Z (NED to ENU conversion) as well as a 90 degree rotation in the Z axis
// for x to point forward
Quaternion orientation;
if (ahrs.get_quaternion(orientation)) {
Quaternion aux(orientation[0], orientation[2], orientation[1], -orientation[3]); //NED to ENU transformation
Quaternion transformation (sqrtF(2) * 0.5,0,0,sqrtF(2) * 0.5); // Z axis 90 degree rotation
orientation = aux * transformation;
msg.pose.orientation.w = orientation[0];
msg.pose.orientation.x = orientation[1];
msg.pose.orientation.y = orientation[2];
msg.pose.orientation.z = orientation[3];
} else {
initialize(msg.pose.orientation);
}
}
#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED
#if AP_DDS_LOCAL_VEL_PUB_ENABLED
void AP_DDS_Client::update_topic(geometry_msgs_msg_TwistStamped& msg)
{
update_topic(msg.header.stamp);
STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID);
auto &ahrs = AP::ahrs();
WITH_SEMAPHORE(ahrs.get_semaphore());
// ROS REP 103 uses the ENU convention:
// X - East
// Y - North
// Z - Up
// https://www.ros.org/reps/rep-0103.html#axis-orientation
// AP_AHRS uses the NED convention
// X - North
// Y - East
// Z - Down
// As a consequence, to follow ROS REP 103, it is necessary to switch X and Y,
// as well as invert Z
Vector3f velocity;
if (ahrs.get_velocity_NED(velocity)) {
msg.twist.linear.x = velocity[1];
msg.twist.linear.y = velocity[0];
msg.twist.linear.z = -velocity[2];
}
// In ROS REP 103, axis orientation uses the following convention:
// X - Forward
// Y - Left
// Z - Up
// https://www.ros.org/reps/rep-0103.html#axis-orientation
// The gyro data is received from AP_AHRS in body-frame
// X - Forward
// Y - Right
// Z - Down
// As a consequence, to follow ROS REP 103, it is necessary to invert Y and Z
Vector3f angular_velocity = ahrs.get_gyro();
msg.twist.angular.x = angular_velocity[0];
msg.twist.angular.y = -angular_velocity[1];
msg.twist.angular.z = -angular_velocity[2];
}
#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED
#if AP_DDS_AIRSPEED_PUB_ENABLED
bool AP_DDS_Client::update_topic(ardupilot_msgs_msg_Airspeed& msg)
{
update_topic(msg.header.stamp);
STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID);
auto &ahrs = AP::ahrs();
WITH_SEMAPHORE(ahrs.get_semaphore());
// In ROS REP 103, axis orientation uses the following convention:
// X - Forward
// Y - Left
// Z - Up
// https://www.ros.org/reps/rep-0103.html#axis-orientation
// The true airspeed data is received from AP_AHRS in body-frame
// X - Forward
// Y - Right
// Z - Down
// As a consequence, to follow ROS REP 103, it is necessary to invert Y and Z
Vector3f true_airspeed_vec_bf;
bool is_airspeed_available {false};
if (ahrs.airspeed_vector_TAS(true_airspeed_vec_bf)) {
msg.true_airspeed.x = true_airspeed_vec_bf[0];
msg.true_airspeed.y = -true_airspeed_vec_bf[1];
msg.true_airspeed.z = -true_airspeed_vec_bf[2];
msg.eas_2_tas = ahrs.get_EAS2TAS();
is_airspeed_available = true;
}
return is_airspeed_available;
}
#endif // AP_DDS_AIRSPEED_PUB_ENABLED
#if AP_DDS_RC_PUB_ENABLED
bool AP_DDS_Client::update_topic(ardupilot_msgs_msg_Rc& msg)
{
update_topic(msg.header.stamp);
AP_RSSI *ap_rssi = AP_RSSI::get_singleton();
auto rc = RC_Channels::get_singleton();
static int16_t counter = 0;
// Is connected if not in failsafe.
// This is only valid if the RC has been connected at least once
msg.is_connected = !rc->in_rc_failsafe();
// Receiver RSSI is reported between 0.0 and 1.0.
msg.receiver_rssi = static_cast<uint8_t>(ap_rssi->read_receiver_rssi()*100.f);
// Limit the max number of available channels to 8
msg.channels_size = MIN(static_cast<uint32_t>(rc->get_valid_channel_count()), 32U);
msg.active_overrides_size = msg.channels_size;
if (msg.channels_size) {
for (uint8_t i = 0; i < static_cast<uint8_t>(msg.channels_size); i++) {
msg.channels[i] = rc->rc_channel(i)->get_radio_in();
msg.active_overrides[i] = rc->rc_channel(i)->has_override();
}
} else {
// If no channels are available, the RC is disconnected.
msg.is_connected = false;
}
// Return true if Radio is connected, or once every 10 steps to reduce useless traffic.
return msg.is_connected ? true : (counter++ % 10 == 0);
}
#endif // AP_DDS_RC_PUB_ENABLED
#if AP_DDS_GEOPOSE_PUB_ENABLED
void AP_DDS_Client::update_topic(geographic_msgs_msg_GeoPoseStamped& msg)
{
update_topic(msg.header.stamp);
STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID);
auto &ahrs = AP::ahrs();
WITH_SEMAPHORE(ahrs.get_semaphore());
Location loc;
if (ahrs.get_location(loc)) {
msg.pose.position.latitude = loc.lat * 1E-7;
msg.pose.position.longitude = loc.lng * 1E-7;
// TODO this is assumed to be absolute frame in WGS-84 as per the GeoPose message definition in ROS.
// Use loc.get_alt_frame() to convert if necessary.
msg.pose.position.altitude = loc.alt * 0.01; // Transform from cm to m
}
// In ROS REP 103, axis orientation uses the following convention:
// X - Forward
// Y - Left
// Z - Up
// https://www.ros.org/reps/rep-0103.html#axis-orientation
// As a consequence, to follow ROS REP 103, it is necessary to switch X and Y,
// as well as invert Z (NED to ENU conversion) as well as a 90 degree rotation in the Z axis
// for x to point forward
Quaternion orientation;
if (ahrs.get_quaternion(orientation)) {
Quaternion aux(orientation[0], orientation[2], orientation[1], -orientation[3]); //NED to ENU transformation
Quaternion transformation(sqrtF(2) * 0.5, 0, 0, sqrtF(2) * 0.5); // Z axis 90 degree rotation
orientation = aux * transformation;
msg.pose.orientation.w = orientation[0];
msg.pose.orientation.x = orientation[1];
msg.pose.orientation.y = orientation[2];
msg.pose.orientation.z = orientation[3];
} else {
initialize(msg.pose.orientation);
}
}
#endif // AP_DDS_GEOPOSE_PUB_ENABLED
#if AP_DDS_GOAL_PUB_ENABLED
bool AP_DDS_Client::update_topic_goal(geographic_msgs_msg_GeoPointStamped& msg)
{
const auto &vehicle = AP::vehicle();
update_topic(msg.header.stamp);
Location target_loc;
// Exit if no target is available.
if (!vehicle->get_target_location(target_loc)) {
return false;
}
target_loc.change_alt_frame(Location::AltFrame::ABSOLUTE);
msg.position.latitude = target_loc.lat * 1e-7;
msg.position.longitude = target_loc.lng * 1e-7;
msg.position.altitude = target_loc.alt * 1e-2;
// Check whether the goal has changed or if the topic has never been published.
const double tolerance_lat_lon = 1e-8; // One order of magnitude smaller than the target's resolution.
const double distance_alt = 1e-3;
if (abs(msg.position.latitude - prev_goal_msg.position.latitude) > tolerance_lat_lon ||
abs(msg.position.longitude - prev_goal_msg.position.longitude) > tolerance_lat_lon ||
abs(msg.position.altitude - prev_goal_msg.position.altitude) > distance_alt ||
prev_goal_msg.header.stamp.sec == 0 ) {
update_topic(prev_goal_msg.header.stamp);
prev_goal_msg.position.latitude = msg.position.latitude;
prev_goal_msg.position.longitude = msg.position.longitude;
prev_goal_msg.position.altitude = msg.position.altitude;
return true;
} else {
return false;
}
}
#endif // AP_DDS_GOAL_PUB_ENABLED
#if AP_DDS_IMU_PUB_ENABLED
void AP_DDS_Client::update_topic(sensor_msgs_msg_Imu& msg)
{
update_topic(msg.header.stamp);
STRCPY(msg.header.frame_id, BASE_LINK_NED_FRAME_ID);
auto &imu = AP::ins();
auto &ahrs = AP::ahrs();
WITH_SEMAPHORE(ahrs.get_semaphore());
Quaternion orientation;
if (ahrs.get_quaternion(orientation)) {
msg.orientation.x = orientation[0];
msg.orientation.y = orientation[1];
msg.orientation.z = orientation[2];
msg.orientation.w = orientation[3];
} else {
initialize(msg.orientation);
}
uint8_t accel_index = ahrs.get_primary_accel_index();
uint8_t gyro_index = ahrs.get_primary_gyro_index();
const Vector3f accel_data = imu.get_accel(accel_index);
const Vector3f gyro_data = imu.get_gyro(gyro_index);
// Populate the message fields
msg.linear_acceleration.x = accel_data.x;
msg.linear_acceleration.y = accel_data.y;
msg.linear_acceleration.z = accel_data.z;
msg.angular_velocity.x = gyro_data.x;
msg.angular_velocity.y = gyro_data.y;
msg.angular_velocity.z = gyro_data.z;
}
#endif // AP_DDS_IMU_PUB_ENABLED
#if AP_DDS_CLOCK_PUB_ENABLED
void AP_DDS_Client::update_topic(rosgraph_msgs_msg_Clock& msg)
{
update_topic(msg.clock);
}
#endif // AP_DDS_CLOCK_PUB_ENABLED
#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
void AP_DDS_Client::update_topic(geographic_msgs_msg_GeoPointStamped& msg)
{
update_topic(msg.header.stamp);
STRCPY(msg.header.frame_id, BASE_LINK_FRAME_ID);
auto &ahrs = AP::ahrs();
WITH_SEMAPHORE(ahrs.get_semaphore());
Location ekf_origin;
// LLA is WGS-84 geodetic coordinate.
// Altitude converted from cm to m.
if (ahrs.get_origin(ekf_origin)) {
msg.position.latitude = ekf_origin.lat * 1E-7;
msg.position.longitude = ekf_origin.lng * 1E-7;
msg.position.altitude = ekf_origin.alt * 0.01;
}
}
#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
#if AP_DDS_STATUS_PUB_ENABLED
bool AP_DDS_Client::update_topic(ardupilot_msgs_msg_Status& msg)
{
// Fill the new message.
const auto &vehicle = AP::vehicle();
const auto &battery = AP::battery();
msg.vehicle_type = static_cast<uint8_t>(AP::fwversion().vehicle_type);
msg.armed = hal.util->get_soft_armed();
msg.mode = vehicle->get_mode();
msg.flying = vehicle->get_likely_flying();
msg.external_control = true; // Always true for now. To be filled after PR#28429.
uint8_t fs_iter = 0;
msg.failsafe_size = 0;
if (rc().in_rc_failsafe()) {
msg.failsafe[fs_iter++] = Status::FS_RADIO;
}
if (battery.has_failsafed()) {
msg.failsafe[fs_iter++] = Status::FS_BATTERY;
}
// TODO: replace flag with function.
if (AP_Notify::flags.failsafe_gcs) {
msg.failsafe[fs_iter++] = Status::FS_GCS;
}
// TODO: replace flag with function.
if (AP_Notify::flags.failsafe_ekf) {
msg.failsafe[fs_iter++] = Status::FS_EKF;
}
msg.failsafe_size = fs_iter;
// Compare with the previous one.
bool is_message_changed {false};
is_message_changed |= (last_status_msg_.flying != msg.flying);
is_message_changed |= (last_status_msg_.armed != msg.armed);
is_message_changed |= (last_status_msg_.mode != msg.mode);
is_message_changed |= (last_status_msg_.vehicle_type != msg.vehicle_type);
is_message_changed |= (last_status_msg_.failsafe_size != msg.failsafe_size);
is_message_changed |= (last_status_msg_.external_control != msg.external_control);
const auto timestamp = AP_HAL::millis64();
if ( is_message_changed ) {
last_status_msg_.flying = msg.flying;
last_status_msg_.armed = msg.armed;
last_status_msg_.mode = msg.mode;
last_status_msg_.vehicle_type = msg.vehicle_type;
last_status_msg_.failsafe_size = msg.failsafe_size;
last_status_msg_.external_control = msg.external_control;
last_status_publish_time_ms = timestamp;
update_topic(msg.header.stamp);
return true;
} else if (timestamp - last_status_publish_time_ms > DELAY_STATUS_TOPIC_MS * 5) {
// Publish the status message at 2Hz even if no change is detected.
last_status_publish_time_ms = timestamp;
update_topic(msg.header.stamp);
return true;
} else {
return false;
}
}
#endif // AP_DDS_STATUS_PUB_ENABLED
/*
start the DDS thread
*/
bool AP_DDS_Client::start(void)
{
AP_Param::setup_object_defaults(this, var_info);
AP_Param::load_object_from_eeprom(this, var_info);
if (enabled == 0) {
return true;
}
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_DDS_Client::main_loop, void),
"DDS",
8192, AP_HAL::Scheduler::PRIORITY_IO, 1)) {
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Thread create failed", msg_prefix);
return false;
}
return true;
}
// read function triggered at every subscription callback
void AP_DDS_Client::on_topic_trampoline(uxrSession* uxr_session, uxrObjectId object_id, uint16_t request_id, uxrStreamId stream_id, struct ucdrBuffer* ub, uint16_t length,
void* args)
{
AP_DDS_Client *dds = (AP_DDS_Client *)args;
dds->on_topic(uxr_session, object_id, request_id, stream_id, ub, length);
}
void AP_DDS_Client::on_topic(uxrSession* uxr_session, uxrObjectId object_id, uint16_t request_id, uxrStreamId stream_id, struct ucdrBuffer* ub, uint16_t length)
{
/*
TEMPLATE for reading to the subscribed topics
1) Store the read contents into the ucdr buffer
2) Deserialize the said contents into the topic instance
*/
(void) uxr_session;
(void) request_id;
(void) stream_id;
(void) length;
switch (object_id.id) {
#if AP_DDS_JOY_SUB_ENABLED
case topics[to_underlying(TopicIndex::JOY_SUB)].dr_id.id: {
const bool success = sensor_msgs_msg_Joy_deserialize_topic(ub, &rx_joy_topic);
if (success == false) {
break;
}
if (rx_joy_topic.axes_size >= 4) {
const uint32_t t_now = AP_HAL::millis();
for (uint8_t i = 0; i < MIN(8U, rx_joy_topic.axes_size); i++) {
// Ignore channel override if NaN.
if (std::isnan(rx_joy_topic.axes[i])) {
// Setting the RC override to 0U releases the channel back to the RC.
RC_Channels::set_override(i, 0U, t_now);
} else {
const uint16_t mapped_data = static_cast<uint16_t>(
linear_interpolate(rc().channel(i)->get_radio_min(),
rc().channel(i)->get_radio_max(),
rx_joy_topic.axes[i],
-1.0, 1.0));
RC_Channels::set_override(i, mapped_data, t_now);
}
}
}
break;
}
#endif // AP_DDS_JOY_SUB_ENABLED
#if AP_DDS_DYNAMIC_TF_SUB_ENABLED
case topics[to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB)].dr_id.id: {
const bool success = tf2_msgs_msg_TFMessage_deserialize_topic(ub, &rx_dynamic_transforms_topic);
if (success == false) {
break;
}
if (rx_dynamic_transforms_topic.transforms_size > 0) {
#if AP_DDS_VISUALODOM_ENABLED
AP_DDS_External_Odom::handle_external_odom(rx_dynamic_transforms_topic);
#endif // AP_DDS_VISUALODOM_ENABLED
} else {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Received tf2_msgs/TFMessage: TF is empty", msg_prefix);
}
break;
}
#endif // AP_DDS_DYNAMIC_TF_SUB_ENABLED
#if AP_DDS_VEL_CTRL_ENABLED
case topics[to_underlying(TopicIndex::VELOCITY_CONTROL_SUB)].dr_id.id: {
const bool success = geometry_msgs_msg_TwistStamped_deserialize_topic(ub, &rx_velocity_control_topic);
if (success == false) {
break;
}
#if AP_EXTERNAL_CONTROL_ENABLED
if (!AP_DDS_External_Control::handle_velocity_control(rx_velocity_control_topic)) {
// TODO #23430 handle velocity control failure through rosout, throttled.
}
#endif // AP_EXTERNAL_CONTROL_ENABLED
break;
}
#endif // AP_DDS_VEL_CTRL_ENABLED
#if AP_DDS_GLOBAL_POS_CTRL_ENABLED
case topics[to_underlying(TopicIndex::GLOBAL_POSITION_SUB)].dr_id.id: {
const bool success = ardupilot_msgs_msg_GlobalPosition_deserialize_topic(ub, &rx_global_position_control_topic);
if (success == false) {
break;
}
#if AP_EXTERNAL_CONTROL_ENABLED
if (!AP_DDS_External_Control::handle_global_position_control(rx_global_position_control_topic)) {
// TODO #23430 handle global position control failure through rosout, throttled.
}
#endif // AP_EXTERNAL_CONTROL_ENABLED
break;
}
#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED
}
}
/*
callback on request completion
*/
void AP_DDS_Client::on_request_trampoline(uxrSession* uxr_session, uxrObjectId object_id, uint16_t request_id, SampleIdentity* sample_id, ucdrBuffer* ub, uint16_t length, void* args)
{
AP_DDS_Client *dds = (AP_DDS_Client *)args;
dds->on_request(uxr_session, object_id, request_id, sample_id, ub, length);
}
void AP_DDS_Client::on_request(uxrSession* uxr_session, uxrObjectId object_id, uint16_t request_id, SampleIdentity* sample_id, ucdrBuffer* ub, uint16_t length)
{
(void) request_id;
(void) length;
switch (object_id.id) {
#if AP_DDS_ARM_SERVER_ENABLED
case services[to_underlying(ServiceIndex::ARMING_MOTORS)].rep_id: {
ardupilot_msgs_srv_ArmMotors_Request arm_motors_request;
ardupilot_msgs_srv_ArmMotors_Response arm_motors_response;
const bool deserialize_success = ardupilot_msgs_srv_ArmMotors_Request_deserialize_topic(ub, &arm_motors_request);
if (deserialize_success == false) {
break;
}
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Request for %sing received", msg_prefix, arm_motors_request.arm ? "arm" : "disarm");
#if AP_EXTERNAL_CONTROL_ENABLED
const bool do_checks = true;
arm_motors_response.result = arm_motors_request.arm ? AP_DDS_External_Control::arm(AP_Arming::Method::DDS, do_checks) : AP_DDS_External_Control::disarm(AP_Arming::Method::DDS, do_checks);
if (!arm_motors_response.result) {
// TODO #23430 handle arm failure through rosout, throttled.
}
#endif // AP_EXTERNAL_CONTROL_ENABLED
const uxrObjectId replier_id = {
.id = services[to_underlying(ServiceIndex::ARMING_MOTORS)].rep_id,
.type = UXR_REPLIER_ID
};
uint8_t reply_buffer[8] {};
ucdrBuffer reply_ub;
ucdr_init_buffer(&reply_ub, reply_buffer, sizeof(reply_buffer));
const bool serialize_success = ardupilot_msgs_srv_ArmMotors_Response_serialize_topic(&reply_ub, &arm_motors_response);
if (serialize_success == false) {
break;
}
uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub));
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Request for Arming/Disarming : %s", msg_prefix, arm_motors_response.result ? "SUCCESS" : "FAIL");
break;
}
#endif // AP_DDS_ARM_SERVER_ENABLED
#if AP_DDS_MODE_SWITCH_SERVER_ENABLED
case services[to_underlying(ServiceIndex::MODE_SWITCH)].rep_id: {
ardupilot_msgs_srv_ModeSwitch_Request mode_switch_request;
ardupilot_msgs_srv_ModeSwitch_Response mode_switch_response;
const bool deserialize_success = ardupilot_msgs_srv_ModeSwitch_Request_deserialize_topic(ub, &mode_switch_request);
if (deserialize_success == false) {
break;
}
mode_switch_response.status = AP::vehicle()->set_mode(mode_switch_request.mode, ModeReason::DDS_COMMAND);
mode_switch_response.curr_mode = AP::vehicle()->get_mode();
const uxrObjectId replier_id = {
.id = services[to_underlying(ServiceIndex::MODE_SWITCH)].rep_id,
.type = UXR_REPLIER_ID
};
uint8_t reply_buffer[8] {};
ucdrBuffer reply_ub;
ucdr_init_buffer(&reply_ub, reply_buffer, sizeof(reply_buffer));
const bool serialize_success = ardupilot_msgs_srv_ModeSwitch_Response_serialize_topic(&reply_ub, &mode_switch_response);
if (serialize_success == false) {
break;
}
uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub));
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Request for Mode Switch : %s", msg_prefix, mode_switch_response.status ? "SUCCESS" : "FAIL");
break;
}
#endif // AP_DDS_MODE_SWITCH_SERVER_ENABLED
#if AP_DDS_VTOL_TAKEOFF_SERVER_ENABLED
case services[to_underlying(ServiceIndex::TAKEOFF)].rep_id: {
ardupilot_msgs_srv_Takeoff_Request takeoff_request;
ardupilot_msgs_srv_Takeoff_Response takeoff_response;
const bool deserialize_success = ardupilot_msgs_srv_Takeoff_Request_deserialize_topic(ub, &takeoff_request);
if (deserialize_success == false) {
break;
}
takeoff_response.status = AP::vehicle()->start_takeoff(takeoff_request.alt);
const uxrObjectId replier_id = {
.id = services[to_underlying(ServiceIndex::TAKEOFF)].rep_id,
.type = UXR_REPLIER_ID
};
uint8_t reply_buffer[8] {};
ucdrBuffer reply_ub;
ucdr_init_buffer(&reply_ub, reply_buffer, sizeof(reply_buffer));
const bool serialize_success = ardupilot_msgs_srv_Takeoff_Response_serialize_topic(&reply_ub, &takeoff_response);
if (serialize_success == false) {
break;
}