@@ -123,6 +123,7 @@ class IntraProcessBuffer : public IntraProcessBufferBase
123123 return result;
124124 }
125125
126+ private:
126127 // need to store the messages somewhere otherwise the memory address will be reused
127128 ConstMessageSharedPtr shared_msg;
128129 MessageUniquePtr unique_msg;
@@ -158,9 +159,9 @@ class PublisherBase
158159public:
159160 RCLCPP_SMART_PTR_DEFINITIONS (PublisherBase)
160161
161- explicit PublisherBase (rclcpp::QoS qos = rclcpp::QoS( 10 ) )
162- : qos_profile(qos ),
163- topic_name( " topic " )
162+ explicit PublisherBase (const std::string & topic, const rclcpp::QoS & qos )
163+ : topic_name(topic ),
164+ qos_profile(qos )
164165 {}
165166
166167 virtual ~PublisherBase ()
@@ -205,10 +206,12 @@ class PublisherBase
205206 return false ;
206207 }
207208
208- rclcpp::QoS qos_profile;
209- std::string topic_name;
210209 uint64_t intra_process_publisher_id_;
211210 IntraProcessManagerWeakPtr weak_ipm_;
211+
212+ private:
213+ std::string topic_name;
214+ rclcpp::QoS qos_profile;
212215};
213216
214217template <typename T, typename Alloc = std::allocator<void >>
@@ -223,8 +226,8 @@ class Publisher : public PublisherBase
223226
224227 RCLCPP_SMART_PTR_DEFINITIONS (Publisher<T, Alloc>)
225228
226- explicit Publisher (rclcpp::QoS qos = rclcpp::QoS( 10 ) )
227- : PublisherBase(qos)
229+ explicit Publisher (const std::string & topic, const rclcpp::QoS & qos )
230+ : PublisherBase(topic, qos)
228231 {
229232 auto allocator = std::make_shared<Alloc>();
230233 message_allocator_ = std::make_shared<MessageAlloc>(*allocator.get ());
@@ -258,9 +261,9 @@ class SubscriptionIntraProcessBase
258261
259262 explicit SubscriptionIntraProcessBase (
260263 rclcpp::Context::SharedPtr context,
261- const std::string & topic = " topic " ,
262- rclcpp::QoS qos = rclcpp::QoS( 10 ) )
263- : qos_profile(qos ), topic_name(topic )
264+ const std::string & topic,
265+ const rclcpp::QoS & qos )
266+ : topic_name(topic ), qos_profile(qos )
264267 {
265268 (void )context;
266269 }
@@ -292,8 +295,8 @@ class SubscriptionIntraProcessBase
292295 size_t
293296 available_capacity () const = 0 ;
294297
295- rclcpp::QoS qos_profile;
296298 std::string topic_name;
299+ rclcpp::QoS qos_profile;
297300};
298301
299302template <
@@ -307,8 +310,8 @@ class SubscriptionIntraProcessBuffer : public SubscriptionIntraProcessBase
307310public:
308311 RCLCPP_SMART_PTR_DEFINITIONS (SubscriptionIntraProcessBuffer)
309312
310- explicit SubscriptionIntraProcessBuffer (rclcpp::QoS qos)
311- : SubscriptionIntraProcessBase(nullptr , " topic" , qos), take_shared_method(false )
313+ explicit SubscriptionIntraProcessBuffer (const std::string & topic, const rclcpp::QoS & qos)
314+ : SubscriptionIntraProcessBase(nullptr , topic, qos), take_shared_method(false )
312315 {
313316 buffer = std::make_unique<rclcpp::experimental::buffers::mock::IntraProcessBuffer<MessageT>>();
314317 }
@@ -375,8 +378,8 @@ class SubscriptionIntraProcess : public SubscriptionIntraProcessBuffer<
375378public:
376379 RCLCPP_SMART_PTR_DEFINITIONS (SubscriptionIntraProcess)
377380
378- explicit SubscriptionIntraProcess (rclcpp::QoS qos = rclcpp::QoS( 10 ) )
379- : SubscriptionIntraProcessBuffer<MessageT, Alloc, Deleter>(qos)
381+ explicit SubscriptionIntraProcess (const std::string & topic, const rclcpp::QoS & qos )
382+ : SubscriptionIntraProcessBuffer<MessageT, Alloc, Deleter>(topic, qos)
380383 {
381384 }
382385};
@@ -466,12 +469,11 @@ TEST(TestIntraProcessManager, add_pub_sub) {
466469
467470 auto ipm = std::make_shared<IntraProcessManagerT>();
468471
469- auto p1 = std::make_shared<PublisherT>(rclcpp::QoS (10 ).best_effort ());
472+ auto p1 = std::make_shared<PublisherT>(" topic " , rclcpp::QoS (10 ).best_effort ());
470473
471- auto p2 = std::make_shared<PublisherT>(rclcpp::QoS (10 ).best_effort ());
472- p2->topic_name = " different_topic_name" ;
474+ auto p2 = std::make_shared<PublisherT>(" different_topic_name" , rclcpp::QoS (10 ).best_effort ());
473475
474- auto s1 = std::make_shared<SubscriptionIntraProcessT>(rclcpp::QoS (10 ).best_effort ());
476+ auto s1 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS (10 ).best_effort ());
475477
476478 auto p1_id = ipm->add_publisher (p1);
477479 auto p2_id = ipm->add_publisher (p2);
@@ -480,24 +482,42 @@ TEST(TestIntraProcessManager, add_pub_sub) {
480482 bool unique_ids = p1_id != p2_id && p2_id != s1_id;
481483 ASSERT_TRUE (unique_ids);
482484
485+ // p1 has 1 subcription, s1
483486 size_t p1_subs = ipm->get_subscription_count (p1_id);
487+ // p2 has 0 subscriptions
484488 size_t p2_subs = ipm->get_subscription_count (p2_id);
489+ // Non-existent publisher_id has 0 subscriptions
485490 size_t non_existing_pub_subs = ipm->get_subscription_count (42 );
486491 ASSERT_EQ (1u , p1_subs);
487492 ASSERT_EQ (0u , p2_subs);
488493 ASSERT_EQ (0u , non_existing_pub_subs);
489494
490- auto p3 = std::make_shared<PublisherT>(rclcpp::QoS (10 ).reliable ());
495+ auto p3 = std::make_shared<PublisherT>(" topic " , rclcpp::QoS (10 ).reliable ());
491496
492- auto s2 = std::make_shared<SubscriptionIntraProcessT>(rclcpp::QoS (10 ).reliable ());
497+ auto s2 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS (10 ).reliable ());
493498
499+ // s2 may be able to communicate with p1 depending on the RMW
494500 auto s2_id = ipm->template add_subscription <MessageT>(s2);
501+ // p3 can definitely communicate with s2, may be able to communicate with s1 depending on the RMW
495502 auto p3_id = ipm->add_publisher (p3);
496503
504+ // p1 definitely matches subscription s1, since the topic name and QoS match exactly.
505+ // If the RMW can match best-effort publishers to reliable subscriptions (like Zenoh can),
506+ // then p1 will also match s2.
497507 p1_subs = ipm->get_subscription_count (p1_id);
508+ // No subscriptions with a topic name of "different_topic_name" were added.
498509 p2_subs = ipm->get_subscription_count (p2_id);
510+ // On all current RMWs (DDS and Zenoh), a reliable publisher like p3 can communicate with both
511+ // reliable and best-effort subscriptions (s1 and s2).
499512 size_t p3_subs = ipm->get_subscription_count (p3_id);
500- ASSERT_EQ (1u , p1_subs);
513+
514+ rclcpp::QoSCheckCompatibleResult qos_compatible =
515+ rclcpp::qos_check_compatible (p1->get_actual_qos (), s2->get_actual_qos ());
516+ if (qos_compatible.compatibility == rclcpp::QoSCompatibility::Error) {
517+ ASSERT_EQ (1u , p1_subs);
518+ } else {
519+ ASSERT_EQ (2u , p1_subs);
520+ }
501521 ASSERT_EQ (0u , p2_subs);
502522 ASSERT_EQ (2u , p3_subs);
503523
@@ -528,11 +548,11 @@ TEST(TestIntraProcessManager, single_subscription) {
528548
529549 auto ipm = std::make_shared<IntraProcessManagerT>();
530550
531- auto p1 = std::make_shared<PublisherT>();
551+ auto p1 = std::make_shared<PublisherT>(" topic " , rclcpp::QoS ( 10 ) );
532552 auto p1_id = ipm->add_publisher (p1);
533553 p1->set_intra_process_manager (p1_id, ipm);
534554
535- auto s1 = std::make_shared<SubscriptionIntraProcessT>();
555+ auto s1 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
536556 s1->take_shared_method = false ;
537557 auto s1_id = ipm->template add_subscription <MessageT>(s1);
538558
@@ -543,7 +563,7 @@ TEST(TestIntraProcessManager, single_subscription) {
543563 ASSERT_EQ (original_message_pointer, received_message_pointer_1);
544564
545565 ipm->remove_subscription (s1_id);
546- auto s2 = std::make_shared<SubscriptionIntraProcessT>();
566+ auto s2 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
547567 s2->take_shared_method = true ;
548568 auto s2_id = ipm->template add_subscription <MessageT>(s2);
549569 (void )s2_id;
@@ -582,15 +602,15 @@ TEST(TestIntraProcessManager, multiple_subscriptions_same_type) {
582602
583603 auto ipm = std::make_shared<IntraProcessManagerT>();
584604
585- auto p1 = std::make_shared<PublisherT>();
605+ auto p1 = std::make_shared<PublisherT>(" topic " , rclcpp::QoS ( 10 ) );
586606 auto p1_id = ipm->add_publisher (p1);
587607 p1->set_intra_process_manager (p1_id, ipm);
588608
589- auto s1 = std::make_shared<SubscriptionIntraProcessT>();
609+ auto s1 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
590610 s1->take_shared_method = false ;
591611 auto s1_id = ipm->template add_subscription <MessageT>(s1);
592612
593- auto s2 = std::make_shared<SubscriptionIntraProcessT>();
613+ auto s2 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
594614 s2->take_shared_method = false ;
595615 auto s2_id = ipm->template add_subscription <MessageT>(s2);
596616
@@ -606,11 +626,11 @@ TEST(TestIntraProcessManager, multiple_subscriptions_same_type) {
606626 ipm->remove_subscription (s1_id);
607627 ipm->remove_subscription (s2_id);
608628
609- auto s3 = std::make_shared<SubscriptionIntraProcessT>();
629+ auto s3 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
610630 s3->take_shared_method = true ;
611631 auto s3_id = ipm->template add_subscription <MessageT>(s3);
612632
613- auto s4 = std::make_shared<SubscriptionIntraProcessT>();
633+ auto s4 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
614634 s4->take_shared_method = true ;
615635 auto s4_id = ipm->template add_subscription <MessageT>(s4);
616636
@@ -625,11 +645,11 @@ TEST(TestIntraProcessManager, multiple_subscriptions_same_type) {
625645 ipm->remove_subscription (s3_id);
626646 ipm->remove_subscription (s4_id);
627647
628- auto s5 = std::make_shared<SubscriptionIntraProcessT>();
648+ auto s5 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
629649 s5->take_shared_method = false ;
630650 auto s5_id = ipm->template add_subscription <MessageT>(s5);
631651
632- auto s6 = std::make_shared<SubscriptionIntraProcessT>();
652+ auto s6 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
633653 s6->take_shared_method = false ;
634654 auto s6_id = ipm->template add_subscription <MessageT>(s6);
635655
@@ -645,12 +665,12 @@ TEST(TestIntraProcessManager, multiple_subscriptions_same_type) {
645665 ipm->remove_subscription (s5_id);
646666 ipm->remove_subscription (s6_id);
647667
648- auto s7 = std::make_shared<SubscriptionIntraProcessT>();
668+ auto s7 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
649669 s7->take_shared_method = true ;
650670 auto s7_id = ipm->template add_subscription <MessageT>(s7);
651671 (void )s7_id;
652672
653- auto s8 = std::make_shared<SubscriptionIntraProcessT>();
673+ auto s8 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
654674 s8->take_shared_method = true ;
655675 auto s8_id = ipm->template add_subscription <MessageT>(s8);
656676 (void )s8_id;
@@ -688,15 +708,15 @@ TEST(TestIntraProcessManager, multiple_subscriptions_different_type) {
688708
689709 auto ipm = std::make_shared<IntraProcessManagerT>();
690710
691- auto p1 = std::make_shared<PublisherT>();
711+ auto p1 = std::make_shared<PublisherT>(" topic " , rclcpp::QoS ( 10 ) );
692712 auto p1_id = ipm->add_publisher (p1);
693713 p1->set_intra_process_manager (p1_id, ipm);
694714
695- auto s1 = std::make_shared<SubscriptionIntraProcessT>();
715+ auto s1 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
696716 s1->take_shared_method = true ;
697717 auto s1_id = ipm->template add_subscription <MessageT>(s1);
698718
699- auto s2 = std::make_shared<SubscriptionIntraProcessT>();
719+ auto s2 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
700720 s2->take_shared_method = false ;
701721 auto s2_id = ipm->template add_subscription <MessageT>(s2);
702722
@@ -711,15 +731,15 @@ TEST(TestIntraProcessManager, multiple_subscriptions_different_type) {
711731 ipm->remove_subscription (s1_id);
712732 ipm->remove_subscription (s2_id);
713733
714- auto s3 = std::make_shared<SubscriptionIntraProcessT>();
734+ auto s3 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
715735 s3->take_shared_method = false ;
716736 auto s3_id = ipm->template add_subscription <MessageT>(s3);
717737
718- auto s4 = std::make_shared<SubscriptionIntraProcessT>();
738+ auto s4 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
719739 s4->take_shared_method = false ;
720740 auto s4_id = ipm->template add_subscription <MessageT>(s4);
721741
722- auto s5 = std::make_shared<SubscriptionIntraProcessT>();
742+ auto s5 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
723743 s5->take_shared_method = true ;
724744 auto s5_id = ipm->template add_subscription <MessageT>(s5);
725745
@@ -743,19 +763,19 @@ TEST(TestIntraProcessManager, multiple_subscriptions_different_type) {
743763 ipm->remove_subscription (s4_id);
744764 ipm->remove_subscription (s5_id);
745765
746- auto s6 = std::make_shared<SubscriptionIntraProcessT>();
766+ auto s6 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
747767 s6->take_shared_method = true ;
748768 auto s6_id = ipm->template add_subscription <MessageT>(s6);
749769
750- auto s7 = std::make_shared<SubscriptionIntraProcessT>();
770+ auto s7 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
751771 s7->take_shared_method = true ;
752772 auto s7_id = ipm->template add_subscription <MessageT>(s7);
753773
754- auto s8 = std::make_shared<SubscriptionIntraProcessT>();
774+ auto s8 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
755775 s8->take_shared_method = false ;
756776 auto s8_id = ipm->template add_subscription <MessageT>(s8);
757777
758- auto s9 = std::make_shared<SubscriptionIntraProcessT>();
778+ auto s9 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
759779 s9->take_shared_method = false ;
760780 auto s9_id = ipm->template add_subscription <MessageT>(s9);
761781
@@ -781,12 +801,12 @@ TEST(TestIntraProcessManager, multiple_subscriptions_different_type) {
781801 ipm->remove_subscription (s8_id);
782802 ipm->remove_subscription (s9_id);
783803
784- auto s10 = std::make_shared<SubscriptionIntraProcessT>();
804+ auto s10 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
785805 s10->take_shared_method = false ;
786806 auto s10_id = ipm->template add_subscription <MessageT>(s10);
787807 (void )s10_id;
788808
789- auto s11 = std::make_shared<SubscriptionIntraProcessT>();
809+ auto s11 = std::make_shared<SubscriptionIntraProcessT>(" topic " , rclcpp::QoS ( 10 ) );
790810 s11->take_shared_method = true ;
791811 auto s11_id = ipm->template add_subscription <MessageT>(s11);
792812 (void )s11_id;
@@ -831,10 +851,12 @@ TEST(TestIntraProcessManager, lowest_available_capacity) {
831851
832852 auto ipm = std::make_shared<IntraProcessManagerT>();
833853
834- auto p1 = std::make_shared<PublisherT>(rclcpp::QoS (history_depth).best_effort ());
854+ auto p1 = std::make_shared<PublisherT>(" topic " , rclcpp::QoS (history_depth).best_effort ());
835855
836- auto s1 = std::make_shared<SubscriptionIntraProcessT>(rclcpp::QoS (history_depth).best_effort ());
837- auto s2 = std::make_shared<SubscriptionIntraProcessT>(rclcpp::QoS (history_depth).best_effort ());
856+ auto s1 =
857+ std::make_shared<SubscriptionIntraProcessT>(" topic" , rclcpp::QoS (history_depth).best_effort ());
858+ auto s2 =
859+ std::make_shared<SubscriptionIntraProcessT>(" topic" , rclcpp::QoS (history_depth).best_effort ());
838860
839861 auto p1_id = ipm->add_publisher (p1);
840862 p1->set_intra_process_manager (p1_id, ipm);
@@ -902,7 +924,7 @@ TEST(TestIntraProcessManager, transient_local_invalid_buffer) {
902924
903925 auto ipm = std::make_shared<IntraProcessManagerT>();
904926
905- auto p1 = std::make_shared<PublisherT>(rclcpp::QoS (history_depth).transient_local ());
927+ auto p1 = std::make_shared<PublisherT>(" topic " , rclcpp::QoS (history_depth).transient_local ());
906928
907929 ASSERT_THROW (
908930 {
@@ -926,14 +948,14 @@ TEST(TestIntraProcessManager, transient_local) {
926948
927949 auto ipm = std::make_shared<IntraProcessManagerT>();
928950
929- auto p1 = std::make_shared<PublisherT>(rclcpp::QoS (history_depth).transient_local ());
951+ auto p1 = std::make_shared<PublisherT>(" topic " , rclcpp::QoS (history_depth).transient_local ());
930952
931- auto s1 =
932- std::make_shared<SubscriptionIntraProcessT>( rclcpp::QoS (history_depth).transient_local ());
933- auto s2 =
934- std::make_shared<SubscriptionIntraProcessT>( rclcpp::QoS (history_depth).transient_local ());
935- auto s3 =
936- std::make_shared<SubscriptionIntraProcessT>( rclcpp::QoS (history_depth).transient_local ());
953+ auto s1 = std::make_shared<SubscriptionIntraProcessT>(
954+ " topic " , rclcpp::QoS (history_depth).transient_local ());
955+ auto s2 = std::make_shared<SubscriptionIntraProcessT>(
956+ " topic " , rclcpp::QoS (history_depth).transient_local ());
957+ auto s3 = std::make_shared<SubscriptionIntraProcessT>(
958+ " topic " , rclcpp::QoS (history_depth).transient_local ());
937959
938960 s1->take_shared_method = false ;
939961 s2->take_shared_method = true ;
0 commit comments