Skip to content

Commit

Permalink
Merge pull request #197 from bjsowa/shared-from-this-fix
Browse files Browse the repository at this point in the history
Don't use shared_from_this in the constructor
  • Loading branch information
jonbinney authored Jul 22, 2024
2 parents e2ed8c3 + 8cb26af commit fb10f8b
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 2 deletions.
3 changes: 2 additions & 1 deletion src/scan_to_cloud_filter_chain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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")
{
Expand Down
2 changes: 1 addition & 1 deletion src/scan_to_scan_filter_chain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ ScanToScanFilterChain::ScanToScanFilterChain(
tf_filter_.reset(
new tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>(
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<double>(tf_filter_tolerance_));

Expand Down

0 comments on commit fb10f8b

Please sign in to comment.