Skip to content

Commit 4aaefad

Browse files
mmattbmbryan
andauthored
Address code cov loss due to unclean shutdown (issue #3271) (#3377)
* Ensure that we break bonds in lifecycle node/manager prior to rcl_shutdown. Partial fix for Issue #3271 Signed-off-by: mbryan <[email protected]> * Add unit tests for lifecycle_node rcl shutdown cb. For Issue #3271. Signed-off-by: mbryan <[email protected]> * Ensure planner_server shuts down cleanly on SIGINT. Needed to ensure code coverage flushes. See Issue #3271. Signed-off-by: mbryan <[email protected]> * Ensure costmap_2d_cloud does not seg fault on SIGINT. One of several clean shutdown issues being address via Issue #3271. Signed-off-by: mbryan <[email protected]> * Fix flake8 issues in some test files Signed-off-by: mbryan <[email protected]> --------- Signed-off-by: mbryan <[email protected]> Co-authored-by: mbryan <[email protected]>
1 parent 8ff085d commit 4aaefad

File tree

19 files changed

+269
-64
lines changed

19 files changed

+269
-64
lines changed

nav2_bringup/launch/localization_launch.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -107,7 +107,7 @@ def generate_launch_description():
107107
load_nodes = GroupAction(
108108
condition=IfCondition(PythonExpression(['not ', use_composition])),
109109
actions=[
110-
SetParameter("use_sim_time", use_sim_time),
110+
SetParameter('use_sim_time', use_sim_time),
111111
Node(
112112
condition=LaunchConfigurationEquals('map', ''),
113113
package='nav2_map_server',
@@ -165,7 +165,7 @@ def generate_launch_description():
165165
load_composable_nodes = GroupAction(
166166
condition=IfCondition(use_composition),
167167
actions=[
168-
SetParameter("use_sim_time", use_sim_time),
168+
SetParameter('use_sim_time', use_sim_time),
169169
LoadComposableNodes(
170170
target_container=container_name_full,
171171
condition=LaunchConfigurationEquals('map', ''),

nav2_bringup/launch/navigation_launch.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -108,7 +108,7 @@ def generate_launch_description():
108108
load_nodes = GroupAction(
109109
condition=IfCondition(PythonExpression(['not ', use_composition])),
110110
actions=[
111-
SetParameter("use_sim_time", use_sim_time),
111+
SetParameter('use_sim_time', use_sim_time),
112112
Node(
113113
package='nav2_controller',
114114
executable='controller_server',
@@ -193,7 +193,7 @@ def generate_launch_description():
193193
load_composable_nodes = GroupAction(
194194
condition=IfCondition(use_composition),
195195
actions=[
196-
SetParameter("use_sim_time", use_sim_time),
196+
SetParameter('use_sim_time', use_sim_time),
197197
LoadComposableNodes(
198198
target_container=container_name_full,
199199
composable_node_descriptions=[

nav2_bringup/launch/slam_launch.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@
1717
from ament_index_python.packages import get_package_share_directory
1818

1919
from launch import LaunchDescription
20-
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, GroupAction
20+
from launch.actions import DeclareLaunchArgument, GroupAction, IncludeLaunchDescription
2121
from launch.conditions import IfCondition, UnlessCondition
2222
from launch.launch_description_sources import PythonLaunchDescriptionSource
2323
from launch.substitutions import LaunchConfiguration
@@ -81,7 +81,7 @@ def generate_launch_description():
8181

8282
start_map_server = GroupAction(
8383
actions=[
84-
SetParameter("use_sim_time", use_sim_time),
84+
SetParameter('use_sim_time', use_sim_time),
8585
Node(
8686
package='nav2_map_server',
8787
executable='map_saver_server',

nav2_controller/src/controller_server.cpp

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

251264
publishZeroVelocity();
252265
vel_publisher_->on_deactivate();
@@ -271,11 +284,16 @@ ControllerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
271284
controllers_.clear();
272285

273286
goal_checkers_.clear();
274-
costmap_ros_->cleanup();
287+
if (costmap_ros_->get_current_state().id() ==
288+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
289+
{
290+
costmap_ros_->cleanup();
291+
}
275292

276293
// Release any allocated resources
277294
action_server_.reset();
278295
odom_sub_.reset();
296+
costmap_thread_.reset();
279297
vel_publisher_.reset();
280298
speed_limit_sub_.reset();
281299

nav2_costmap_2d/src/costmap_2d_cloud.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -225,6 +225,11 @@ int main(int argc, char ** argv)
225225
"voxel_grid", rclcpp::SystemDefaultsQoS(), voxelCallback);
226226

227227
rclcpp::spin(g_node->get_node_base_interface());
228+
229+
g_node.reset();
230+
pub_marked.reset();
231+
pub_unknown.reset();
232+
228233
rclcpp::shutdown();
229234

230235
return 0;

nav2_costmap_2d/src/costmap_2d_ros.cpp

Lines changed: 26 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -299,19 +299,22 @@ Costmap2DROS::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
299299

300300
dyn_params_handler.reset();
301301

302+
stop();
303+
304+
// Map thread stuff
305+
map_update_thread_shutdown_ = true;
306+
307+
if (map_update_thread_->joinable()) {
308+
map_update_thread_->join();
309+
}
310+
302311
footprint_pub_->on_deactivate();
303312
costmap_publisher_->on_deactivate();
304313

305314
for (auto & layer_pub : layer_publishers_) {
306315
layer_pub->on_deactivate();
307316
}
308317

309-
stop();
310-
311-
// Map thread stuff
312-
map_update_thread_shutdown_ = true;
313-
map_update_thread_->join();
314-
315318
return nav2_util::CallbackReturn::SUCCESS;
316319
}
317320

@@ -575,18 +578,23 @@ void
575578
Costmap2DROS::stop()
576579
{
577580
stop_updates_ = true;
578-
std::vector<std::shared_ptr<Layer>> * plugins = layered_costmap_->getPlugins();
579-
std::vector<std::shared_ptr<Layer>> * filters = layered_costmap_->getFilters();
580-
// unsubscribe from topics
581-
for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
582-
plugin != plugins->end(); ++plugin)
583-
{
584-
(*plugin)->deactivate();
585-
}
586-
for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
587-
filter != filters->end(); ++filter)
588-
{
589-
(*filter)->deactivate();
581+
582+
// layered_costmap_ is set only if on_configure has been called
583+
if (layered_costmap_) {
584+
std::vector<std::shared_ptr<Layer>> * plugins = layered_costmap_->getPlugins();
585+
std::vector<std::shared_ptr<Layer>> * filters = layered_costmap_->getFilters();
586+
587+
// unsubscribe from topics
588+
for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
589+
plugin != plugins->end(); ++plugin)
590+
{
591+
(*plugin)->deactivate();
592+
}
593+
for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
594+
filter != filters->end(); ++filter)
595+
{
596+
(*filter)->deactivate();
597+
}
590598
}
591599
initialized_ = false;
592600
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"
@@ -69,6 +70,10 @@ PlannerServer::PlannerServer(const rclcpp::NodeOptions & options)
6970

7071
PlannerServer::~PlannerServer()
7172
{
73+
/*
74+
* Backstop ensuring this state is destroyed, even if deactivate/cleanup are
75+
* never called.
76+
*/
7277
planners_.clear();
7378
costmap_thread_.reset();
7479
}
@@ -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_simple_commander/nav2_simple_commander/footprint_collision_checker.py

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -22,10 +22,10 @@
2222
"""
2323

2424
from math import cos, sin
25-
from nav2_simple_commander.line_iterator import LineIterator
25+
26+
from geometry_msgs.msg import Point32, Polygon
2627
from nav2_simple_commander.costmap_2d import PyCostmap2D
27-
from geometry_msgs.msg import Polygon
28-
from geometry_msgs.msg import Point32
28+
from nav2_simple_commander.line_iterator import LineIterator
2929

3030
NO_INFORMATION = 255
3131
LETHAL_OBSTACLE = 254
@@ -146,7 +146,7 @@ def worldToMapValidated(self, wx: float, wy: float):
146146
"""
147147
if self.costmap_ is None:
148148
raise ValueError(
149-
"Costmap not specified, use setCostmap to specify the costmap first")
149+
'Costmap not specified, use setCostmap to specify the costmap first')
150150
return self.costmap_.worldToMapValidated(wx, wy)
151151

152152
def pointCost(self, x: int, y: int):
@@ -165,7 +165,7 @@ def pointCost(self, x: int, y: int):
165165
"""
166166
if self.costmap_ is None:
167167
raise ValueError(
168-
"Costmap not specified, use setCostmap to specify the costmap first")
168+
'Costmap not specified, use setCostmap to specify the costmap first')
169169
return self.costmap_.getCostXY(x, y)
170170

171171
def setCostmap(self, costmap: PyCostmap2D):

0 commit comments

Comments
 (0)