Skip to content

Commit 0ca14fe

Browse files
Fixing 3768: planner server lifecycle transition down (#3786)
1 parent 0cf0462 commit 0ca14fe

File tree

8 files changed

+226
-25
lines changed

8 files changed

+226
-25
lines changed

nav2_controller/src/controller_server.cpp

Lines changed: 21 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include <utility>
2020
#include <limits>
2121

22+
#include "lifecycle_msgs/msg/state.hpp"
2223
#include "nav2_core/exceptions.hpp"
2324
#include "nav_2d_utils/conversions.hpp"
2425
#include "nav_2d_utils/tf_help.hpp"
@@ -245,7 +246,19 @@ ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
245246
for (it = controllers_.begin(); it != controllers_.end(); ++it) {
246247
it->second->deactivate();
247248
}
248-
costmap_ros_->deactivate();
249+
250+
/*
251+
* The costmap is also a lifecycle node, so it may have already fired on_deactivate
252+
* via rcl preshutdown cb. Despite the rclcpp docs saying on_shutdown callbacks fire
253+
* in the order added, the preshutdown callbacks clearly don't per se, due to using an
254+
* unordered_set iteration. Once this issue is resolved, we can maybe make a stronger
255+
* ordering assumption: https://github.com/ros2/rclcpp/issues/2096
256+
*/
257+
if (costmap_ros_->get_current_state().id() ==
258+
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
259+
{
260+
costmap_ros_->deactivate();
261+
}
249262

250263
publishZeroVelocity();
251264
vel_publisher_->on_deactivate();
@@ -270,11 +283,17 @@ ControllerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
270283
controllers_.clear();
271284

272285
goal_checkers_.clear();
273-
costmap_ros_->cleanup();
286+
287+
if (costmap_ros_->get_current_state().id() ==
288+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
289+
{
290+
costmap_ros_->cleanup();
291+
}
274292

275293
// Release any allocated resources
276294
action_server_.reset();
277295
odom_sub_.reset();
296+
costmap_thread_.reset();
278297
vel_publisher_.reset();
279298
speed_limit_sub_.reset();
280299

nav2_costmap_2d/src/costmap_2d_ros.cpp

Lines changed: 23 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -272,14 +272,18 @@ Costmap2DROS::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
272272
RCLCPP_INFO(get_logger(), "Deactivating");
273273

274274
dyn_params_handler.reset();
275-
costmap_publisher_->on_deactivate();
276-
footprint_pub_->on_deactivate();
277275

278276
stop();
279277

280278
// Map thread stuff
281279
map_update_thread_shutdown_ = true;
282-
map_update_thread_->join();
280+
281+
if (map_update_thread_->joinable()) {
282+
map_update_thread_->join();
283+
}
284+
285+
costmap_publisher_->on_deactivate();
286+
footprint_pub_->on_deactivate();
283287

284288
return nav2_util::CallbackReturn::SUCCESS;
285289
}
@@ -529,18 +533,22 @@ void
529533
Costmap2DROS::stop()
530534
{
531535
stop_updates_ = true;
532-
std::vector<std::shared_ptr<Layer>> * plugins = layered_costmap_->getPlugins();
533-
std::vector<std::shared_ptr<Layer>> * filters = layered_costmap_->getFilters();
534-
// unsubscribe from topics
535-
for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
536-
plugin != plugins->end(); ++plugin)
537-
{
538-
(*plugin)->deactivate();
539-
}
540-
for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
541-
filter != filters->end(); ++filter)
542-
{
543-
(*filter)->deactivate();
536+
// layered_costmap_ is set only if on_configure has been called
537+
if (layered_costmap_) {
538+
std::vector<std::shared_ptr<Layer>> * plugins = layered_costmap_->getPlugins();
539+
std::vector<std::shared_ptr<Layer>> * filters = layered_costmap_->getFilters();
540+
541+
// unsubscribe from topics
542+
for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
543+
plugin != plugins->end(); ++plugin)
544+
{
545+
(*plugin)->deactivate();
546+
}
547+
for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
548+
filter != filters->end(); ++filter)
549+
{
550+
(*filter)->deactivate();
551+
}
544552
}
545553
initialized_ = false;
546554
stopped_ = true;

nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -114,6 +114,13 @@ class LifecycleManager : public rclcpp::Node
114114
*/
115115
bool resume();
116116

117+
/**
118+
* @brief Perform preshutdown activities before our Context is shutdown.
119+
* Note that this is related to our Context's shutdown sequence, not the
120+
* lifecycle node state machine or shutdown().
121+
*/
122+
void onRclPreshutdown();
123+
117124
// Support function for creating service clients
118125
/**
119126
* @brief Support function for creating service clients
@@ -186,6 +193,14 @@ class LifecycleManager : public rclcpp::Node
186193
*/
187194
void CreateActiveDiagnostic(diagnostic_updater::DiagnosticStatusWrapper & stat);
188195

196+
/**
197+
* Register our preshutdown callback for this Node's rcl Context.
198+
* The callback fires before this Node's Context is shutdown.
199+
* Note this is not directly related to the lifecycle state machine or the
200+
* shutdown() instance function.
201+
*/
202+
void registerRclPreshutdownCallback();
203+
189204
// Timer thread to look at bond connections
190205
rclcpp::TimerBase::SharedPtr init_timer_;
191206
rclcpp::TimerBase::SharedPtr bond_timer_;

nav2_lifecycle_manager/src/lifecycle_manager.cpp

Lines changed: 31 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,8 @@ LifecycleManager::LifecycleManager(const rclcpp::NodeOptions & options)
4545
declare_parameter("bond_respawn_max_duration", 10.0);
4646
declare_parameter("attempt_respawn_reconnection", true);
4747

48+
registerRclPreshutdownCallback();
49+
4850
node_names_ = get_parameter("node_names").as_string_array();
4951
get_parameter("autostart", autostart_);
5052
double bond_timeout_s;
@@ -378,6 +380,35 @@ LifecycleManager::destroyBondTimer()
378380
}
379381
}
380382

383+
void
384+
LifecycleManager::onRclPreshutdown()
385+
{
386+
RCLCPP_INFO(
387+
get_logger(), "Running Nav2 LifecycleManager rcl preshutdown (%s)",
388+
this->get_name());
389+
390+
destroyBondTimer();
391+
392+
/*
393+
* Dropping the bond map is what we really need here, but we drop the others
394+
* to prevent the bond map being used. Likewise, squash the service thread.
395+
*/
396+
service_thread_.reset();
397+
node_names_.clear();
398+
node_map_.clear();
399+
bond_map_.clear();
400+
}
401+
402+
void
403+
LifecycleManager::registerRclPreshutdownCallback()
404+
{
405+
rclcpp::Context::SharedPtr context = get_node_base_interface()->get_context();
406+
407+
context->add_pre_shutdown_callback(
408+
std::bind(&LifecycleManager::onRclPreshutdown, this)
409+
);
410+
}
411+
381412
void
382413
LifecycleManager::checkBondConnections()
383414
{

nav2_planner/src/planner_server.cpp

Lines changed: 30 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
#include <utility>
2626

2727
#include "builtin_interfaces/msg/duration.hpp"
28+
#include "lifecycle_msgs/msg/state.hpp"
2829
#include "nav2_util/costmap.hpp"
2930
#include "nav2_util/node_utils.hpp"
3031
#include "nav2_util/geometry_utils.hpp"
@@ -66,6 +67,10 @@ PlannerServer::PlannerServer(const rclcpp::NodeOptions & options)
6667

6768
PlannerServer::~PlannerServer()
6869
{
70+
/*
71+
* Backstop ensuring this state is destroyed, even if deactivate/cleanup are
72+
* never called.
73+
*/
6974
planners_.clear();
7075
costmap_thread_.reset();
7176
}
@@ -194,7 +199,19 @@ PlannerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
194199
action_server_pose_->deactivate();
195200
action_server_poses_->deactivate();
196201
plan_publisher_->on_deactivate();
197-
costmap_ros_->deactivate();
202+
203+
/*
204+
* The costmap is also a lifecycle node, so it may have already fired on_deactivate
205+
* via rcl preshutdown cb. Despite the rclcpp docs saying on_shutdown callbacks fire
206+
* in the order added, the preshutdown callbacks clearly don't per se, due to using an
207+
* unordered_set iteration. Once this issue is resolved, we can maybe make a stronger
208+
* ordering assumption: https://github.com/ros2/rclcpp/issues/2096
209+
*/
210+
if (costmap_ros_->get_current_state().id() ==
211+
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
212+
{
213+
costmap_ros_->deactivate();
214+
}
198215

199216
PlannerMap::iterator it;
200217
for (it = planners_.begin(); it != planners_.end(); ++it) {
@@ -218,13 +235,24 @@ PlannerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
218235
action_server_poses_.reset();
219236
plan_publisher_.reset();
220237
tf_.reset();
221-
costmap_ros_->cleanup();
238+
239+
/*
240+
* Double check whether something else transitioned it to INACTIVE
241+
* already, e.g. the rcl preshutdown callback.
242+
*/
243+
if (costmap_ros_->get_current_state().id() ==
244+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
245+
{
246+
costmap_ros_->cleanup();
247+
}
222248

223249
PlannerMap::iterator it;
224250
for (it = planners_.begin(); it != planners_.end(); ++it) {
225251
it->second->cleanup();
226252
}
253+
227254
planners_.clear();
255+
costmap_thread_.reset();
228256
costmap_ = nullptr;
229257
return nav2_util::CallbackReturn::SUCCESS;
230258
}

nav2_util/include/nav2_util/lifecycle_node.hpp

Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -167,6 +167,13 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
167167
return nav2_util::CallbackReturn::SUCCESS;
168168
}
169169

170+
/**
171+
* @brief Perform preshutdown activities before our Context is shutdown.
172+
* Note that this is related to our Context's shutdown sequence, not the
173+
* lifecycle node state machine.
174+
*/
175+
virtual void on_rcl_preshutdown();
176+
170177
/**
171178
* @brief Create bond connection to lifecycle manager
172179
*/
@@ -183,6 +190,19 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
183190
*/
184191
void printLifecycleNodeNotification();
185192

193+
/**
194+
* Register our preshutdown callback for this Node's rcl Context.
195+
* The callback fires before this Node's Context is shutdown.
196+
* Note this is not directly related to the lifecycle state machine.
197+
*/
198+
void register_rcl_preshutdown_callback();
199+
std::unique_ptr<rclcpp::PreShutdownCallbackHandle> rcl_preshutdown_cb_handle_{nullptr};
200+
201+
/**
202+
* Run some common cleanup steps shared between rcl preshutdown and destruction.
203+
*/
204+
void runCleanups();
205+
186206
// Connection to tell that server is still up
187207
std::unique_ptr<bond::Bond> bond_{nullptr};
188208
};

nav2_util/src/lifecycle_node.cpp

Lines changed: 50 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -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

4143
LifecycleNode::~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+
67111
void LifecycleNode::destroyBond()
68112
{
69113
RCLCPP_INFO(get_logger(), "Destroying bond (%s) to lifecycle manager.", this->get_name());

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)