forked from ros2/rmw_zenoh
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathrmw_zenoh.cpp
More file actions
2742 lines (2487 loc) · 96.6 KB
/
rmw_zenoh.cpp
File metadata and controls
2742 lines (2487 loc) · 96.6 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
// Copyright 2023 Open Source Robotics Foundation, Inc.
//
// 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 <fastcdr/FastBuffer.h>
#include <rmw/get_topic_endpoint_info.h>
#include <chrono>
#include <cinttypes>
#include <cstring>
#include <memory>
#include <mutex>
#include <new>
#include <optional>
#include <string>
#include <utility>
#include <zenoh.hxx>
#include "detail/cdr.hpp"
#include "detail/guard_condition.hpp"
#include "detail/graph_cache.hpp"
#include "detail/identifier.hpp"
#include "detail/liveliness_utils.hpp"
#include "detail/logging_macros.hpp"
#include "detail/message_type_support.hpp"
#include "detail/qos.hpp"
#include "detail/rmw_context_impl_s.hpp"
#include "detail/serialization_format.hpp"
#include "detail/type_support_common.hpp"
#include "detail/zenoh_utils.hpp"
#include "rcpputils/scope_exit.hpp"
#include "rcutils/env.h"
#include "rcutils/strdup.h"
#include "rcutils/types.h"
#include "rmw/allocators.h"
#include "rmw/dynamic_message_type_support.h"
#include "rmw/error_handling.h"
#include "rmw/features.h"
#include "rmw/impl/cpp/macros.hpp"
#include "rmw/ret_types.h"
#include "rmw/rmw.h"
#include "rmw/validate_namespace.h"
#include "rmw/validate_node_name.h"
#include "tracetools/tracetools.h"
#include "rmw_zenoh_cpp/rmw_zenoh.hpp"
namespace
{
//==============================================================================
const rosidl_message_type_support_t * find_message_type_support(
const rosidl_message_type_support_t * type_supports)
{
const rosidl_message_type_support_t * type_support = get_message_typesupport_handle(
type_supports, RMW_ZENOH_CPP_TYPESUPPORT_C);
if (!type_support) {
rcutils_error_string_t prev_error_string = rcutils_get_error_string();
rcutils_reset_error();
type_support = get_message_typesupport_handle(type_supports, RMW_ZENOH_CPP_TYPESUPPORT_CPP);
if (!type_support) {
rcutils_error_string_t error_string = rcutils_get_error_string();
rcutils_reset_error();
RMW_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Type support not from this implementation. Got:\n"
" %s\n"
" %s\n"
"while fetching it",
prev_error_string.str, error_string.str);
return nullptr;
}
}
return type_support;
}
//==============================================================================
const rosidl_service_type_support_t * find_service_type_support(
const rosidl_service_type_support_t * type_supports)
{
const rosidl_service_type_support_t * type_support = get_service_typesupport_handle(
type_supports, RMW_ZENOH_CPP_TYPESUPPORT_C);
if (!type_support) {
rcutils_error_string_t prev_error_string = rcutils_get_error_string();
rcutils_reset_error();
type_support = get_service_typesupport_handle(
type_supports, RMW_ZENOH_CPP_TYPESUPPORT_CPP);
if (!type_support) {
rcutils_error_string_t error_string = rcutils_get_error_string();
rcutils_reset_error();
RMW_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Type support not from this implementation. Got:\n"
" %s\n"
" %s\n"
"while fetching it",
prev_error_string.str, error_string.str);
return nullptr;
}
}
return type_support;
}
} // namespace
extern "C"
{
//==============================================================================
/// Get the name of the rmw implementation being used
const char *
rmw_get_implementation_identifier(void)
{
return rmw_zenoh_cpp::rmw_zenoh_identifier;
}
//==============================================================================
/// Get the unique serialization format for this middleware.
const char *
rmw_get_serialization_format(void)
{
return rmw_zenoh_cpp::rmw_zenoh_serialization_format;
}
//==============================================================================
bool rmw_feature_supported(rmw_feature_t feature)
{
switch (feature) {
case RMW_FEATURE_MESSAGE_INFO_PUBLICATION_SEQUENCE_NUMBER:
return true;
case RMW_FEATURE_MESSAGE_INFO_RECEPTION_SEQUENCE_NUMBER:
return true;
case RMW_MIDDLEWARE_SUPPORTS_TYPE_DISCOVERY:
return true;
case RMW_MIDDLEWARE_CAN_TAKE_DYNAMIC_MESSAGE:
return false;
}
return false;
}
//==============================================================================
/// Create a node and return a handle to that node.
rmw_node_t *
rmw_create_node(
rmw_context_t * context,
const char * name,
const char * namespace_)
{
RMW_CHECK_ARGUMENT_FOR_NULL(context, nullptr);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
context,
context->implementation_identifier,
rmw_zenoh_cpp::rmw_zenoh_identifier,
return nullptr);
RMW_CHECK_FOR_NULL_WITH_MSG(
context->impl,
"expected initialized context",
return nullptr);
rmw_context_impl_t * context_impl = static_cast<rmw_context_impl_t *>(context->impl);
RMW_CHECK_FOR_NULL_WITH_MSG(
context_impl,
"expected initialized context_impl",
return nullptr);
if (context_impl->is_shutdown()) {
RCUTILS_SET_ERROR_MSG("context has been shutdown");
return nullptr;
}
int validation_result = RMW_NODE_NAME_VALID;
rmw_ret_t ret = rmw_validate_node_name(name, &validation_result, nullptr);
if (RMW_RET_OK != ret) {
return nullptr;
}
if (RMW_NODE_NAME_VALID != validation_result) {
const char * reason = rmw_node_name_validation_result_string(validation_result);
RMW_SET_ERROR_MSG_WITH_FORMAT_STRING("invalid node name: %s", reason);
return nullptr;
}
validation_result = RMW_NAMESPACE_VALID;
ret = rmw_validate_namespace(namespace_, &validation_result, nullptr);
if (RMW_RET_OK != ret) {
return nullptr;
}
if (RMW_NAMESPACE_VALID != validation_result) {
const char * reason = rmw_namespace_validation_result_string(validation_result);
RMW_SET_ERROR_MSG_WITH_FORMAT_STRING("invalid node namespace: %s", reason);
return nullptr;
}
rcutils_allocator_t * allocator = &context->options.allocator;
rmw_node_t * node =
static_cast<rmw_node_t *>(allocator->zero_allocate(1, sizeof(rmw_node_t), allocator->state));
RMW_CHECK_FOR_NULL_WITH_MSG(
node,
"unable to allocate memory for rmw_node_t",
return nullptr);
auto free_node = rcpputils::make_scope_exit(
[node, allocator]() {
allocator->deallocate(node, allocator->state);
});
node->name = rcutils_strdup(name, *allocator);
RMW_CHECK_FOR_NULL_WITH_MSG(
node->name,
"unable to allocate memory for node name",
return nullptr);
auto free_name = rcpputils::make_scope_exit(
[node, allocator]() {
allocator->deallocate(const_cast<char *>(node->name), allocator->state);
});
node->namespace_ = rcutils_strdup(namespace_, *allocator);
RMW_CHECK_FOR_NULL_WITH_MSG(
node->namespace_,
"unable to allocate memory for node namespace",
return nullptr);
auto free_namespace = rcpputils::make_scope_exit(
[node, allocator]() {
allocator->deallocate(const_cast<char *>(node->namespace_), allocator->state);
});
// Create the NodeData for this node.
if (!context_impl->create_node_data(node, namespace_, name)) {
// Error already set.
return nullptr;
}
node->implementation_identifier = rmw_zenoh_cpp::rmw_zenoh_identifier;
node->context = context;
// Store type erased rmw_context_impl_s in node->data so that the NodeData
// can be safely accessed.
node->data = context->impl;
free_namespace.cancel();
free_name.cancel();
free_node.cancel();
return node;
}
//==============================================================================
/// Finalize a given node handle, reclaim the resources, and deallocate the node handle.
rmw_ret_t
rmw_destroy_node(rmw_node_t * node)
{
RMW_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_ARGUMENT_FOR_NULL(node->context, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_ARGUMENT_FOR_NULL(node->context->impl, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_ARGUMENT_FOR_NULL(node->data, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
node,
node->implementation_identifier,
rmw_zenoh_cpp::rmw_zenoh_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
rcutils_allocator_t * allocator = &node->context->options.allocator;
// Undeclare liveliness token for the node to advertise that the node has ridden
// off into the sunset.
rmw_context_impl_s * context_impl =
static_cast<rmw_context_impl_s *>(node->data);
if (context_impl == nullptr) {
RMW_SET_ERROR_MSG("Unable to cast node->data into rmw_context_impl_s.");
return RMW_RET_ERROR;
}
context_impl->delete_node_data(node);
allocator->deallocate(const_cast<char *>(node->namespace_), allocator->state);
allocator->deallocate(const_cast<char *>(node->name), allocator->state);
allocator->deallocate(node, allocator->state);
return RMW_RET_OK;
}
//==============================================================================
/// Return a guard condition which is triggered when the ROS graph changes.
const rmw_guard_condition_t *
rmw_node_get_graph_guard_condition(const rmw_node_t * node)
{
RMW_CHECK_ARGUMENT_FOR_NULL(node, nullptr);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
node,
node->implementation_identifier,
rmw_zenoh_cpp::rmw_zenoh_identifier,
return nullptr);
RMW_CHECK_ARGUMENT_FOR_NULL(node->context, nullptr);
RMW_CHECK_ARGUMENT_FOR_NULL(node->context->impl, nullptr);
return node->context->impl->graph_guard_condition();
}
//==============================================================================
/// Initialize a publisher allocation to be used with later publications.
rmw_ret_t
rmw_init_publisher_allocation(
const rosidl_message_type_support_t * type_support,
const rosidl_runtime_c__Sequence__bound * message_bounds,
rmw_publisher_allocation_t * allocation)
{
static_cast<void>(type_support);
static_cast<void>(message_bounds);
static_cast<void>(allocation);
RMW_SET_ERROR_MSG("rmw_init_publisher_allocation: unimplemented");
return RMW_RET_UNSUPPORTED;
}
//==============================================================================
/// Destroy a publisher allocation object.
rmw_ret_t
rmw_fini_publisher_allocation(
rmw_publisher_allocation_t * allocation)
{
static_cast<void>(allocation);
RMW_SET_ERROR_MSG("rmw_fini_publisher_allocation: unimplemented");
return RMW_RET_UNSUPPORTED;
}
//==============================================================================
/// Create a publisher and return a handle to that publisher.
rmw_publisher_t *
rmw_create_publisher(
const rmw_node_t * node,
const rosidl_message_type_support_t * type_supports,
const char * topic_name,
const rmw_qos_profile_t * qos_profile,
const rmw_publisher_options_t * publisher_options)
{
RMW_CHECK_ARGUMENT_FOR_NULL(node, nullptr);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
node,
node->implementation_identifier,
rmw_zenoh_cpp::rmw_zenoh_identifier,
return nullptr);
RMW_CHECK_ARGUMENT_FOR_NULL(type_supports, nullptr);
RMW_CHECK_ARGUMENT_FOR_NULL(topic_name, nullptr);
if (topic_name[0] == '\0') {
RMW_SET_ERROR_MSG("topic_name argument is an empty string");
return nullptr;
}
RMW_CHECK_ARGUMENT_FOR_NULL(qos_profile, nullptr);
if (!qos_profile->avoid_ros_namespace_conventions) {
int validation_result = RMW_TOPIC_VALID;
rmw_ret_t ret = rmw_validate_full_topic_name(topic_name, &validation_result, nullptr);
if (RMW_RET_OK != ret) {
return nullptr;
}
if (RMW_TOPIC_VALID != validation_result) {
const char * reason = rmw_full_topic_name_validation_result_string(validation_result);
RMW_SET_ERROR_MSG_WITH_FORMAT_STRING("invalid topic name: %s", reason);
return nullptr;
}
}
RMW_CHECK_ARGUMENT_FOR_NULL(publisher_options, nullptr);
if (publisher_options->require_unique_network_flow_endpoints ==
RMW_UNIQUE_NETWORK_FLOW_ENDPOINTS_STRICTLY_REQUIRED)
{
RMW_SET_ERROR_MSG(
"Strict requirement on unique network flow endpoints for publishers not supported");
return nullptr;
}
// Get the RMW type support.
const rosidl_message_type_support_t * type_support = find_message_type_support(type_supports);
if (type_support == nullptr) {
// error was already set by find_message_type_support
return nullptr;
}
RMW_CHECK_FOR_NULL_WITH_MSG(
node->context,
"expected initialized context",
return nullptr);
RMW_CHECK_FOR_NULL_WITH_MSG(
node->context->impl,
"expected initialized context impl",
return nullptr);
rmw_context_impl_s * context_impl = static_cast<rmw_context_impl_s *>(
node->context->impl);
RMW_CHECK_FOR_NULL_WITH_MSG(
context_impl,
"unable to get rmw_context_impl_s",
return nullptr);
if (context_impl->is_shutdown()) {
RMW_SET_ERROR_MSG("context_impl is shutdown");
return nullptr;
}
if (!context_impl->session_is_valid()) {
RMW_SET_ERROR_MSG("zenoh session is invalid");
return nullptr;
}
rcutils_allocator_t * allocator = &node->context->options.allocator;
if (!rcutils_allocator_is_valid(allocator)) {
RMW_SET_ERROR_MSG("allocator is invalid.");
return nullptr;
}
// Create the rmw_publisher.
auto rmw_publisher =
static_cast<rmw_publisher_t *>(allocator->zero_allocate(
1, sizeof(rmw_publisher_t), allocator->state));
RMW_CHECK_FOR_NULL_WITH_MSG(
rmw_publisher,
"failed to allocate memory for the publisher",
return nullptr);
auto free_rmw_publisher = rcpputils::make_scope_exit(
[rmw_publisher, allocator]() {
allocator->deallocate(rmw_publisher, allocator->state);
});
auto node_data = context_impl->get_node_data(node);
RMW_CHECK_FOR_NULL_WITH_MSG(
node_data,
"NodeData not found.",
return nullptr);
if (!node_data->create_pub_data(
rmw_publisher,
context_impl->session(),
context_impl->get_next_entity_id(),
topic_name,
type_support,
qos_profile))
{
// Error already handled.
return nullptr;
}
// Store type erased node in rmw_publisher->data so that the
// PublisherData can be safely accessed.
rmw_publisher->data = reinterpret_cast<void *>(const_cast<rmw_node_t *>(node));
rmw_publisher->implementation_identifier = rmw_zenoh_cpp::rmw_zenoh_identifier;
rmw_publisher->options = *publisher_options;
rmw_publisher->can_loan_messages = false;
rmw_publisher->topic_name = rcutils_strdup(topic_name, *allocator);
RMW_CHECK_FOR_NULL_WITH_MSG(
rmw_publisher->topic_name,
"Failed to allocate topic name",
return nullptr);
auto free_topic_name = rcpputils::make_scope_exit(
[rmw_publisher, allocator]() {
allocator->deallocate(const_cast<char *>(rmw_publisher->topic_name), allocator->state);
});
free_topic_name.cancel();
free_rmw_publisher.cancel();
if (TRACETOOLS_TRACEPOINT_ENABLED(rmw_publisher_init)) {
rmw_gid_t gid{};
// Trigger tracepoint even if we cannot get the GID
rmw_ret_t gid_ret = rmw_get_gid_for_publisher(rmw_publisher, &gid);
static_cast<void>(gid_ret);
TRACETOOLS_DO_TRACEPOINT(
rmw_publisher_init, static_cast<const void *>(rmw_publisher), gid.data);
}
return rmw_publisher;
}
//==============================================================================
/// Finalize a given publisher handle, reclaim the resources, and deallocate the publisher handle.
rmw_ret_t
rmw_destroy_publisher(rmw_node_t * node, rmw_publisher_t * publisher)
{
RMW_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_ARGUMENT_FOR_NULL(node->context, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_ARGUMENT_FOR_NULL(node->context->impl, RMW_RET_INVALID_ARGUMENT);
rmw_context_impl_s * context_impl = static_cast<rmw_context_impl_s *>(node->context->impl);
RMW_CHECK_ARGUMENT_FOR_NULL(context_impl, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_ARGUMENT_FOR_NULL(publisher, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
node,
node->implementation_identifier,
rmw_zenoh_cpp::rmw_zenoh_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
publisher,
publisher->implementation_identifier,
rmw_zenoh_cpp::rmw_zenoh_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
auto node_data = context_impl->get_node_data(node);
if (node_data == nullptr) {
return RMW_RET_INVALID_ARGUMENT;
}
auto pub_data = node_data->get_pub_data(publisher);
if (pub_data == nullptr) {
return RMW_RET_INVALID_ARGUMENT;
}
// Remove any event callbacks registered to this publisher.
context_impl->graph_cache()->remove_qos_event_callbacks(pub_data->gid_hash());
// Remove the PublisherData from NodeData.
node_data->delete_pub_data(publisher);
rcutils_allocator_t * allocator = &node->context->options.allocator;
allocator->deallocate(const_cast<char *>(publisher->topic_name), allocator->state);
allocator->deallocate(publisher, allocator->state);
return RMW_RET_OK;
}
//==============================================================================
rmw_ret_t
rmw_take_dynamic_message(
const rmw_subscription_t * subscription,
rosidl_dynamic_typesupport_dynamic_data_t * dynamic_message,
bool * taken,
rmw_subscription_allocation_t * allocation)
{
static_cast<void>(subscription);
static_cast<void>(dynamic_message);
static_cast<void>(taken);
static_cast<void>(allocation);
return RMW_RET_UNSUPPORTED;
}
//==============================================================================
rmw_ret_t
rmw_take_dynamic_message_with_info(
const rmw_subscription_t * subscription,
rosidl_dynamic_typesupport_dynamic_data_t * dynamic_message,
bool * taken,
rmw_message_info_t * message_info,
rmw_subscription_allocation_t * allocation)
{
static_cast<void>(subscription);
static_cast<void>(dynamic_message);
static_cast<void>(taken);
static_cast<void>(message_info);
static_cast<void>(allocation);
return RMW_RET_UNSUPPORTED;
}
//==============================================================================
rmw_ret_t
rmw_serialization_support_init(
const char * serialization_lib_name,
rcutils_allocator_t * allocator,
rosidl_dynamic_typesupport_serialization_support_t * serialization_support)
{
static_cast<void>(serialization_lib_name);
static_cast<void>(allocator);
static_cast<void>(serialization_support);
return RMW_RET_UNSUPPORTED;
}
//==============================================================================
/// Borrow a loaned ROS message.
rmw_ret_t
rmw_borrow_loaned_message(
const rmw_publisher_t * publisher,
const rosidl_message_type_support_t * type_support,
void ** ros_message)
{
static_cast<void>(publisher);
static_cast<void>(type_support);
static_cast<void>(ros_message);
return RMW_RET_UNSUPPORTED;
}
//==============================================================================
/// Return a loaned message previously borrowed from a publisher.
rmw_ret_t
rmw_return_loaned_message_from_publisher(
const rmw_publisher_t * publisher,
void * loaned_message)
{
static_cast<void>(publisher);
static_cast<void>(loaned_message);
return RMW_RET_UNSUPPORTED;
}
//==============================================================================
/// Publish a ROS message.
rmw_ret_t
rmw_publish(
const rmw_publisher_t * publisher,
const void * ros_message,
rmw_publisher_allocation_t * allocation)
{
static_cast<void>(allocation);
RMW_CHECK_FOR_NULL_WITH_MSG(
publisher, "publisher handle is null",
return RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
publisher, publisher->implementation_identifier, rmw_zenoh_cpp::rmw_zenoh_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
RMW_CHECK_FOR_NULL_WITH_MSG(
ros_message, "ros message handle is null",
return RMW_RET_INVALID_ARGUMENT);
rmw_node_t * rmw_node = static_cast<rmw_node_t *>(publisher->data);
RMW_CHECK_FOR_NULL_WITH_MSG(
rmw_node, "publisher_data is null",
return RMW_RET_INVALID_ARGUMENT);
rmw_context_impl_s * context_impl = static_cast<rmw_context_impl_s *>(rmw_node->context->impl);
RMW_CHECK_FOR_NULL_WITH_MSG(
context_impl, "context_impl is null",
return RMW_RET_INVALID_ARGUMENT);
auto node_data = context_impl->get_node_data(rmw_node);
if (node_data == nullptr) {
return RMW_RET_INVALID_ARGUMENT;
}
auto pub_data = node_data->get_pub_data(publisher);
if (pub_data == nullptr) {
return RMW_RET_INVALID_ARGUMENT;
}
return pub_data->publish(
ros_message,
context_impl->shm().get()
);
}
//==============================================================================
/// Publish a loaned ROS message.
rmw_ret_t
rmw_publish_loaned_message(
const rmw_publisher_t * publisher,
void * ros_message,
rmw_publisher_allocation_t * allocation)
{
static_cast<void>(publisher);
static_cast<void>(ros_message);
static_cast<void>(allocation);
return RMW_RET_UNSUPPORTED;
}
//==============================================================================
/// Retrieve the number of matched subscriptions to a publisher.
rmw_ret_t
rmw_publisher_count_matched_subscriptions(
const rmw_publisher_t * publisher,
size_t * subscription_count)
{
RMW_CHECK_ARGUMENT_FOR_NULL(publisher, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_ARGUMENT_FOR_NULL(publisher->data, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
publisher,
publisher->implementation_identifier,
rmw_zenoh_cpp::rmw_zenoh_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
RMW_CHECK_ARGUMENT_FOR_NULL(subscription_count, RMW_RET_INVALID_ARGUMENT);
rmw_node_t * node =
static_cast<rmw_node_t *>(publisher->data);
RMW_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_INVALID_ARGUMENT);
rmw_context_impl_s * context_impl =
static_cast<rmw_context_impl_s *>(node->context->impl);
RMW_CHECK_ARGUMENT_FOR_NULL(context_impl, RMW_RET_INVALID_ARGUMENT);
auto node_data = context_impl->get_node_data(node);
RMW_CHECK_ARGUMENT_FOR_NULL(node_data, RMW_RET_INVALID_ARGUMENT);
auto pub_data = node_data->get_pub_data(publisher);
RMW_CHECK_ARGUMENT_FOR_NULL(pub_data, RMW_RET_INVALID_ARGUMENT);
return context_impl->graph_cache()->publisher_count_matched_subscriptions(
pub_data->topic_info(), subscription_count);
}
//==============================================================================
/// Retrieve the actual qos settings of the publisher.
rmw_ret_t
rmw_publisher_get_actual_qos(
const rmw_publisher_t * publisher,
rmw_qos_profile_t * qos)
{
RMW_CHECK_ARGUMENT_FOR_NULL(publisher, RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
publisher,
publisher->implementation_identifier,
rmw_zenoh_cpp::rmw_zenoh_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
RMW_CHECK_ARGUMENT_FOR_NULL(qos, RMW_RET_INVALID_ARGUMENT);
rmw_node_t * node =
static_cast<rmw_node_t *>(publisher->data);
RMW_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_INVALID_ARGUMENT);
rmw_context_impl_s * context_impl =
static_cast<rmw_context_impl_s *>(node->context->impl);
RMW_CHECK_ARGUMENT_FOR_NULL(context_impl, RMW_RET_INVALID_ARGUMENT);
auto node_data = context_impl->get_node_data(node);
RMW_CHECK_ARGUMENT_FOR_NULL(node_data, RMW_RET_INVALID_ARGUMENT);
auto pub_data = node_data->get_pub_data(publisher);
RMW_CHECK_ARGUMENT_FOR_NULL(pub_data, RMW_RET_INVALID_ARGUMENT);
*qos = pub_data->topic_info().qos_;
return RMW_RET_OK;
}
//==============================================================================
/// Publish a ROS message as a byte stream.
rmw_ret_t
rmw_publish_serialized_message(
const rmw_publisher_t * publisher,
const rmw_serialized_message_t * serialized_message,
rmw_publisher_allocation_t * allocation)
{
static_cast<void>(allocation);
RMW_CHECK_FOR_NULL_WITH_MSG(
publisher, "publisher handle is null",
return RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
publisher, publisher->implementation_identifier, rmw_zenoh_cpp::rmw_zenoh_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
RMW_CHECK_FOR_NULL_WITH_MSG(
serialized_message, "serialized message handle is null",
return RMW_RET_INVALID_ARGUMENT);
rmw_node_t * node =
static_cast<rmw_node_t *>(publisher->data);
RMW_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_INVALID_ARGUMENT);
rmw_context_impl_s * context_impl =
static_cast<rmw_context_impl_s *>(node->context->impl);
RMW_CHECK_ARGUMENT_FOR_NULL(context_impl, RMW_RET_INVALID_ARGUMENT);
auto node_data = context_impl->get_node_data(node);
RMW_CHECK_ARGUMENT_FOR_NULL(node_data, RMW_RET_INVALID_ARGUMENT);
auto publisher_data = node_data->get_pub_data(publisher);
RMW_CHECK_ARGUMENT_FOR_NULL(publisher_data, RMW_RET_INVALID_ARGUMENT);
return publisher_data->publish_serialized_message(
serialized_message,
context_impl->shm().get()
);
}
//==============================================================================
/// Compute the size of a serialized message.
rmw_ret_t
rmw_get_serialized_message_size(
const rosidl_message_type_support_t * type_support,
const rosidl_runtime_c__Sequence__bound * message_bounds,
size_t * size)
{
static_cast<void>(type_support);
static_cast<void>(message_bounds);
static_cast<void>(size);
return RMW_RET_UNSUPPORTED;
}
//==============================================================================
/// Manually assert that this Publisher is alive (for RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC)
rmw_ret_t
rmw_publisher_assert_liveliness(const rmw_publisher_t * publisher)
{
RMW_CHECK_FOR_NULL_WITH_MSG(
publisher, "publisher handle is null",
return RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_FOR_NULL_WITH_MSG(
publisher->data, "publisher data is null",
return RMW_RET_INVALID_ARGUMENT);
rmw_node_t * node =
static_cast<rmw_node_t *>(publisher->data);
RMW_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_INVALID_ARGUMENT);
rmw_context_impl_s * context_impl =
static_cast<rmw_context_impl_s *>(node->context->impl);
RMW_CHECK_ARGUMENT_FOR_NULL(context_impl, RMW_RET_INVALID_ARGUMENT);
auto node_data = context_impl->get_node_data(node);
RMW_CHECK_ARGUMENT_FOR_NULL(node_data, RMW_RET_INVALID_ARGUMENT);
auto pub_data = node_data->get_pub_data(publisher);
RMW_CHECK_ARGUMENT_FOR_NULL(pub_data, RMW_RET_INVALID_ARGUMENT);
if (!pub_data->liveliness_is_valid()) {
return RMW_RET_ERROR;
}
return RMW_RET_OK;
}
//==============================================================================
/// Wait until all published message data is acknowledged or until the specified timeout elapses.
rmw_ret_t
rmw_publisher_wait_for_all_acked(
const rmw_publisher_t * publisher,
rmw_time_t wait_timeout)
{
RMW_CHECK_FOR_NULL_WITH_MSG(
publisher, "publisher handle is null",
return RMW_RET_INVALID_ARGUMENT);
static_cast<void>(publisher);
static_cast<void>(wait_timeout);
// We are not currently tracking all published data, so we don't know what data is in flight that
// we might have to wait for. Even if we did start tracking it, we don't have insight into the
// TCP stream that Zenoh is managing for us, so we couldn't guarantee this anyway.
// Just lie to the upper layers and say that everything is working as expected.
// We return OK rather than UNSUPPORTED so that certain upper-layer tests continue working.
return RMW_RET_OK;
}
//==============================================================================
/// Serialize a ROS message into a rmw_serialized_message_t.
rmw_ret_t
rmw_serialize(
const void * ros_message,
const rosidl_message_type_support_t * type_support,
rmw_serialized_message_t * serialized_message)
{
const rosidl_message_type_support_t * ts = find_message_type_support(type_support);
if (ts == nullptr) {
// error was already set by find_message_type_support
return RMW_RET_ERROR;
}
auto callbacks = static_cast<const message_type_support_callbacks_t *>(ts->data);
auto tss = rmw_zenoh_cpp::MessageTypeSupport(callbacks);
auto data_length = tss.get_estimated_serialized_size(ros_message, callbacks);
if (serialized_message->buffer_capacity < data_length) {
if (rmw_serialized_message_resize(serialized_message, data_length) != RMW_RET_OK) {
rmw_reset_error();
RMW_SET_ERROR_MSG("unable to dynamically resize serialized message");
return RMW_RET_ERROR;
}
}
eprosima::fastcdr::FastBuffer buffer(
reinterpret_cast<char *>(serialized_message->buffer), data_length);
rmw_zenoh_cpp::Cdr ser(buffer);
auto ret = tss.serialize_ros_message(ros_message, ser.get_cdr(), callbacks);
serialized_message->buffer_length = data_length;
serialized_message->buffer_capacity = data_length;
return ret == true ? RMW_RET_OK : RMW_RET_ERROR;
}
//==============================================================================
/// Deserialize a ROS message.
rmw_ret_t
rmw_deserialize(
const rmw_serialized_message_t * serialized_message,
const rosidl_message_type_support_t * type_support,
void * ros_message)
{
const rosidl_message_type_support_t * ts = find_message_type_support(type_support);
if (ts == nullptr) {
// error was already set by find_message_type_support
return RMW_RET_ERROR;
}
auto callbacks = static_cast<const message_type_support_callbacks_t *>(ts->data);
auto tss = rmw_zenoh_cpp::MessageTypeSupport(callbacks);
eprosima::fastcdr::FastBuffer buffer(
reinterpret_cast<char *>(serialized_message->buffer), serialized_message->buffer_length);
rmw_zenoh_cpp::Cdr deser(buffer);
auto ret = tss.deserialize_ros_message(deser.get_cdr(), ros_message, callbacks);
return ret == true ? RMW_RET_OK : RMW_RET_ERROR;
}
//==============================================================================
/// Initialize a subscription allocation to be used with later `take`s.
rmw_ret_t
rmw_init_subscription_allocation(
const rosidl_message_type_support_t * type_support,
const rosidl_runtime_c__Sequence__bound * message_bounds,
rmw_subscription_allocation_t * allocation)
{
// Unused in current implementation.
static_cast<void>(type_support);
static_cast<void>(message_bounds);
static_cast<void>(allocation);
return RMW_RET_UNSUPPORTED;
}
//==============================================================================
/// Destroy a publisher allocation object.
rmw_ret_t
rmw_fini_subscription_allocation(
rmw_subscription_allocation_t * allocation)
{
static_cast<void>(allocation);
return RMW_RET_UNSUPPORTED;
}
//==============================================================================
/// Create a subscription and return a handle to that subscription.
rmw_subscription_t *
rmw_create_subscription(
const rmw_node_t * node,
const rosidl_message_type_support_t * type_supports,
const char * topic_name,
const rmw_qos_profile_t * qos_profile,
const rmw_subscription_options_t * subscription_options)
{
RMW_CHECK_ARGUMENT_FOR_NULL(node, nullptr);
RMW_CHECK_ARGUMENT_FOR_NULL(node->data, nullptr);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
node,
node->implementation_identifier,
rmw_zenoh_cpp::rmw_zenoh_identifier,
return nullptr);
RMW_CHECK_ARGUMENT_FOR_NULL(type_supports, nullptr);
RMW_CHECK_ARGUMENT_FOR_NULL(topic_name, nullptr);
if (topic_name[0] == '\0') {
RMW_SET_ERROR_MSG("topic_name argument is an empty string");
return nullptr;
}
RMW_CHECK_ARGUMENT_FOR_NULL(qos_profile, nullptr);
if (!qos_profile->avoid_ros_namespace_conventions) {
int validation_result = RMW_TOPIC_VALID;
rmw_ret_t ret = rmw_validate_full_topic_name(topic_name, &validation_result, nullptr);
if (RMW_RET_OK != ret) {
return nullptr;
}
if (RMW_TOPIC_VALID != validation_result) {
const char * reason = rmw_full_topic_name_validation_result_string(validation_result);
RMW_SET_ERROR_MSG_WITH_FORMAT_STRING("invalid topic name: %s", reason);
return nullptr;
}
}
RMW_CHECK_ARGUMENT_FOR_NULL(subscription_options, nullptr);
if (subscription_options->require_unique_network_flow_endpoints ==
RMW_UNIQUE_NETWORK_FLOW_ENDPOINTS_STRICTLY_REQUIRED)
{
RMW_SET_ERROR_MSG(
"Strict requirement on unique network flow endpoints for subscriptions not supported");
return nullptr;
}
const rosidl_message_type_support_t * type_support = find_message_type_support(type_supports);
if (type_support == nullptr) {
// error was already set by find_message_type_support
return nullptr;
}
RMW_CHECK_FOR_NULL_WITH_MSG(
node->context,
"expected initialized context",
return nullptr);
RMW_CHECK_FOR_NULL_WITH_MSG(
node->context->impl,
"expected initialized context impl",
return nullptr);
rmw_context_impl_s * context_impl = static_cast<rmw_context_impl_s *>(
node->context->impl);
RMW_CHECK_FOR_NULL_WITH_MSG(
context_impl,
"unable to get rmw_context_impl_s",
return nullptr);
if (context_impl->is_shutdown()) {
RMW_SET_ERROR_MSG("context_impl is shutdown");
return nullptr;
}
if (!context_impl->session_is_valid()) {
RMW_SET_ERROR_MSG("zenoh session is invalid");
return nullptr;
}
rcutils_allocator_t * allocator = &node->context->options.allocator;
if (!rcutils_allocator_is_valid(allocator)) {
RMW_SET_ERROR_MSG("allocator is invalid.");
return nullptr;
}
// Create the rmw_subscription.
rmw_subscription_t * rmw_subscription =
static_cast<rmw_subscription_t *>(allocator->zero_allocate(
1, sizeof(rmw_subscription_t), allocator->state));
RMW_CHECK_FOR_NULL_WITH_MSG(
rmw_subscription,
"failed to allocate memory for the subscription",
return nullptr);
auto free_rmw_subscription = rcpputils::make_scope_exit(
[rmw_subscription, allocator]() {
allocator->deallocate(rmw_subscription, allocator->state);
});
auto node_data = context_impl->get_node_data(node);
RMW_CHECK_FOR_NULL_WITH_MSG(
node_data,
"NodeData not found.",
return nullptr);
if (!node_data->create_sub_data(
rmw_subscription,
context_impl->session(),
context_impl->graph_cache(),
context_impl->get_next_entity_id(),
topic_name,
type_support,
qos_profile,
*subscription_options))
{
// Error already handled.
return nullptr;
}
// TODO(Yadunund): We cannot store the rmw_node_t * here since this type erased
// subscription handle will be returned in the rmw_subscriptions_t in rmw_wait
// from which we cannot obtain SubscriptionData.
rmw_subscription->data = static_cast<void *>(node_data->get_sub_data(rmw_subscription).get());
rmw_subscription->implementation_identifier = rmw_zenoh_cpp::rmw_zenoh_identifier;