Skip to content

Commit

Permalink
Update graph_listener tests and please linters
Browse files Browse the repository at this point in the history
Signed-off-by: Ivan Santiago Paunovic <ivanpauno@ekumenlabs.com>
  • Loading branch information
ivanpauno committed Nov 12, 2020
1 parent 2297071 commit 6e8e157
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 24 deletions.
5 changes: 2 additions & 3 deletions rclcpp/src/rclcpp/graph_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,7 @@ namespace graph_listener
{

GraphListener::GraphListener(const std::shared_ptr<Context> & parent_context)
:
weak_parent_context_(parent_context),
: weak_parent_context_(parent_context),
rcl_parent_context_(parent_context->get_rcl_context()),
is_started_(false),
is_shutdown_(false)
Expand Down Expand Up @@ -92,7 +91,7 @@ GraphListener::start_if_not_started()
// This is important to ensure that the wait set is finalized before
// destruction of static objects occurs.
std::weak_ptr<GraphListener> weak_this = shared_from_this();
parent_context->on_shutdown(
parent_context->on_shutdown(
[weak_this]() {
auto shared_this = weak_this.lock();
if (shared_this) {
Expand Down
24 changes: 3 additions & 21 deletions rclcpp/test/rclcpp/test_graph_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,9 @@ TEST_F(TestGraphListener, error_run_graph_listener_destroy_context) {
auto graph_listener_error =
std::make_shared<TestGraphListenerProtectedMethods>(context_to_destroy);
context_to_destroy.reset();
EXPECT_NO_THROW(graph_listener_error->run_protected());
EXPECT_THROW(
graph_listener_error->run_protected(),
rclcpp::exceptions::RCLError);
}

TEST_F(TestGraphListener, error_run_graph_listener_mock_wait_set_clear) {
Expand All @@ -170,26 +172,6 @@ TEST_F(TestGraphListener, error_run_graph_listener_mock_wait_set_add_guard_condi
std::runtime_error("failed to add interrupt guard condition to wait set: error not set"));
}

TEST_F(TestGraphListener, error_run_graph_listener_mock_wait_set_add_guard_condition_twice) {
auto global_context = rclcpp::contexts::get_global_default_context();
auto graph_listener_test =
std::make_shared<TestGraphListenerProtectedMethods>(global_context);
graph_listener_test->mock_init_wait_set();
auto mock = mocking_utils::patch(
"lib:rclcpp", rcl_wait_set_add_guard_condition, [](auto, ...) {
static int counter = 1;
if (counter == 1) {
counter++;
return RCL_RET_OK;
} else {
return RCL_RET_ERROR;
}
});
RCLCPP_EXPECT_THROW_EQ(
graph_listener_test->run_protected(),
std::runtime_error("failed to add shutdown guard condition to wait set: error not set"));
}

TEST_F(TestGraphListener, error_run_graph_listener_mock_wait_error) {
auto global_context = rclcpp::contexts::get_global_default_context();
auto graph_listener_test =
Expand Down

0 comments on commit 6e8e157

Please sign in to comment.