@@ -36,17 +36,20 @@ LifecycleNode::LifecycleNode(
3636 bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM, true ));
3737
3838 printLifecycleNodeNotification ();
39+
40+ register_rcl_preshutdown_callback ();
3941}
4042
4143LifecycleNode::~LifecycleNode ()
4244{
4345 RCLCPP_INFO (get_logger (), " Destroying" );
44- // In case this lifecycle node wasn't properly shut down, do it here
45- if (get_current_state ().id () ==
46- lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
47- {
48- on_deactivate (get_current_state ());
49- on_cleanup (get_current_state ());
46+
47+ runCleanups ();
48+
49+ if (rcl_preshutdown_cb_handle_) {
50+ rclcpp::Context::SharedPtr context = get_node_base_interface ()->get_context ();
51+ context->remove_pre_shutdown_callback (*(rcl_preshutdown_cb_handle_.get ()));
52+ rcl_preshutdown_cb_handle_.reset ();
5053 }
5154}
5255
@@ -64,6 +67,47 @@ void LifecycleNode::createBond()
6467 bond_->start ();
6568}
6669
70+ void LifecycleNode::runCleanups ()
71+ {
72+ /*
73+ * In case this lifecycle node wasn't properly shut down, do it here.
74+ * We will give the user some ability to clean up properly here, but it's
75+ * best effort; i.e. we aren't trying to account for all possible states.
76+ */
77+ if (get_current_state ().id () ==
78+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
79+ {
80+ this ->deactivate ();
81+ }
82+
83+ if (get_current_state ().id () ==
84+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
85+ {
86+ this ->cleanup ();
87+ }
88+ }
89+
90+ void LifecycleNode::on_rcl_preshutdown ()
91+ {
92+ RCLCPP_INFO (
93+ get_logger (), " Running Nav2 LifecycleNode rcl preshutdown (%s)" ,
94+ this ->get_name ());
95+
96+ runCleanups ();
97+
98+ destroyBond ();
99+ }
100+
101+ void LifecycleNode::register_rcl_preshutdown_callback ()
102+ {
103+ rclcpp::Context::SharedPtr context = get_node_base_interface ()->get_context ();
104+
105+ rcl_preshutdown_cb_handle_ = std::make_unique<rclcpp::PreShutdownCallbackHandle>(
106+ context->add_pre_shutdown_callback (
107+ std::bind (&LifecycleNode::on_rcl_preshutdown, this ))
108+ );
109+ }
110+
67111void LifecycleNode::destroyBond ()
68112{
69113 RCLCPP_INFO (get_logger (), " Destroying bond (%s) to lifecycle manager." , this ->get_name ());
0 commit comments