@@ -287,40 +287,12 @@ rmw_node_t *
287
287
rmw_create_node (
288
288
rmw_context_t * context,
289
289
const char * name,
290
- const char * ns
291
- #if RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_DASHING
292
- ,
290
+ const char * ns,
293
291
size_t domain_id,
294
- const rmw_node_security_options_t * security_options
295
- #elif RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT
296
- ,
297
- size_t domain_id,
298
- const rmw_node_security_options_t * security_options,
299
- bool localhost_only
300
- #elif RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_FOXY
301
- ,
302
- size_t domain_id,
303
- bool localhost_only
304
- #endif /* RMW_CONNEXT_RELEASE */
305
- )
292
+ const rmw_node_security_options_t * security_options)
306
293
{
307
294
return rmw_api_connextdds_create_node (
308
- context, name, ns
309
- #if RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_DASHING
310
- ,
311
- domain_id,
312
- security_options
313
- #elif RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT
314
- ,
315
- domain_id,
316
- security_options,
317
- localhost_only
318
- #elif RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_FOXY
319
- ,
320
- domain_id,
321
- localhost_only
322
- #endif /* RMW_CONNEXT_RELEASE */
323
- );
295
+ context, name, ns, domain_id, security_options);
324
296
}
325
297
326
298
@@ -337,14 +309,11 @@ rmw_node_get_graph_guard_condition(const rmw_node_t * rmw_node)
337
309
return rmw_api_connextdds_node_get_graph_guard_condition (rmw_node);
338
310
}
339
311
340
- #if RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT
341
-
342
312
rmw_ret_t
343
313
rmw_node_assert_liveliness (const rmw_node_t * node)
344
314
{
345
315
return rmw_api_connextdds_node_assert_liveliness (node);
346
316
}
347
- #endif /* RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT */
348
317
349
318
/* ****************************************************************************
350
319
* Publication API
@@ -385,21 +354,11 @@ rmw_publish_loaned_message(
385
354
rmw_ret_t
386
355
rmw_init_publisher_allocation (
387
356
const rosidl_message_type_support_t * type_support,
388
- #if RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT
389
357
const rosidl_message_bounds_t * message_bounds,
390
- #else
391
- const rosidl_runtime_c__Sequence__bound * message_bounds,
392
- #endif /* RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT */
393
358
rmw_publisher_allocation_t * allocation)
394
359
{
395
360
return rmw_api_connextdds_init_publisher_allocation (
396
- type_support,
397
- #if RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT
398
- message_bounds,
399
- #else
400
- message_bounds,
401
- #endif /* RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT */
402
- allocation);
361
+ type_support, message_bounds, allocation);
403
362
}
404
363
405
364
@@ -416,19 +375,10 @@ rmw_create_publisher(
416
375
const rmw_node_t * node,
417
376
const rosidl_message_type_support_t * type_supports,
418
377
const char * topic_name,
419
- const rmw_qos_profile_t * qos_policies
420
- #if RMW_CONNEXT_HAVE_OPTIONS_PUBSUB
421
- ,
422
- const rmw_publisher_options_t * publisher_options
423
- #endif /* RMW_CONNEXT_HAVE_OPTIONS_PUBSUB */
424
- )
378
+ const rmw_qos_profile_t * qos_policies)
425
379
{
426
380
return rmw_api_connextdds_create_publisher (
427
- node, type_supports, topic_name, qos_policies
428
- #if RMW_CONNEXT_HAVE_OPTIONS_PUBSUB
429
- , publisher_options
430
- #endif /* RMW_CONNEXT_HAVE_OPTIONS_PUBSUB */
431
- );
381
+ node, type_supports, topic_name, qos_policies);
432
382
}
433
383
434
384
@@ -518,21 +468,11 @@ rmw_destroy_publisher(
518
468
rmw_ret_t
519
469
rmw_get_serialized_message_size (
520
470
const rosidl_message_type_support_t * type_supports,
521
- #if RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT
522
471
const rosidl_message_bounds_t * message_bounds,
523
- #else
524
- const rosidl_runtime_c__Sequence__bound * message_bounds,
525
- #endif /* RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT */
526
472
size_t * size)
527
473
{
528
474
return rmw_api_connextdds_get_serialized_message_size (
529
- type_supports,
530
- #if RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT
531
- message_bounds,
532
- #else
533
- message_bounds,
534
- #endif /* RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT */
535
- size);
475
+ type_supports, message_bounds, size);
536
476
}
537
477
538
478
@@ -564,21 +504,13 @@ rmw_deserialize(
564
504
rmw_ret_t
565
505
rmw_take_response (
566
506
const rmw_client_t * client,
567
- #if RMW_CONNEXT_HAVE_SERVICE_INFO
568
- rmw_service_info_t * request_header,
569
- #else
570
507
rmw_request_id_t * request_header,
571
- #endif /* RMW_CONNEXT_HAVE_SERVICE_INFO */
572
508
void * ros_response,
573
509
bool * taken)
574
510
{
575
511
return rmw_api_connextdds_take_response (
576
512
client,
577
- #if RMW_CONNEXT_HAVE_SERVICE_INFO
578
- request_header,
579
- #else
580
513
request_header,
581
- #endif /* RMW_CONNEXT_HAVE_SERVICE_INFO */
582
514
ros_response,
583
515
taken);
584
516
}
@@ -587,21 +519,13 @@ rmw_take_response(
587
519
rmw_ret_t
588
520
rmw_take_request (
589
521
const rmw_service_t * service,
590
- #if RMW_CONNEXT_HAVE_SERVICE_INFO
591
- rmw_service_info_t * request_header,
592
- #else
593
522
rmw_request_id_t * request_header,
594
- #endif /* RMW_CONNEXT_HAVE_SERVICE_INFO */
595
523
void * ros_request,
596
524
bool * taken)
597
525
{
598
526
return rmw_api_connextdds_take_request (
599
527
service,
600
- #if RMW_CONNEXT_HAVE_SERVICE_INFO
601
528
request_header,
602
- #else
603
- request_header,
604
- #endif /* RMW_CONNEXT_HAVE_SERVICE_INFO */
605
529
ros_request,
606
530
taken);
607
531
}
@@ -674,21 +598,11 @@ rmw_destroy_service(
674
598
rmw_ret_t
675
599
rmw_init_subscription_allocation (
676
600
const rosidl_message_type_support_t * type_support,
677
- #if RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT
678
601
const rosidl_message_bounds_t * message_bounds,
679
- #else
680
- const rosidl_runtime_c__Sequence__bound * message_bounds,
681
- #endif /* RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT */
682
602
rmw_subscription_allocation_t * allocation)
683
603
{
684
604
return rmw_api_connextdds_init_subscription_allocation (
685
- type_support,
686
- #if RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT
687
- message_bounds,
688
- #else
689
- message_bounds,
690
- #endif /* RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT */
691
- allocation);
605
+ type_support, message_bounds, allocation);
692
606
}
693
607
694
608
@@ -706,21 +620,10 @@ rmw_create_subscription(
706
620
const rosidl_message_type_support_t * type_supports,
707
621
const char * topic_name,
708
622
const rmw_qos_profile_t * qos_policies,
709
- #if RMW_CONNEXT_HAVE_OPTIONS_PUBSUB
710
- const rmw_subscription_options_t * subscription_options
711
- #else
712
- bool ignore_local_publications
713
- #endif /* RMW_CONNEXT_HAVE_OPTIONS_PUBSUB */
714
- )
623
+ bool ignore_local_publications)
715
624
{
716
625
return rmw_api_connextdds_create_subscription (
717
- node, type_supports, topic_name, qos_policies,
718
- #if RMW_CONNEXT_HAVE_OPTIONS_PUBSUB
719
- subscription_options
720
- #else
721
- ignore_local_publications
722
- #endif /* RMW_CONNEXT_HAVE_OPTIONS_PUBSUB */
723
- );
626
+ node, type_supports, topic_name, qos_policies, ignore_local_publications);
724
627
}
725
628
726
629
@@ -775,25 +678,6 @@ rmw_take_with_info(
775
678
subscription, ros_message, taken, message_info, allocation);
776
679
}
777
680
778
- #if RMW_CONNEXT_HAVE_TAKE_SEQ
779
-
780
- rmw_ret_t
781
- rmw_take_sequence (
782
- const rmw_subscription_t * subscription,
783
- size_t count,
784
- rmw_message_sequence_t * message_sequence,
785
- rmw_message_info_sequence_t * message_info_sequence,
786
- size_t * taken,
787
- rmw_subscription_allocation_t * allocation)
788
- {
789
- return rmw_api_connextdds_take_sequence (
790
- subscription, count, message_sequence, message_info_sequence,
791
- taken, allocation);
792
- }
793
-
794
- #endif /* RMW_CONNEXT_HAVE_TAKE_SEQ */
795
-
796
-
797
681
rmw_ret_t
798
682
rmw_take_serialized_message (
799
683
const rmw_subscription_t * subscription,
@@ -910,25 +794,3 @@ rmw_wait(
910
794
return rmw_api_connextdds_wait (
911
795
subs, gcs, srvs, cls, evs, wait_set, wait_timeout);
912
796
}
913
-
914
-
915
- /* *****************************************************************************
916
- * QoS Profile functions
917
- ******************************************************************************/
918
- #if RMW_CONNEXT_HAVE_QOS_PROFILE_API
919
- rmw_ret_t
920
- rmw_qos_profile_check_compatible (
921
- const rmw_qos_profile_t publisher_profile,
922
- const rmw_qos_profile_t subscription_profile,
923
- rmw_qos_compatibility_type_t * compatibility,
924
- char * reason,
925
- size_t reason_size)
926
- {
927
- return rmw_api_connextdds_qos_profile_check_compatible (
928
- publisher_profile,
929
- subscription_profile,
930
- compatibility,
931
- reason,
932
- reason_size);
933
- }
934
- #endif /* RMW_CONNEXT_HAVE_QOS_PROFILE_API */
0 commit comments