From 8cb26af562c8129f2e3abbb10952f10ec0a50c2d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Wed, 17 Jul 2024 10:57:22 +0000 Subject: [PATCH] Don't use shared_from_this in the constructor --- src/scan_to_cloud_filter_chain.cpp | 3 ++- src/scan_to_scan_filter_chain.cpp | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/src/scan_to_cloud_filter_chain.cpp b/src/scan_to_cloud_filter_chain.cpp index 66a4e89..6b78378 100644 --- a/src/scan_to_cloud_filter_chain.cpp +++ b/src/scan_to_cloud_filter_chain.cpp @@ -46,7 +46,8 @@ ScanToCloudFilterChain::ScanToCloudFilterChain( buffer_(this->get_clock()), tf_(buffer_), sub_(this, "scan", rmw_qos_profile_sensor_data), - filter_(sub_, buffer_, "", 50, this->shared_from_this()), + filter_(sub_, buffer_, "", 50, this->get_node_logging_interface(), + this->get_node_clock_interface()), cloud_filter_chain_("sensor_msgs::msg::PointCloud2"), scan_filter_chain_("sensor_msgs::msg::LaserScan") { diff --git a/src/scan_to_scan_filter_chain.cpp b/src/scan_to_scan_filter_chain.cpp index 45fa445..df51038 100644 --- a/src/scan_to_scan_filter_chain.cpp +++ b/src/scan_to_scan_filter_chain.cpp @@ -56,7 +56,7 @@ ScanToScanFilterChain::ScanToScanFilterChain( tf_filter_.reset( new tf2_ros::MessageFilter( scan_sub_, buffer_, "", - 50, this->shared_from_this())); + 50, this->get_node_logging_interface(), this->get_node_clock_interface())); tf_filter_->setTargetFrame(tf_message_filter_target_frame); tf_filter_->setTolerance(std::chrono::duration(tf_filter_tolerance_));