Skip to content

Commit

Permalink
Add unit tests for lifecycle_node rcl shutdown cb.
Browse files Browse the repository at this point in the history
For Issue ros-navigation#3271.

Signed-off-by: mbryan <[email protected]>
  • Loading branch information
mbryan committed Feb 1, 2023
1 parent e6cf45a commit 624a5e7
Showing 1 changed file with 36 additions and 0 deletions.
36 changes: 36 additions & 0 deletions nav2_util/test/test_lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,3 +47,39 @@ TEST(LifecycleNode, MultipleRclcppNodesExitCleanly)
std::this_thread::sleep_for(std::chrono::seconds(1));
SUCCEED();
}

TEST(LifecycleNode, OnPreshutdownCbFires)
{
// Ensure the on_rcl_preshutdown_cb fires

class MyNodeType : public nav2_util::LifecycleNode
{
public:
MyNodeType(
const std::string & node_name)
: nav2_util::LifecycleNode(node_name) {}

bool fired = false;

protected:
void on_rcl_preshutdown() override
{
fired = true;

nav2_util::LifecycleNode::on_rcl_preshutdown();
}
};

auto node = std::make_shared<MyNodeType>("test_node");

ASSERT_EQ(node->fired, false);

rclcpp::shutdown();

ASSERT_EQ(node->fired, true);

// Fire dtor to ensure nothing insane happens, e.g. exceptions.
node.reset();

SUCCEED();
}

0 comments on commit 624a5e7

Please sign in to comment.