Skip to content

Commit 8cb26af

Browse files
committed
Don't use shared_from_this in the constructor
1 parent e2ed8c3 commit 8cb26af

File tree

2 files changed

+3
-2
lines changed

2 files changed

+3
-2
lines changed

src/scan_to_cloud_filter_chain.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,8 @@ ScanToCloudFilterChain::ScanToCloudFilterChain(
4646
buffer_(this->get_clock()),
4747
tf_(buffer_),
4848
sub_(this, "scan", rmw_qos_profile_sensor_data),
49-
filter_(sub_, buffer_, "", 50, this->shared_from_this()),
49+
filter_(sub_, buffer_, "", 50, this->get_node_logging_interface(),
50+
this->get_node_clock_interface()),
5051
cloud_filter_chain_("sensor_msgs::msg::PointCloud2"),
5152
scan_filter_chain_("sensor_msgs::msg::LaserScan")
5253
{

src/scan_to_scan_filter_chain.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,7 @@ ScanToScanFilterChain::ScanToScanFilterChain(
5656
tf_filter_.reset(
5757
new tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>(
5858
scan_sub_, buffer_, "",
59-
50, this->shared_from_this()));
59+
50, this->get_node_logging_interface(), this->get_node_clock_interface()));
6060
tf_filter_->setTargetFrame(tf_message_filter_target_frame);
6161
tf_filter_->setTolerance(std::chrono::duration<double>(tf_filter_tolerance_));
6262

0 commit comments

Comments
 (0)