@@ -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
+ bool localhost_only)
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, localhost_only);
324
296
}
325
297
326
298
@@ -337,15 +309,6 @@ 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
- rmw_ret_t
343
- rmw_node_assert_liveliness (const rmw_node_t * node)
344
- {
345
- return rmw_api_connextdds_node_assert_liveliness (node);
346
- }
347
- #endif /* RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT */
348
-
349
312
/* ****************************************************************************
350
313
* Publication API
351
314
*****************************************************************************/
@@ -385,21 +348,11 @@ rmw_publish_loaned_message(
385
348
rmw_ret_t
386
349
rmw_init_publisher_allocation (
387
350
const rosidl_message_type_support_t * type_support,
388
- #if RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT
389
- const rosidl_message_bounds_t * message_bounds,
390
- #else
391
351
const rosidl_runtime_c__Sequence__bound * message_bounds,
392
- #endif /* RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT */
393
352
rmw_publisher_allocation_t * allocation)
394
353
{
395
354
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);
355
+ type_support, message_bounds, allocation);
403
356
}
404
357
405
358
@@ -416,19 +369,11 @@ rmw_create_publisher(
416
369
const rmw_node_t * node,
417
370
const rosidl_message_type_support_t * type_supports,
418
371
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
- )
372
+ const rmw_qos_profile_t * qos_policies,
373
+ const rmw_publisher_options_t * publisher_options)
425
374
{
426
375
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
- );
376
+ node, type_supports, topic_name, qos_policies, publisher_options);
432
377
}
433
378
434
379
@@ -518,21 +463,11 @@ rmw_destroy_publisher(
518
463
rmw_ret_t
519
464
rmw_get_serialized_message_size (
520
465
const rosidl_message_type_support_t * type_supports,
521
- #if RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT
522
- const rosidl_message_bounds_t * message_bounds,
523
- #else
524
466
const rosidl_runtime_c__Sequence__bound * message_bounds,
525
- #endif /* RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT */
526
467
size_t * size)
527
468
{
528
469
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);
470
+ type_supports, message_bounds, size);
536
471
}
537
472
538
473
@@ -564,21 +499,13 @@ rmw_deserialize(
564
499
rmw_ret_t
565
500
rmw_take_response (
566
501
const rmw_client_t * client,
567
- #if RMW_CONNEXT_HAVE_SERVICE_INFO
568
502
rmw_service_info_t * request_header,
569
- #else
570
- rmw_request_id_t * request_header,
571
- #endif /* RMW_CONNEXT_HAVE_SERVICE_INFO */
572
503
void * ros_response,
573
504
bool * taken)
574
505
{
575
506
return rmw_api_connextdds_take_response (
576
507
client,
577
- #if RMW_CONNEXT_HAVE_SERVICE_INFO
578
- request_header,
579
- #else
580
508
request_header,
581
- #endif /* RMW_CONNEXT_HAVE_SERVICE_INFO */
582
509
ros_response,
583
510
taken);
584
511
}
@@ -587,21 +514,13 @@ rmw_take_response(
587
514
rmw_ret_t
588
515
rmw_take_request (
589
516
const rmw_service_t * service,
590
- #if RMW_CONNEXT_HAVE_SERVICE_INFO
591
517
rmw_service_info_t * request_header,
592
- #else
593
- rmw_request_id_t * request_header,
594
- #endif /* RMW_CONNEXT_HAVE_SERVICE_INFO */
595
518
void * ros_request,
596
519
bool * taken)
597
520
{
598
521
return rmw_api_connextdds_take_request (
599
522
service,
600
- #if RMW_CONNEXT_HAVE_SERVICE_INFO
601
523
request_header,
602
- #else
603
- request_header,
604
- #endif /* RMW_CONNEXT_HAVE_SERVICE_INFO */
605
524
ros_request,
606
525
taken);
607
526
}
@@ -674,21 +593,11 @@ rmw_destroy_service(
674
593
rmw_ret_t
675
594
rmw_init_subscription_allocation (
676
595
const rosidl_message_type_support_t * type_support,
677
- #if RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT
678
- const rosidl_message_bounds_t * message_bounds,
679
- #else
680
596
const rosidl_runtime_c__Sequence__bound * message_bounds,
681
- #endif /* RMW_CONNEXT_RELEASE <= RMW_CONNEXT_RELEASE_ELOQUENT */
682
597
rmw_subscription_allocation_t * allocation)
683
598
{
684
599
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);
600
+ type_support, message_bounds, allocation);
692
601
}
693
602
694
603
@@ -706,21 +615,10 @@ rmw_create_subscription(
706
615
const rosidl_message_type_support_t * type_supports,
707
616
const char * topic_name,
708
617
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
- )
618
+ const rmw_subscription_options_t * subscription_options)
715
619
{
716
620
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
- );
621
+ node, type_supports, topic_name, qos_policies, subscription_options);
724
622
}
725
623
726
624
@@ -775,8 +673,6 @@ rmw_take_with_info(
775
673
subscription, ros_message, taken, message_info, allocation);
776
674
}
777
675
778
- #if RMW_CONNEXT_HAVE_TAKE_SEQ
779
-
780
676
rmw_ret_t
781
677
rmw_take_sequence (
782
678
const rmw_subscription_t * subscription,
@@ -791,9 +687,6 @@ rmw_take_sequence(
791
687
taken, allocation);
792
688
}
793
689
794
- #endif /* RMW_CONNEXT_HAVE_TAKE_SEQ */
795
-
796
-
797
690
rmw_ret_t
798
691
rmw_take_serialized_message (
799
692
const rmw_subscription_t * subscription,
@@ -910,25 +803,3 @@ rmw_wait(
910
803
return rmw_api_connextdds_wait (
911
804
subs, gcs, srvs, cls, evs, wait_set, wait_timeout);
912
805
}
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