Skip to content

Commit 65e561f

Browse files
author
mbryan
committed
Add unit tests for lifecycle_node rcl shutdown cb.
For Issue ros-navigation#3271. Signed-off-by: mbryan <matthew.bryan@dell.com>
1 parent b3b548d commit 65e561f

File tree

1 file changed

+36
-0
lines changed

1 file changed

+36
-0
lines changed

nav2_util/test/test_lifecycle_node.cpp

Lines changed: 36 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -47,3 +47,39 @@ TEST(LifecycleNode, MultipleRclcppNodesExitCleanly)
4747
std::this_thread::sleep_for(std::chrono::seconds(1));
4848
SUCCEED();
4949
}
50+
51+
TEST(LifecycleNode, OnPreshutdownCbFires)
52+
{
53+
// Ensure the on_rcl_preshutdown_cb fires
54+
55+
class MyNodeType : public nav2_util::LifecycleNode
56+
{
57+
public:
58+
MyNodeType(
59+
const std::string & node_name)
60+
: nav2_util::LifecycleNode(node_name) {}
61+
62+
bool fired = false;
63+
64+
protected:
65+
void on_rcl_preshutdown() override
66+
{
67+
fired = true;
68+
69+
nav2_util::LifecycleNode::on_rcl_preshutdown();
70+
}
71+
};
72+
73+
auto node = std::make_shared<MyNodeType>("test_node");
74+
75+
ASSERT_EQ(node->fired, false);
76+
77+
rclcpp::shutdown();
78+
79+
ASSERT_EQ(node->fired, true);
80+
81+
// Fire dtor to ensure nothing insane happens, e.g. exceptions.
82+
node.reset();
83+
84+
SUCCEED();
85+
}

0 commit comments

Comments
 (0)