Skip to content

Commit

Permalink
Use scope exit to clean context
Browse files Browse the repository at this point in the history
Signed-off-by: Jorge Perez <jjperez@ekumenlabs.com>
  • Loading branch information
Blast545 committed Sep 21, 2020
1 parent cbeae71 commit ff35723
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions rclcpp/test/rclcpp/test_utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include "rcl/init.h"
#include "rcl/logging.h"

#include "rclcpp/scope_exit.hpp"
#include "rclcpp/contexts/default_context.hpp"
#include "rclcpp/exceptions.hpp"
#include "rclcpp/utilities.hpp"
Expand Down Expand Up @@ -107,8 +108,9 @@ MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t, <)
TEST(TestUtilities, test_context_release_interrupt_guard_condition) {
auto context1 = std::make_shared<rclcpp::contexts::DefaultContext>();
context1->init(0, nullptr);
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
RCLCPP_SCOPE_EXIT(rclcpp::shutdown(context1););

rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
rcl_ret_t ret = rcl_wait_set_init(
&wait_set, 0, 2, 0, 0, 0, 0, context1->get_rcl_context().get(),
rcl_get_default_allocator());
Expand Down Expand Up @@ -154,8 +156,6 @@ TEST(TestUtilities, test_context_release_interrupt_guard_condition) {
interrupt_guard_condition = context1->get_interrupt_guard_condition(&wait_set);
EXPECT_NE(nullptr, interrupt_guard_condition);
EXPECT_NO_THROW(context1->release_interrupt_guard_condition(&wait_set));

rclcpp::shutdown(context1);
}


Expand Down

0 comments on commit ff35723

Please sign in to comment.