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.master
parent
5f1ff900b4
commit
eb86ba6e7c
|
@ -179,6 +179,7 @@ class Node {
|
|||
tf2_ros::TransformBroadcaster tf_broadcaster_;
|
||||
|
||||
absl::Mutex mutex_;
|
||||
std::unique_ptr<cartographer_ros::metrics::FamilyFactory> 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<cartographer_ros::metrics::FamilyFactory> metrics_registry_;
|
||||
};
|
||||
|
||||
} // namespace cartographer_ros
|
||||
|
|
Loading…
Reference in New Issue