From eb86ba6e7c45a173c45a9c9737bba8f72d078a53 Mon Sep 17 00:00:00 2001 From: Michael Grupp Date: Tue, 26 Mar 2019 12:06:14 +0100 Subject: [PATCH] Fix segfault by changing the destruction order. (#1235) The metrics registry is used as a raw pointer reference in map builder and must outlive it. Since C++ destroys in reverse declaration order, we have to put the registry declaration before the map builder bridge. Fixes #1234. --- cartographer_ros/cartographer_ros/node.h | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/cartographer_ros/cartographer_ros/node.h b/cartographer_ros/cartographer_ros/node.h index 7282dd5..62eb6f9 100644 --- a/cartographer_ros/cartographer_ros/node.h +++ b/cartographer_ros/cartographer_ros/node.h @@ -179,6 +179,7 @@ class Node { tf2_ros::TransformBroadcaster tf_broadcaster_; absl::Mutex mutex_; + std::unique_ptr metrics_registry_; MapBuilderBridge map_builder_bridge_ GUARDED_BY(mutex_); ::ros::NodeHandle node_handle_; @@ -225,8 +226,6 @@ class Node { // simulation time is standing still. This prevents overflowing the transform // listener buffer by publishing the same transforms over and over again. ::ros::Timer publish_local_trajectory_data_timer_; - - std::unique_ptr metrics_registry_; }; } // namespace cartographer_ros