Skip to content

Commit

Permalink
Use osrf_testing_tools_cpp
Browse files Browse the repository at this point in the history
  • Loading branch information
dhood committed Jun 12, 2018
1 parent 7121ad1 commit f4fffc7
Showing 1 changed file with 8 additions and 13 deletions.
21 changes: 8 additions & 13 deletions rcl/test/rcl/test_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,6 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin
* 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);
Expand All @@ -131,12 +130,10 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publishers_diff
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();
});
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();
Expand All @@ -147,12 +144,10 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publishers_diff
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();
});
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;
Expand Down

0 comments on commit f4fffc7

Please sign in to comment.