-
Notifications
You must be signed in to change notification settings - Fork 34
/
rmw_impl.cpp
3054 lines (2659 loc) · 81.4 KB
/
rmw_impl.cpp
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
// Copyright 2020 Real-Time Innovations, Inc. (RTI)
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "rmw_connextdds/rmw_impl.hpp"
#include <algorithm>
#include <string>
#include <vector>
#include <stdexcept>
#include "rmw_connextdds/graph_cache.hpp"
#define ROS_SERVICE_REQUESTER_PREFIX_STR "rq"
#define ROS_SERVICE_RESPONSE_PREFIX_STR "rr"
const char * const ROS_TOPIC_PREFIX = "rt";
const char * const ROS_SERVICE_REQUESTER_PREFIX = ROS_SERVICE_REQUESTER_PREFIX_STR;
const char * const ROS_SERVICE_RESPONSE_PREFIX = ROS_SERVICE_RESPONSE_PREFIX_STR;
std::string
rmw_connextdds_create_topic_name(
const char * prefix,
const char * topic_name,
const char * suffix,
bool avoid_ros_namespace_conventions)
{
if (avoid_ros_namespace_conventions) {
return std::string(topic_name) + std::string(suffix);
} else {
return std::string(prefix) +
std::string(topic_name) +
std::string(suffix);
}
}
std::string
rmw_connextdds_create_topic_name(
const char * prefix,
const char * topic_name,
const char * suffix,
const rmw_qos_profile_t * qos_policies)
{
return rmw_connextdds_create_topic_name(
prefix,
topic_name,
suffix,
qos_policies->avoid_ros_namespace_conventions);
}
rcutils_ret_t
rcutils_uint8_array_copy(
rcutils_uint8_array_t * const dst,
const rcutils_uint8_array_t * const src)
{
if (src->buffer_length > 0) {
if (src->buffer_length > dst->buffer_capacity) {
rcutils_ret_t rc =
rcutils_uint8_array_resize(dst, src->buffer_length);
if (RCUTILS_RET_OK != rc) {
return rc;
}
}
dst->buffer_length = src->buffer_length;
memcpy(dst->buffer, src->buffer, src->buffer_length);
} else {
dst->buffer_length = 0;
}
return RCUTILS_RET_OK;
}
static inline void str_trim(
const char * const s,
const size_t s_len,
size_t * const s_start_out,
size_t * const s_end_out)
{
size_t s_i = 0;
for (; s_i < s_len && std::isspace(s[s_i]); s_i++) {
}
*s_start_out = s_i;
for (; s_i < s_len && !std::isspace(s[s_i]); s_i++) {
}
*s_end_out = s_i;
}
// This function "tokenizes" a string and stores the parsed tokens in a sequence.
// Note that that a trailing empty element is not supported (e.g. `"foo,bar,"`,
// or `"foo, bar, "` if trimming is enabled), unless empty elements are allowed
// (in which, e.g., `"foo,,bar,"` would also be accepted).
rmw_ret_t
rmw_connextdds_parse_string_list(
const char * const list,
struct DDS_StringSeq * const parsed_out,
const char delimiter,
const bool trim_elements,
const bool allow_empty_elements,
const bool append_values)
{
const size_t input_len = strlen(list);
// This function expects to be called on a non-empty input string
RMW_CONNEXT_ASSERT(input_len > 0)
RMW_CONNEXT_LOG_TRACE_A(
"parse list: "
"delim=%c, trim_el=%d, empty_el=%d, append=%d, input='%s'",
delimiter, trim_elements, allow_empty_elements, append_values, list)
DDS_Long parsed_len = DDS_StringSeq_get_length(parsed_out);
if (!append_values) {
parsed_len = 0;
if (!DDS_StringSeq_set_length(parsed_out, parsed_len)) {
RMW_CONNEXT_LOG_ERROR_SET("failed to reset sequence length")
return RMW_RET_ERROR;
}
}
size_t input_i = 0,
next_i_start = 0;
for (;
input_i < input_len;
parsed_len += 1,
input_i += 2,
next_i_start = input_i)
{
// determine token's lenght by finding a delimiter (or end of input)
for (;
input_i + 1 < input_len && delimiter != list[input_i + 1];
input_i += 1)
{
}
RMW_CONNEXT_ASSERT(input_i >= next_i_start)
RMW_CONNEXT_ASSERT(input_i < input_len)
size_t next_len = input_i - next_i_start + 1;
if (next_len > 0 && trim_elements) {
size_t trim_head = 0,
trim_tail = 0;
str_trim(list + next_i_start, next_len, &trim_head, &trim_tail);
next_i_start += trim_head;
next_len = trim_tail - trim_head;
}
if (next_len == 0 && !allow_empty_elements) {
RMW_CONNEXT_LOG_ERROR_A_SET("empty elements are not allowed: '%s'", list)
return RMW_RET_ERROR;
}
if (!DDS_StringSeq_ensure_length(
parsed_out, parsed_len + 1, parsed_len + 1))
{
RMW_CONNEXT_LOG_ERROR_SET("failed to resize string sequence")
return RMW_RET_ERROR;
}
char ** const el_ref = DDS_StringSeq_get_reference(parsed_out, parsed_len);
RMW_CONNEXT_ASSERT(nullptr != el_ref);
if (nullptr != *el_ref) {
DDS_String_free(*el_ref);
}
*el_ref = DDS_String_alloc(next_len);
if (nullptr == el_ref) {
RMW_CONNEXT_LOG_ERROR_SET("failed to allocate string")
return RMW_RET_ERROR;
}
if (next_len > 0) {
memcpy(*el_ref, list + next_i_start, next_len);
}
RMW_CONNEXT_LOG_TRACE_A(
"parsed list element: i=%d, el='%s'",
parsed_len, *el_ref)
// check if we have a trailing empty element
if (input_i + 2 == input_len) {
if (!allow_empty_elements) {
RMW_CONNEXT_LOG_ERROR_A_SET("empty elements are not allowed: '%s'", list)
return RMW_RET_ERROR;
}
}
}
return RMW_RET_OK;
}
bool
rmw_connextdds_find_string_in_list(
const DDS_StringSeq * const values,
const char * const value)
{
const DDS_Long values_len = DDS_StringSeq_get_length(values);
for (DDS_Long i = 0; i < values_len; i++) {
const char * const v_str =
*DDS_StringSeq_get_reference(values, i);
if (strcmp(v_str, value) == 0) {
return true;
}
}
return false;
}
/******************************************************************************
* Qos Helpers
******************************************************************************/
rmw_qos_policy_kind_t
dds_qos_policy_to_rmw_qos_policy(const DDS_QosPolicyId_t last_policy_id)
{
switch (last_policy_id) {
case DDS_DURABILITY_QOS_POLICY_ID:
return RMW_QOS_POLICY_DURABILITY;
case DDS_DEADLINE_QOS_POLICY_ID:
return RMW_QOS_POLICY_DEADLINE;
case DDS_LIVELINESS_QOS_POLICY_ID:
return RMW_QOS_POLICY_LIVELINESS;
case DDS_RELIABILITY_QOS_POLICY_ID:
return RMW_QOS_POLICY_RELIABILITY;
case DDS_HISTORY_QOS_POLICY_ID:
return RMW_QOS_POLICY_HISTORY;
case DDS_LIFESPAN_QOS_POLICY_ID:
return RMW_QOS_POLICY_LIFESPAN;
default:
break;
}
return RMW_QOS_POLICY_INVALID;
}
rmw_ret_t
rmw_connextdds_get_readerwriter_qos(
const bool writer_qos,
RMW_Connext_MessageTypeSupport * const type_support,
DDS_HistoryQosPolicy * const history,
DDS_ReliabilityQosPolicy * const reliability,
DDS_DurabilityQosPolicy * const durability,
DDS_DeadlineQosPolicy * const deadline,
DDS_LivelinessQosPolicy * const liveliness,
DDS_ResourceLimitsQosPolicy * const resource_limits,
DDS_PublishModeQosPolicy * const publish_mode,
DDS_LifespanQosPolicy * const lifespan,
const rmw_qos_profile_t * const qos_policies,
const rmw_publisher_options_t * const pub_options,
const rmw_subscription_options_t * const sub_options)
{
UNUSED_ARG(writer_qos);
UNUSED_ARG(type_support);
UNUSED_ARG(publish_mode);
UNUSED_ARG(resource_limits);
UNUSED_ARG(pub_options);
UNUSED_ARG(sub_options);
switch (qos_policies->history) {
case RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT:
{
break;
}
case RMW_QOS_POLICY_HISTORY_KEEP_LAST:
{
if (qos_policies->depth == RMW_QOS_POLICY_DEPTH_SYSTEM_DEFAULT) {
history->depth = 1;
history->kind = DDS_KEEP_LAST_HISTORY_QOS;
} else {
if (qos_policies->depth < 1 || qos_policies->depth > INT32_MAX) {
RMW_CONNEXT_LOG_ERROR_A_SET(
"unsupported history depth: %ld", qos_policies->depth)
return RMW_RET_ERROR;
}
history->depth = static_cast<DDS_Long>(qos_policies->depth);
history->kind = DDS_KEEP_LAST_HISTORY_QOS;
}
break;
}
case RMW_QOS_POLICY_HISTORY_KEEP_ALL:
{
history->kind = DDS_KEEP_ALL_HISTORY_QOS;
break;
}
// case RMW_QOS_POLICY_HISTORY_UNKNOWN:
default:
{
RMW_CONNEXT_LOG_ERROR_A_SET(
"unsupported history kind: %d", qos_policies->history)
return RMW_RET_ERROR;
}
}
RMW_CONNEXT_LOG_DEBUG_A(
"endpoint resource history: "
"kind=%d, "
"depth=%d",
history->kind,
history->depth);
reliability->max_blocking_time = DDS_DURATION_INFINITE;
switch (qos_policies->reliability) {
case RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT:
{
break;
}
case RMW_QOS_POLICY_RELIABILITY_RELIABLE:
{
reliability->kind = DDS_RELIABLE_RELIABILITY_QOS;
break;
}
case RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT:
{
reliability->kind = DDS_BEST_EFFORT_RELIABILITY_QOS;
break;
}
// case RMW_QOS_POLICY_RELIABILITY_UNKNOWN:
default:
{
RMW_CONNEXT_LOG_ERROR_A_SET(
"unsupported reliability kind: %d", qos_policies->reliability)
return RMW_RET_ERROR;
}
}
switch (qos_policies->durability) {
case RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT:
{
break;
}
case RMW_QOS_POLICY_DURABILITY_VOLATILE:
{
durability->kind = DDS_VOLATILE_DURABILITY_QOS;
break;
}
case RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL:
{
durability->kind = DDS_TRANSIENT_LOCAL_DURABILITY_QOS;
break;
}
// case RMW_QOS_POLICY_DURABILITY_UNKNOWN:
default:
{
RMW_CONNEXT_LOG_ERROR_A_SET(
"unsupported durability kind: %d", qos_policies->durability)
return RMW_RET_ERROR;
}
}
if (qos_policies->deadline.sec != 0 || qos_policies->deadline.nsec != 0) {
deadline->period.sec =
static_cast<DDS_Long>(qos_policies->deadline.sec);
deadline->period.nanosec =
static_cast<DDS_UnsignedLong>(qos_policies->deadline.nsec);
}
if (qos_policies->liveliness_lease_duration.sec != 0 ||
qos_policies->liveliness_lease_duration.nsec != 0)
{
liveliness->lease_duration.sec =
static_cast<DDS_Long>(qos_policies->liveliness_lease_duration.sec);
liveliness->lease_duration.nanosec =
static_cast<DDS_UnsignedLong>(
qos_policies->liveliness_lease_duration.nsec);
}
switch (qos_policies->liveliness) {
case RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT:
{
break;
}
case RMW_QOS_POLICY_LIVELINESS_AUTOMATIC:
{
liveliness->kind = DDS_AUTOMATIC_LIVELINESS_QOS;
break;
}
case RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC:
{
liveliness->kind = DDS_MANUAL_BY_TOPIC_LIVELINESS_QOS;
break;
}
// case RMW_QOS_POLICY_LIVELINESS_UNKNOWN:
default:
{
RMW_CONNEXT_LOG_ERROR_A_SET(
"unsupported liveliness kind: %d", qos_policies->liveliness)
return RMW_RET_ERROR;
}
}
if (nullptr != lifespan &&
(qos_policies->lifespan.sec != 0 || qos_policies->lifespan.nsec != 0))
{
#if RMW_CONNEXT_DDS_API == RMW_CONNEXT_DDS_API_PRO
lifespan->duration.sec = static_cast<DDS_Long>(qos_policies->lifespan.sec);
lifespan->duration.nanosec =
static_cast<DDS_UnsignedLong>(qos_policies->lifespan.nsec);
#else
RMW_CONNEXT_LOG_WARNING("lifespan qos policy not supported")
#endif /* RMW_CONNEXT_DDS_API == RMW_CONNEXT_DDS_API_PRO */
}
// Make sure that resource limits are consistent with history qos
// TODO(asorbini): do not overwrite if using non-default QoS
// if (history->kind == DDS_KEEP_LAST_HISTORY_QOS &&
// history->depth > 1 &&
// resource_limits->max_samples_per_instance == DDS_LENGTH_UNLIMITED)
// {
// resource_limits->max_samples_per_instance = history->depth;
// if (resource_limits->max_samples != DDS_LENGTH_UNLIMITED &&
// resource_limits->max_samples < resource_limits->max_samples_per_instance)
// {
// resource_limits->max_samples =
// resource_limits->max_samples_per_instance;
// }
// }
return RMW_RET_OK;
}
rmw_ret_t
rmw_connextdds_readerwriter_qos_to_ros(
const DDS_HistoryQosPolicy * const history,
const DDS_ReliabilityQosPolicy * const reliability,
const DDS_DurabilityQosPolicy * const durability,
const DDS_DeadlineQosPolicy * const deadline,
const DDS_LivelinessQosPolicy * const liveliness,
const DDS_LifespanQosPolicy * const lifespan,
rmw_qos_profile_t * const qos_policies)
{
if (nullptr != history) {
switch (history->kind) {
case DDS_KEEP_LAST_HISTORY_QOS:
{
qos_policies->history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
break;
}
case DDS_KEEP_ALL_HISTORY_QOS:
{
qos_policies->history = RMW_QOS_POLICY_HISTORY_KEEP_ALL;
break;
}
default:
{
RMW_CONNEXT_LOG_ERROR_A_SET(
"invalid DDS history kind: %d", history->kind)
return RMW_RET_ERROR;
}
}
qos_policies->depth = (uint32_t) history->depth;
}
switch (reliability->kind) {
case DDS_RELIABLE_RELIABILITY_QOS:
{
qos_policies->reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
break;
}
case DDS_BEST_EFFORT_RELIABILITY_QOS:
{
qos_policies->reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
break;
}
default:
{
RMW_CONNEXT_LOG_ERROR_A_SET(
"invalid DDS reliability kind: %d", reliability->kind)
return RMW_RET_ERROR;
}
}
switch (durability->kind) {
case DDS_VOLATILE_DURABILITY_QOS:
{
qos_policies->durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
break;
}
case DDS_TRANSIENT_LOCAL_DURABILITY_QOS:
{
qos_policies->durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
break;
}
default:
{
RMW_CONNEXT_LOG_ERROR_A_SET(
"invalid DDS durability kind: %d", durability->kind)
return RMW_RET_ERROR;
}
}
qos_policies->deadline.sec = deadline->period.sec;
qos_policies->deadline.nsec = deadline->period.nanosec;
qos_policies->liveliness_lease_duration.sec =
liveliness->lease_duration.sec;
qos_policies->liveliness_lease_duration.nsec =
liveliness->lease_duration.nanosec;
switch (liveliness->kind) {
case DDS_AUTOMATIC_LIVELINESS_QOS:
{
qos_policies->liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
break;
}
case DDS_MANUAL_BY_TOPIC_LIVELINESS_QOS:
{
qos_policies->liveliness = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC;
break;
}
default:
{
RMW_CONNEXT_LOG_ERROR_A_SET(
"invalid DDS liveliness kind: %d", liveliness->kind)
return RMW_RET_ERROR;
}
}
if (nullptr != lifespan) {
#if RMW_CONNEXT_DDS_API == RMW_CONNEXT_DDS_API_PRO
qos_policies->lifespan.sec = lifespan->duration.sec;
qos_policies->lifespan.nsec = lifespan->duration.nanosec;
#else
RMW_CONNEXT_LOG_WARNING("lifespan qos policy not supported")
#endif /* RMW_CONNEXT_DDS_API == RMW_CONNEXT_DDS_API_PRO */
}
return RMW_RET_OK;
}
rmw_ret_t
rmw_connextdds_datawriter_qos_to_ros(
DDS_DataWriterQos * const qos,
rmw_qos_profile_t * const qos_policies)
{
return rmw_connextdds_readerwriter_qos_to_ros(
&qos->history,
&qos->reliability,
&qos->durability,
&qos->deadline,
&qos->liveliness,
#if RMW_CONNEXT_DDS_API == RMW_CONNEXT_DDS_API_PRO
&qos->lifespan,
#elif RMW_CONNEXT_DDS_API == RMW_CONNEXT_DDS_API_MICRO
nullptr,
#endif /* RMW_CONNEXT_DDS_API == RMW_CONNEXT_DDS_API_PRO */
qos_policies);
}
rmw_ret_t
rmw_connextdds_datareader_qos_to_ros(
DDS_DataReaderQos * const qos,
rmw_qos_profile_t * const qos_policies)
{
return rmw_connextdds_readerwriter_qos_to_ros(
&qos->history,
&qos->reliability,
&qos->durability,
&qos->deadline,
&qos->liveliness,
nullptr /* Lifespan is a writer-only qos policy */,
qos_policies);
}
/******************************************************************************
* Node support
******************************************************************************/
RMW_Connext_Node *
RMW_Connext_Node::create(
rmw_context_impl_t * const ctx)
{
RMW_Connext_Node * node_impl =
new (std::nothrow) RMW_Connext_Node(ctx);
if (nullptr == node_impl) {
RMW_CONNEXT_LOG_ERROR_SET("failed to allocate node implementation")
return nullptr;
}
return node_impl;
}
rmw_ret_t
RMW_Connext_Node::finalize()
{
return RMW_RET_OK;
}
/******************************************************************************
* Publisher Implementation functions
******************************************************************************/
RMW_Connext_Publisher::RMW_Connext_Publisher(
rmw_context_impl_t * const ctx,
DDS_DataWriter * const dds_writer,
RMW_Connext_MessageTypeSupport * const type_support,
const bool created_topic)
: ctx(ctx),
dds_writer(dds_writer),
type_support(type_support),
created_topic(created_topic),
status_condition(dds_writer)
{
rmw_connextdds_get_entity_gid(this->dds_writer, this->ros_gid);
if (RMW_RET_OK != this->status_condition.install(this)) {
RMW_CONNEXT_LOG_ERROR("failed to install condition on writer")
throw std::runtime_error("failed to install condition on writer");
}
}
RMW_Connext_Publisher *
RMW_Connext_Publisher::create(
rmw_context_impl_t * const ctx,
DDS_DomainParticipant * const dp,
DDS_Publisher * const pub,
const rosidl_message_type_support_t * const type_supports,
const char * const topic_name,
const rmw_qos_profile_t * const qos_policies,
const rmw_publisher_options_t * const publisher_options,
const bool internal,
const RMW_Connext_MessageType msg_type,
const void * const intro_members,
const bool intro_members_cpp,
std::string * const type_name)
{
UNUSED_ARG(internal);
RMW_Connext_MessageTypeSupport * type_support =
RMW_Connext_MessageTypeSupport::register_type_support(
ctx,
type_supports,
dp,
msg_type,
intro_members,
intro_members_cpp,
type_name);
if (nullptr == type_support) {
RMW_CONNEXT_LOG_ERROR("failed to register type for writer")
return nullptr;
}
auto scope_exit_type_unregister = rcpputils::make_scope_exit(
[dp, type_support, ctx]()
{
if (RMW_RET_OK !=
RMW_Connext_MessageTypeSupport::unregister_type_support(
ctx, dp, type_support->type_name()))
{
RMW_CONNEXT_LOG_ERROR(
"failed to unregister type for writer")
}
delete type_support;
});
std::string fqtopic_name;
std::string prefix_rep(ROS_SERVICE_RESPONSE_PREFIX_STR "/");
std::string prefix_req(ROS_SERVICE_REQUESTER_PREFIX_STR "/");
std::string str_topic(topic_name);
if (str_topic.find(prefix_rep) == 0 || str_topic.find(prefix_req) == 0) {
fqtopic_name = str_topic;
} else {
fqtopic_name =
rmw_connextdds_create_topic_name(
ROS_TOPIC_PREFIX, topic_name, "", qos_policies);
}
DDS_Topic * topic = nullptr;
bool topic_created = false;
if (RMW_RET_OK !=
ctx->assert_topic(
dp,
fqtopic_name.c_str(),
type_support->type_name(),
internal,
&topic,
topic_created))
{
RMW_CONNEXT_LOG_ERROR_A(
"failed to assert topic: "
"name=%s, "
"type=%s",
fqtopic_name.c_str(),
type_support->type_name())
return nullptr;
}
auto scope_exit_topic_delete = rcpputils::make_scope_exit(
[topic_created, dp, topic]()
{
if (topic_created) {
if (DDS_RETCODE_OK !=
DDS_DomainParticipant_delete_topic(dp, topic))
{
RMW_CONNEXT_LOG_ERROR_SET(
"failed to delete writer's topic")
}
}
});
// The following initialization generates warnings when built
// with RTI Connext DDS Professional < 6 (e.g. 5.3.1), so use
// DDS_DataWriterQos_initialize() for older versions.
#if !RMW_CONNEXT_DDS_API_PRO_LEGACY
DDS_DataWriterQos dw_qos = DDS_DataWriterQos_INITIALIZER;
#else
DDS_DataWriterQos dw_qos;
if (DDS_RETCODE_OK != DDS_DataWriterQos_initialize(&dw_qos)) {
RMW_CONNEXT_LOG_ERROR_SET("failed to initialize datawriter qos")
return nullptr;
}
#endif /* !RMW_CONNEXT_DDS_API_PRO_LEGACY */
DDS_DataWriterQos * const dw_qos_ptr = &dw_qos;
auto scope_exit_dw_qos_delete =
rcpputils::make_scope_exit(
[dw_qos_ptr]()
{
if (DDS_RETCODE_OK != DDS_DataWriterQos_finalize(dw_qos_ptr)) {
RMW_CONNEXT_LOG_ERROR_SET("failed to finalize DataWriterQoS")
}
});
if (DDS_RETCODE_OK !=
DDS_Publisher_get_default_datawriter_qos_w_topic_name(pub, &dw_qos, fqtopic_name.c_str()))
{
RMW_CONNEXT_LOG_ERROR_SET("failed to get default writer QoS")
return nullptr;
}
DDS_DataWriter * const dds_writer =
rmw_connextdds_create_datawriter(
ctx,
dp,
pub,
qos_policies,
publisher_options,
internal,
type_support,
topic,
&dw_qos);
if (nullptr == dds_writer) {
RMW_CONNEXT_LOG_ERROR("failed to create DDS writer")
return nullptr;
}
auto scope_exit_dds_writer_delete =
rcpputils::make_scope_exit(
[pub, dds_writer]()
{
if (DDS_RETCODE_OK !=
DDS_Publisher_delete_datawriter(pub, dds_writer))
{
RMW_CONNEXT_LOG_ERROR_SET(
"failed to delete DDS DataWriter")
}
});
RMW_Connext_Publisher * rmw_pub_impl =
new (std::nothrow) RMW_Connext_Publisher(
ctx, dds_writer, type_support, topic_created);
if (nullptr == rmw_pub_impl) {
RMW_CONNEXT_LOG_ERROR_SET("failed to allocate RMW publisher")
return nullptr;
}
scope_exit_type_unregister.cancel();
scope_exit_topic_delete.cancel();
scope_exit_dds_writer_delete.cancel();
return rmw_pub_impl;
}
rmw_ret_t
RMW_Connext_Publisher::finalize()
{
RMW_CONNEXT_LOG_DEBUG_A(
"finalizing publisher: pub=%p, type=%s",
(void *)this, this->type_support->type_name())
// Make sure publisher's condition is detached from any waitset
this->status_condition.invalidate();
if (DDS_RETCODE_OK !=
DDS_Publisher_delete_datawriter(
this->dds_publisher(), this->dds_writer))
{
RMW_CONNEXT_LOG_ERROR_SET("failed to delete DDS DataWriter")
return RMW_RET_ERROR;
}
DDS_DomainParticipant * const participant = this->dds_participant();
if (this->created_topic) {
DDS_Topic * const topic = this->dds_topic();
RMW_CONNEXT_LOG_DEBUG_A(
"deleting topic: name=%s",
DDS_TopicDescription_get_name(
DDS_Topic_as_topicdescription(topic)))
DDS_ReturnCode_t rc =
DDS_DomainParticipant_delete_topic(participant, topic);
if (DDS_RETCODE_OK != rc) {
RMW_CONNEXT_LOG_ERROR_SET("failed to delete DDS Topic")
return RMW_RET_ERROR;
}
}
rmw_ret_t rc = RMW_Connext_MessageTypeSupport::unregister_type_support(
this->ctx, participant, this->type_support->type_name());
if (RMW_RET_OK != rc) {
return rc;
}
delete this->type_support;
this->type_support = nullptr;
return RMW_RET_OK;
}
#ifndef DDS_GUID_INITIALIZER
#define DDS_GUID_INITIALIZER DDS_GUID_DEFAULT
#endif /* DDS_GUID_INITIALIZER */
rmw_ret_t
RMW_Connext_Publisher::requestreply_header_to_dds(
const RMW_Connext_RequestReplyMessage * const rr_msg,
DDS_SampleIdentity_t * const sample_identity,
DDS_SampleIdentity_t * const related_sample_identity)
{
struct DDS_GUID_t src_guid = DDS_GUID_INITIALIZER;
struct DDS_SequenceNumber_t src_sn = DDS_SEQUENCE_NUMBER_UNKNOWN;
rmw_ret_t rc = RMW_RET_ERROR;
rc = rmw_connextdds_gid_to_guid(rr_msg->gid, src_guid);
if (RMW_RET_OK != rc) {
return rc;
}
rmw_connextdds_sn_ros_to_dds(rr_msg->sn, src_sn);
if (rr_msg->request) {
sample_identity->writer_guid = src_guid;
sample_identity->sequence_number = src_sn;
} else {
related_sample_identity->writer_guid = src_guid;
related_sample_identity->sequence_number = src_sn;
}
return RMW_RET_OK;
}
rmw_ret_t
RMW_Connext_Publisher::write(
const void * const ros_message,
const bool serialized,
int64_t * const sn_out)
{
RMW_Connext_Message user_msg;
user_msg.user_data = ros_message;
user_msg.serialized = serialized;
user_msg.type_support = this->type_support;
return rmw_connextdds_write_message(this, &user_msg, sn_out);
}
size_t
RMW_Connext_Publisher::subscriptions_count()
{
DDS_PublicationMatchedStatus status =
DDS_PublicationMatchedStatus_INITIALIZER;
if (DDS_RETCODE_OK !=
DDS_DataWriter_get_publication_matched_status(
this->dds_writer, &status))
{
RMW_CONNEXT_LOG_ERROR_SET(
"failed to get publication matched status")
return 0;
}
return status.current_count;
}
rmw_ret_t
RMW_Connext_Publisher::assert_liveliness()
{
if (DDS_RETCODE_OK !=
DDS_DataWriter_assert_liveliness(this->dds_writer))
{
RMW_CONNEXT_LOG_ERROR_SET(
"failed to assert writer liveliness")
return RMW_RET_ERROR;
}
return RMW_RET_OK;
}
rmw_ret_t
RMW_Connext_Publisher::qos(rmw_qos_profile_t * const qos)
{
// The following initialization generates warnings when built
// with RTI Connext DDS Professional < 6 (e.g. 5.3.1), so use
// DDS_DataWriterQos_initialize() for older versions.
#if !RMW_CONNEXT_DDS_API_PRO_LEGACY
DDS_DataWriterQos dw_qos = DDS_DataWriterQos_INITIALIZER;
#else
DDS_DataWriterQos dw_qos;
if (DDS_RETCODE_OK != DDS_DataWriterQos_initialize(&dw_qos)) {
RMW_CONNEXT_LOG_ERROR_SET("failed to initialize datawriter qos")
return RMW_RET_ERROR;
}
#endif /* !RMW_CONNEXT_DDS_API_PRO_LEGACY */
if (DDS_RETCODE_OK != DDS_DataWriter_get_qos(this->dds_writer, &dw_qos)) {
RMW_CONNEXT_LOG_ERROR_SET("failed to get DDS writer's qos")
return RMW_RET_ERROR;
}
rmw_ret_t rc = rmw_connextdds_datawriter_qos_to_ros(&dw_qos, qos);
DDS_DataWriterQos_finalize(&dw_qos);
return rc;
}
rmw_publisher_t *
rmw_connextdds_create_publisher(
rmw_context_impl_t * const ctx,
const rmw_node_t * const node,
DDS_DomainParticipant * const dp,
DDS_Publisher * const pub,
const rosidl_message_type_support_t * const type_supports,
const char * const topic_name,
const rmw_qos_profile_t * const qos_policies,
const rmw_publisher_options_t * const publisher_options,
const bool internal)
{
std::lock_guard<std::mutex> guard(ctx->endpoint_mutex);
RMW_Connext_Publisher * rmw_pub_impl =
RMW_Connext_Publisher::create(
ctx,
dp,
pub,
type_supports,
topic_name,
qos_policies,
publisher_options,
internal);
if (nullptr == rmw_pub_impl) {
RMW_CONNEXT_LOG_ERROR(
"failed to allocate RMW_Connext_Publisher")
return nullptr;
}
auto scope_exit_rmw_writer_impl_delete =
rcpputils::make_scope_exit(
[rmw_pub_impl]()
{
if (RMW_RET_OK != rmw_pub_impl->finalize()) {
RMW_CONNEXT_LOG_ERROR(
"failed to finalize RMW_Connext_Publisher")
}
delete rmw_pub_impl;
});
rmw_publisher_t * rmw_publisher = rmw_publisher_allocate();
if (nullptr == rmw_publisher) {
RMW_CONNEXT_LOG_ERROR_SET(
"failed to allocate RMW publisher")
return nullptr;
}
rmw_publisher->topic_name = nullptr;
auto scope_exit_rmw_writer_delete = rcpputils::make_scope_exit(
[rmw_publisher]() {