diff --git a/rcl/test/rcl/test_publisher.cpp b/rcl/test/rcl/test_publisher.cpp index f40f722c7..0c4a48431 100644 --- a/rcl/test/rcl/test_publisher.cpp +++ b/rcl/test/rcl/test_publisher.cpp @@ -115,6 +115,55 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); } +/* Test two publishers using different message types with the same basename. + * + * Regression test for https://github.com/ros2/rmw_connext/issues/234, where rmw_connext_cpp could + * not support publishers on topics with the same basename (but different namespaces) using + * different message types, because at the time partitions were used for implementing namespaces. + */ +TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publishers_different_types) { + rcl_ret_t ret; + rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); + const rosidl_message_type_support_t * ts_int = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int64); + const char * topic_name = "basename"; + const char * expected_topic_name = "/basename"; + rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); + ret = rcl_publisher_init(&publisher, this->node_ptr, ts_int, topic_name, &publisher_options); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); + EXPECT_EQ(strcmp(rcl_publisher_get_topic_name(&publisher), expected_topic_name), 0); + + rcl_publisher_t publisher_in_namespace = rcl_get_zero_initialized_publisher(); + const rosidl_message_type_support_t * ts_string = ROSIDL_GET_MSG_TYPE_SUPPORT( + std_msgs, msg, String); + topic_name = "namespace/basename"; + expected_topic_name = "/namespace/basename"; + ret = rcl_publisher_init( + &publisher_in_namespace, this->node_ptr, ts_string, topic_name, &publisher_options); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_publisher_fini(&publisher_in_namespace, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); + EXPECT_EQ(strcmp(rcl_publisher_get_topic_name(&publisher_in_namespace), expected_topic_name), 0); + + std_msgs__msg__Int64 msg_int; + std_msgs__msg__Int64__init(&msg_int); + msg_int.data = 42; + ret = rcl_publish(&publisher, &msg_int); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + std_msgs__msg__Int64__fini(&msg_int); + + std_msgs__msg__String msg_string; + std_msgs__msg__String__init(&msg_string); + ASSERT_TRUE(rosidl_generator_c__String__assign(&msg_string.data, "testing")); + ret = rcl_publish(&publisher_in_namespace, &msg_string); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); +} + /* Testing the publisher init and fini functions. */ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_init_fini) {