Skip to content

Commit

Permalink
Add regression test for connext 'wrong type writer' error
Browse files Browse the repository at this point in the history
  • Loading branch information
dhood committed Jun 8, 2018
1 parent 0f8b3ee commit e7b8809
Showing 1 changed file with 54 additions and 0 deletions.
54 changes: 54 additions & 0 deletions rcl/test/rcl/test_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,6 +133,60 @@ 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) {
stop_memory_checking();
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();
auto publisher_exit = make_scope_exit(
[&publisher, this]() {
stop_memory_checking();
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();
auto publisher_in_namespace_exit = make_scope_exit(
[&publisher_in_namespace, this]() {
stop_memory_checking();
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) {
Expand Down

0 comments on commit e7b8809

Please sign in to comment.