Skip to content

Commit f10aa77

Browse files
authored
Fix bad_weak_ptr in createBond() by using shared_ptr (#5341)
* Update lifecycle_node.hpp :: createBond() -> bond_ type fix Signed-off-by: Dhruv Patel <dhruvpatel2991998@gmail.com> * Update lifecycle_node.hpp Signed-off-by: Dhruv Patel <dhruvpatel2991998@gmail.com> * Update lifecycle_node.hpp: removing extra spaces Signed-off-by: Dhruv Patel <dhruvpatel2991998@gmail.com> --------- Signed-off-by: Dhruv Patel <dhruvpatel2991998@gmail.com>
1 parent 5021b51 commit f10aa77

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

nav2_ros_common/include/nav2_ros_common/lifecycle_node.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -313,7 +313,7 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
313313
if (bond_heartbeat_period > 0.0) {
314314
RCLCPP_INFO(get_logger(), "Creating bond (%s) to lifecycle manager.", this->get_name());
315315

316-
bond_ = std::make_unique<bond::Bond>(
316+
bond_ = std::make_shared<bond::Bond>(
317317
std::string("bond"),
318318
this->get_name(),
319319
shared_from_this());
@@ -392,7 +392,7 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
392392

393393
// Connection to tell that server is still up
394394
std::unique_ptr<rclcpp::PreShutdownCallbackHandle> rcl_preshutdown_cb_handle_{nullptr};
395-
std::unique_ptr<bond::Bond> bond_{nullptr};
395+
std::shared_ptr<bond::Bond> bond_{nullptr};
396396
double bond_heartbeat_period{0.1};
397397
rclcpp::TimerBase::SharedPtr autostart_timer_;
398398

0 commit comments

Comments
 (0)