blob: 4b921d2be7178c6ed0e528e4ee51dd9bc4f3dbd6 (
plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
|
diff -Naur nav2-util-1.1.20_orig/include/nav2_util/lifecycle_node.hpp nav2-util-1.1.20/include/nav2_util/lifecycle_node.hpp
--- nav2-util-1.1.20_orig/include/nav2_util/lifecycle_node.hpp 2024-01-01 00:00:00.000000000 +0800
+++ nav2-util-1.1.20/include/nav2_util/lifecycle_node.hpp 2024-01-01 00:00:00.000000000 +0800
@@ -204,7 +204,7 @@
std::shared_ptr<tf2_ros::Buffer> tf_;
std::shared_ptr<tf2_ros::TransformListener> transform_listener_;
- std::unique_ptr<bond::Bond> bond_{nullptr};
+ std::shared_ptr<bond::Bond> bond_{nullptr};
};
} // namespace nav2_util
diff -Naur nav2-util-1.1.20_orig/src/lifecycle_node.cpp nav2-util-1.1.20/src/lifecycle_node.cpp
--- nav2-util-1.1.20_orig/src/lifecycle_node.cpp 2024-01-01 00:00:00.000000000 +0800
+++ nav2-util-1.1.20/src/lifecycle_node.cpp 2024-01-01 00:00:00.000000000 +0800
@@ -73,7 +73,7 @@
{
RCLCPP_INFO(get_logger(), "Creating bond (%s) to lifecycle manager.", this->get_name());
- bond_ = std::make_unique<bond::Bond>(
+ bond_ = std::make_shared<bond::Bond>(
std::string("bond"),
this->get_name(),
shared_from_this());
|