Skip to content

Commit 4fcafae

Browse files
authored
Merge pull request #251 from ros-perception/mergify/bp/rolling/pr-250
Expose depth_publisher param (backport #250)
2 parents 1f7bde2 + 02e9e92 commit 4fcafae

File tree

2 files changed

+8
-3
lines changed

2 files changed

+8
-3
lines changed

src/scan_to_scan_filter_chain.cpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -60,13 +60,15 @@ ScanToScanFilterChain::ScanToScanFilterChain(
6060
#endif
6161
this->declare_parameter("tf_message_filter_target_frame", "", read_only_desc);
6262
this->declare_parameter("tf_message_filter_tolerance", 0.03, read_only_desc);
63+
this->declare_parameter("scan_filtered_history_depth", 1000);
6364

6465
// Get parameters
6566
#ifdef RCLCPP_SUPPORTS_MATCHED_CALLBACKS
6667
this->get_parameter("lazy_subscription", lazy_subscription_);
6768
#endif
6869
this->get_parameter("tf_message_filter_target_frame", tf_message_filter_target_frame_);
6970
this->get_parameter("tf_message_filter_tolerance", tf_filter_tolerance_);
71+
this->get_parameter("scan_filtered_history_depth", scan_filtered_history_depth_);
7072

7173
if (!tf_message_filter_target_frame_.empty()) {
7274
tf_.reset(new tf2_ros::TransformListener(buffer_));
@@ -103,13 +105,15 @@ ScanToScanFilterChain::ScanToScanFilterChain(
103105
}
104106
};
105107
output_pub_ = this->create_publisher<sensor_msgs::msg::LaserScan>(
106-
"scan_filtered", 1000, pub_options);
108+
"scan_filtered", scan_filtered_history_depth_, pub_options);
107109
} else {
108-
output_pub_ = this->create_publisher<sensor_msgs::msg::LaserScan>("scan_filtered", 1000);
110+
output_pub_ = this->create_publisher<sensor_msgs::msg::LaserScan>(
111+
"scan_filtered", scan_filtered_history_depth_);
109112
scan_sub_.subscribe(this, "scan", rclcpp::SensorDataQoS());
110113
}
111114
#else
112-
output_pub_ = this->create_publisher<sensor_msgs::msg::LaserScan>("scan_filtered", 1000);
115+
output_pub_ = this->create_publisher<sensor_msgs::msg::LaserScan>(
116+
"scan_filtered", scan_filtered_history_depth_);
113117
scan_sub_.subscribe(this, "scan", rclcpp::SensorDataQoS());
114118
#endif
115119
}

src/scan_to_scan_filter_chain.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -65,6 +65,7 @@ class ScanToScanFilterChain : public rclcpp::Node
6565
#endif
6666
std::string tf_message_filter_target_frame_;
6767
double tf_filter_tolerance_;
68+
int scan_filtered_history_depth_;
6869

6970
// Diagnostic updater
7071
diagnostic_updater::Heartbeat heartbeat_diagnostics_;

0 commit comments

Comments
 (0)