Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_DDS/AP_DDS_Topic_Table.h
9584 views
1
#include "builtin_interfaces/msg/Time.h"
2
#include "sensor_msgs/msg/NavSatFix.h"
3
#include "tf2_msgs/msg/TFMessage.h"
4
#include "sensor_msgs/msg/BatteryState.h"
5
#include "geographic_msgs/msg/GeoPoseStamped.h"
6
#include "geometry_msgs/msg/Vector3Stamped.h"
7
#if AP_DDS_IMU_PUB_ENABLED
8
#include "sensor_msgs/msg/Imu.h"
9
#endif //AP_DDS_IMU_PUB_ENABLED
10
11
#include "uxr/client/client.h"
12
13
// Code generated table based on the enabled topics.
14
// Mavgen is using python, loops are not readable.
15
// Can use jinja to template (like Flask)
16
17
enum class TopicIndex: uint8_t {
18
#if AP_DDS_TIME_PUB_ENABLED
19
TIME_PUB,
20
#endif // AP_DDS_TIME_PUB_ENABLED
21
#if AP_DDS_NAVSATFIX_PUB_ENABLED
22
NAV_SAT_FIX_PUB,
23
#endif // AP_DDS_NAVSATFIX_PUB_ENABLED
24
#if AP_DDS_STATIC_TF_PUB_ENABLED
25
STATIC_TRANSFORMS_PUB,
26
#endif // AP_DDS_STATIC_TF_PUB_ENABLED
27
#if AP_DDS_BATTERY_STATE_PUB_ENABLED
28
BATTERY_STATE_PUB,
29
#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED
30
#if AP_DDS_IMU_PUB_ENABLED
31
IMU_PUB,
32
#endif //AP_DDS_IMU_PUB_ENABLED
33
#if AP_DDS_LOCAL_POSE_PUB_ENABLED
34
LOCAL_POSE_PUB,
35
#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED
36
#if AP_DDS_LOCAL_VEL_PUB_ENABLED
37
LOCAL_VELOCITY_PUB,
38
#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED
39
#if AP_DDS_AIRSPEED_PUB_ENABLED
40
LOCAL_AIRSPEED_PUB,
41
#endif // AP_DDS_AIRSPEED_PUB_ENABLED
42
#if AP_DDS_RC_PUB_ENABLED
43
LOCAL_RC_PUB,
44
#endif // AP_DDS_RC_PUB_ENABLED
45
#if AP_DDS_GEOPOSE_PUB_ENABLED
46
GEOPOSE_PUB,
47
#endif // AP_DDS_GEOPOSE_PUB_ENABLED
48
#if AP_DDS_GOAL_PUB_ENABLED
49
GOAL_PUB,
50
#endif // AP_DDS_GOAL_PUB_ENABLED
51
#if AP_DDS_CLOCK_PUB_ENABLED
52
CLOCK_PUB,
53
#endif // AP_DDS_CLOCK_PUB_ENABLED
54
#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
55
GPS_GLOBAL_ORIGIN_PUB,
56
#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
57
#if AP_DDS_STATUS_PUB_ENABLED
58
STATUS_PUB,
59
#endif // AP_DDS_STATUS_PUB_ENABLED
60
#if AP_DDS_JOY_SUB_ENABLED
61
JOY_SUB,
62
#endif // AP_DDS_JOY_SUB_ENABLED
63
#if AP_DDS_DYNAMIC_TF_SUB_ENABLED
64
DYNAMIC_TRANSFORMS_SUB,
65
#endif // AP_DDS_DYNAMIC_TF_SUB_ENABLED
66
#if AP_DDS_VEL_CTRL_ENABLED
67
VELOCITY_CONTROL_SUB,
68
#endif // AP_DDS_VEL_CTRL_ENABLED
69
#if AP_DDS_GLOBAL_POS_CTRL_ENABLED
70
GLOBAL_POSITION_SUB,
71
#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED
72
};
73
74
static inline constexpr uint8_t to_underlying(const TopicIndex index)
75
{
76
static_assert(sizeof(index) == sizeof(uint8_t));
77
return static_cast<uint8_t>(index);
78
}
79
80
81
constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
82
#if AP_DDS_TIME_PUB_ENABLED
83
{
84
.topic_id = to_underlying(TopicIndex::TIME_PUB),
85
.pub_id = to_underlying(TopicIndex::TIME_PUB),
86
.sub_id = to_underlying(TopicIndex::TIME_PUB),
87
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::TIME_PUB), .type=UXR_DATAWRITER_ID},
88
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::TIME_PUB), .type=UXR_DATAREADER_ID},
89
.topic_rw = Topic_rw::DataWriter,
90
.topic_name = "rt/ap/time",
91
.type_name = "builtin_interfaces::msg::dds_::Time_",
92
.qos = {
93
.durability = UXR_DURABILITY_VOLATILE,
94
.reliability = UXR_RELIABILITY_RELIABLE,
95
.history = UXR_HISTORY_KEEP_LAST,
96
.depth = 20,
97
},
98
},
99
#endif // AP_DDS_TIME_PUB_ENABLED
100
#if AP_DDS_NAVSATFIX_PUB_ENABLED
101
{
102
.topic_id = to_underlying(TopicIndex::NAV_SAT_FIX_PUB),
103
.pub_id = to_underlying(TopicIndex::NAV_SAT_FIX_PUB),
104
.sub_id = to_underlying(TopicIndex::NAV_SAT_FIX_PUB),
105
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::NAV_SAT_FIX_PUB), .type=UXR_DATAWRITER_ID},
106
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::NAV_SAT_FIX_PUB), .type=UXR_DATAREADER_ID},
107
.topic_rw = Topic_rw::DataWriter,
108
.topic_name = "rt/ap/navsat",
109
.type_name = "sensor_msgs::msg::dds_::NavSatFix_",
110
.qos = {
111
.durability = UXR_DURABILITY_VOLATILE,
112
.reliability = UXR_RELIABILITY_BEST_EFFORT,
113
.history = UXR_HISTORY_KEEP_LAST,
114
.depth = 5,
115
},
116
},
117
#endif // AP_DDS_NAVSATFIX_PUB_ENABLED
118
#if AP_DDS_STATIC_TF_PUB_ENABLED
119
{
120
.topic_id = to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB),
121
.pub_id = to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB),
122
.sub_id = to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB),
123
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB), .type=UXR_DATAWRITER_ID},
124
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB), .type=UXR_DATAREADER_ID},
125
.topic_rw = Topic_rw::DataWriter,
126
.topic_name = "rt/ap/tf_static",
127
.type_name = "tf2_msgs::msg::dds_::TFMessage_",
128
.qos = {
129
.durability = UXR_DURABILITY_TRANSIENT_LOCAL,
130
.reliability = UXR_RELIABILITY_RELIABLE,
131
.history = UXR_HISTORY_KEEP_LAST,
132
.depth = 1,
133
},
134
},
135
#endif // AP_DDS_STATIC_TF_PUB_ENABLED
136
#if AP_DDS_BATTERY_STATE_PUB_ENABLED
137
{
138
.topic_id = to_underlying(TopicIndex::BATTERY_STATE_PUB),
139
.pub_id = to_underlying(TopicIndex::BATTERY_STATE_PUB),
140
.sub_id = to_underlying(TopicIndex::BATTERY_STATE_PUB),
141
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::BATTERY_STATE_PUB), .type=UXR_DATAWRITER_ID},
142
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::BATTERY_STATE_PUB), .type=UXR_DATAREADER_ID},
143
.topic_rw = Topic_rw::DataWriter,
144
.topic_name = "rt/ap/battery",
145
.type_name = "sensor_msgs::msg::dds_::BatteryState_",
146
.qos = {
147
.durability = UXR_DURABILITY_VOLATILE,
148
.reliability = UXR_RELIABILITY_BEST_EFFORT,
149
.history = UXR_HISTORY_KEEP_LAST,
150
.depth = 5,
151
},
152
},
153
#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED
154
#if AP_DDS_IMU_PUB_ENABLED
155
{
156
.topic_id = to_underlying(TopicIndex::IMU_PUB),
157
.pub_id = to_underlying(TopicIndex::IMU_PUB),
158
.sub_id = to_underlying(TopicIndex::IMU_PUB),
159
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::IMU_PUB), .type=UXR_DATAWRITER_ID},
160
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::IMU_PUB), .type=UXR_DATAREADER_ID},
161
.topic_rw = Topic_rw::DataWriter,
162
.topic_name = "rt/ap/imu/experimental/data",
163
.type_name = "sensor_msgs::msg::dds_::Imu_",
164
.qos = {
165
.durability = UXR_DURABILITY_VOLATILE,
166
.reliability = UXR_RELIABILITY_BEST_EFFORT,
167
.history = UXR_HISTORY_KEEP_LAST,
168
.depth = 5,
169
},
170
},
171
#endif //AP_DDS_IMU_PUB_ENABLED
172
#if AP_DDS_LOCAL_POSE_PUB_ENABLED
173
{
174
.topic_id = to_underlying(TopicIndex::LOCAL_POSE_PUB),
175
.pub_id = to_underlying(TopicIndex::LOCAL_POSE_PUB),
176
.sub_id = to_underlying(TopicIndex::LOCAL_POSE_PUB),
177
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_POSE_PUB), .type=UXR_DATAWRITER_ID},
178
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_POSE_PUB), .type=UXR_DATAREADER_ID},
179
.topic_rw = Topic_rw::DataWriter,
180
.topic_name = "rt/ap/pose/filtered",
181
.type_name = "geometry_msgs::msg::dds_::PoseStamped_",
182
.qos = {
183
.durability = UXR_DURABILITY_VOLATILE,
184
.reliability = UXR_RELIABILITY_BEST_EFFORT,
185
.history = UXR_HISTORY_KEEP_LAST,
186
.depth = 5,
187
},
188
},
189
#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED
190
#if AP_DDS_LOCAL_VEL_PUB_ENABLED
191
{
192
.topic_id = to_underlying(TopicIndex::LOCAL_VELOCITY_PUB),
193
.pub_id = to_underlying(TopicIndex::LOCAL_VELOCITY_PUB),
194
.sub_id = to_underlying(TopicIndex::LOCAL_VELOCITY_PUB),
195
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_VELOCITY_PUB), .type=UXR_DATAWRITER_ID},
196
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_VELOCITY_PUB), .type=UXR_DATAREADER_ID},
197
.topic_rw = Topic_rw::DataWriter,
198
.topic_name = "rt/ap/twist/filtered",
199
.type_name = "geometry_msgs::msg::dds_::TwistStamped_",
200
.qos = {
201
.durability = UXR_DURABILITY_VOLATILE,
202
.reliability = UXR_RELIABILITY_BEST_EFFORT,
203
.history = UXR_HISTORY_KEEP_LAST,
204
.depth = 5,
205
},
206
},
207
#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED
208
#if AP_DDS_AIRSPEED_PUB_ENABLED
209
{
210
.topic_id = to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB),
211
.pub_id = to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB),
212
.sub_id = to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB),
213
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB), .type=UXR_DATAWRITER_ID},
214
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB), .type=UXR_DATAREADER_ID},
215
.topic_rw = Topic_rw::DataWriter,
216
.topic_name = "rt/ap/airspeed",
217
.type_name = "ardupilot_msgs::msg::dds_::Airspeed_",
218
.qos = {
219
.durability = UXR_DURABILITY_VOLATILE,
220
.reliability = UXR_RELIABILITY_BEST_EFFORT,
221
.history = UXR_HISTORY_KEEP_LAST,
222
.depth = 5,
223
},
224
},
225
#endif // AP_DDS_AIRSPEED_PUB_ENABLED
226
#if AP_DDS_RC_PUB_ENABLED
227
{
228
.topic_id = to_underlying(TopicIndex::LOCAL_RC_PUB),
229
.pub_id = to_underlying(TopicIndex::LOCAL_RC_PUB),
230
.sub_id = to_underlying(TopicIndex::LOCAL_RC_PUB),
231
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_RC_PUB), .type=UXR_DATAWRITER_ID},
232
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_RC_PUB), .type=UXR_DATAREADER_ID},
233
.topic_rw = Topic_rw::DataWriter,
234
.topic_name = "rt/ap/rc",
235
.type_name = "ardupilot_msgs::msg::dds_::Rc_",
236
.qos = {
237
.durability = UXR_DURABILITY_VOLATILE,
238
.reliability = UXR_RELIABILITY_BEST_EFFORT,
239
.history = UXR_HISTORY_KEEP_LAST,
240
.depth = 1,
241
},
242
},
243
#endif // AP_DDS_RC_PUB_ENABLED
244
#if AP_DDS_GEOPOSE_PUB_ENABLED
245
{
246
.topic_id = to_underlying(TopicIndex::GEOPOSE_PUB),
247
.pub_id = to_underlying(TopicIndex::GEOPOSE_PUB),
248
.sub_id = to_underlying(TopicIndex::GEOPOSE_PUB),
249
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GEOPOSE_PUB), .type=UXR_DATAWRITER_ID},
250
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GEOPOSE_PUB), .type=UXR_DATAREADER_ID},
251
.topic_rw = Topic_rw::DataWriter,
252
.topic_name = "rt/ap/geopose/filtered",
253
.type_name = "geographic_msgs::msg::dds_::GeoPoseStamped_",
254
.qos = {
255
.durability = UXR_DURABILITY_VOLATILE,
256
.reliability = UXR_RELIABILITY_BEST_EFFORT,
257
.history = UXR_HISTORY_KEEP_LAST,
258
.depth = 5,
259
},
260
},
261
#endif // AP_DDS_GEOPOSE_PUB_ENABLED
262
#if AP_DDS_GOAL_PUB_ENABLED
263
{
264
.topic_id = to_underlying(TopicIndex::GOAL_PUB),
265
.pub_id = to_underlying(TopicIndex::GOAL_PUB),
266
.sub_id = to_underlying(TopicIndex::GOAL_PUB),
267
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GOAL_PUB), .type=UXR_DATAWRITER_ID},
268
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GOAL_PUB), .type=UXR_DATAREADER_ID},
269
.topic_rw = Topic_rw::DataWriter,
270
.topic_name = "rt/ap/goal_lla",
271
.type_name = "geographic_msgs::msg::dds_::GeoPointStamped_",
272
.qos = {
273
.durability = UXR_DURABILITY_TRANSIENT_LOCAL,
274
.reliability = UXR_RELIABILITY_RELIABLE,
275
.history = UXR_HISTORY_KEEP_LAST,
276
.depth = 1,
277
},
278
},
279
#endif // AP_DDS_GOAL_PUB_ENABLED
280
#if AP_DDS_CLOCK_PUB_ENABLED
281
{
282
.topic_id = to_underlying(TopicIndex::CLOCK_PUB),
283
.pub_id = to_underlying(TopicIndex::CLOCK_PUB),
284
.sub_id = to_underlying(TopicIndex::CLOCK_PUB),
285
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::CLOCK_PUB), .type=UXR_DATAWRITER_ID},
286
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::CLOCK_PUB), .type=UXR_DATAREADER_ID},
287
.topic_rw = Topic_rw::DataWriter,
288
.topic_name = "rt/ap/clock",
289
.type_name = "rosgraph_msgs::msg::dds_::Clock_",
290
.qos = {
291
.durability = UXR_DURABILITY_VOLATILE,
292
.reliability = UXR_RELIABILITY_RELIABLE,
293
.history = UXR_HISTORY_KEEP_LAST,
294
.depth = 20,
295
},
296
},
297
#endif // AP_DDS_CLOCK_PUB_ENABLED
298
#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
299
{
300
.topic_id = to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB),
301
.pub_id = to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB),
302
.sub_id = to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB),
303
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB), .type=UXR_DATAWRITER_ID},
304
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB), .type=UXR_DATAREADER_ID},
305
.topic_rw = Topic_rw::DataWriter,
306
.topic_name = "rt/ap/gps_global_origin/filtered",
307
.type_name = "geographic_msgs::msg::dds_::GeoPointStamped_",
308
.qos = {
309
.durability = UXR_DURABILITY_VOLATILE,
310
.reliability = UXR_RELIABILITY_BEST_EFFORT,
311
.history = UXR_HISTORY_KEEP_LAST,
312
.depth = 5,
313
},
314
},
315
#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED
316
#if AP_DDS_STATUS_PUB_ENABLED
317
{
318
.topic_id = to_underlying(TopicIndex::STATUS_PUB),
319
.pub_id = to_underlying(TopicIndex::STATUS_PUB),
320
.sub_id = to_underlying(TopicIndex::STATUS_PUB),
321
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::STATUS_PUB), .type=UXR_DATAWRITER_ID},
322
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::STATUS_PUB), .type=UXR_DATAREADER_ID},
323
.topic_rw = Topic_rw::DataWriter,
324
.topic_name = "rt/ap/status",
325
.type_name = "ardupilot_msgs::msg::dds_::Status_",
326
.qos = {
327
.durability = UXR_DURABILITY_TRANSIENT_LOCAL,
328
.reliability = UXR_RELIABILITY_RELIABLE,
329
.history = UXR_HISTORY_KEEP_LAST,
330
.depth = 1,
331
},
332
},
333
#endif // AP_DDS_STATUS_PUB_ENABLED
334
#if AP_DDS_JOY_SUB_ENABLED
335
{
336
.topic_id = to_underlying(TopicIndex::JOY_SUB),
337
.pub_id = to_underlying(TopicIndex::JOY_SUB),
338
.sub_id = to_underlying(TopicIndex::JOY_SUB),
339
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::JOY_SUB), .type=UXR_DATAWRITER_ID},
340
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::JOY_SUB), .type=UXR_DATAREADER_ID},
341
.topic_rw = Topic_rw::DataReader,
342
.topic_name = "rt/ap/joy",
343
.type_name = "sensor_msgs::msg::dds_::Joy_",
344
.qos = {
345
.durability = UXR_DURABILITY_VOLATILE,
346
.reliability = UXR_RELIABILITY_BEST_EFFORT,
347
.history = UXR_HISTORY_KEEP_LAST,
348
.depth = 5,
349
},
350
},
351
#endif // AP_DDS_JOY_SUB_ENABLED
352
#if AP_DDS_DYNAMIC_TF_SUB_ENABLED
353
{
354
.topic_id = to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB),
355
.pub_id = to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB),
356
.sub_id = to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB),
357
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB), .type=UXR_DATAWRITER_ID},
358
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB), .type=UXR_DATAREADER_ID},
359
.topic_rw = Topic_rw::DataReader,
360
.topic_name = "rt/ap/tf",
361
.type_name = "tf2_msgs::msg::dds_::TFMessage_",
362
.qos = {
363
.durability = UXR_DURABILITY_VOLATILE,
364
.reliability = UXR_RELIABILITY_BEST_EFFORT,
365
.history = UXR_HISTORY_KEEP_LAST,
366
.depth = 5,
367
},
368
},
369
#endif // AP_DDS_DYNAMIC_TF_SUB_ENABLED
370
#if AP_DDS_VEL_CTRL_ENABLED
371
{
372
.topic_id = to_underlying(TopicIndex::VELOCITY_CONTROL_SUB),
373
.pub_id = to_underlying(TopicIndex::VELOCITY_CONTROL_SUB),
374
.sub_id = to_underlying(TopicIndex::VELOCITY_CONTROL_SUB),
375
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::VELOCITY_CONTROL_SUB), .type=UXR_DATAWRITER_ID},
376
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::VELOCITY_CONTROL_SUB), .type=UXR_DATAREADER_ID},
377
.topic_rw = Topic_rw::DataReader,
378
.topic_name = "rt/ap/cmd_vel",
379
.type_name = "geometry_msgs::msg::dds_::TwistStamped_",
380
.qos = {
381
.durability = UXR_DURABILITY_VOLATILE,
382
.reliability = UXR_RELIABILITY_BEST_EFFORT,
383
.history = UXR_HISTORY_KEEP_LAST,
384
.depth = 5,
385
},
386
},
387
#endif // AP_DDS_VEL_CTRL_ENABLED
388
#if AP_DDS_GLOBAL_POS_CTRL_ENABLED
389
{
390
.topic_id = to_underlying(TopicIndex::GLOBAL_POSITION_SUB),
391
.pub_id = to_underlying(TopicIndex::GLOBAL_POSITION_SUB),
392
.sub_id = to_underlying(TopicIndex::GLOBAL_POSITION_SUB),
393
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GLOBAL_POSITION_SUB), .type=UXR_DATAWRITER_ID},
394
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GLOBAL_POSITION_SUB), .type=UXR_DATAREADER_ID},
395
.topic_rw = Topic_rw::DataReader,
396
.topic_name = "rt/ap/cmd_gps_pose",
397
.type_name = "ardupilot_msgs::msg::dds_::GlobalPosition_",
398
.qos = {
399
.durability = UXR_DURABILITY_VOLATILE,
400
.reliability = UXR_RELIABILITY_BEST_EFFORT,
401
.history = UXR_HISTORY_KEEP_LAST,
402
.depth = 5,
403
},
404
},
405
#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED
406
};
407
408