Skip to content

Commit

Permalink
Ensure costmap_2d_cloud does not seg fault on SIGINT.
Browse files Browse the repository at this point in the history
One of several clean shutdown issues being address via Issue ros-navigation#3271.

Signed-off-by: mbryan <matthew.bryan@dell.com>
  • Loading branch information
mbryan committed Jan 20, 2023
1 parent c2d6f0c commit 98d17bb
Showing 1 changed file with 6 additions and 0 deletions.
6 changes: 6 additions & 0 deletions nav2_costmap_2d/src/costmap_2d_cloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -225,6 +225,12 @@ int main(int argc, char ** argv)
"voxel_grid", rclcpp::SystemDefaultsQoS(), voxelCallback);

rclcpp::spin(g_node->get_node_base_interface());

// Force dtors to fire before shutdown(). We see segfaults otherwise.
g_node.reset();
pub_marked.reset();
pub_unknown.reset();

rclcpp::shutdown();

return 0;
Expand Down

0 comments on commit 98d17bb

Please sign in to comment.