Skip to content

Commit

Permalink
Add lazy subscription to filter chains
Browse files Browse the repository at this point in the history
  • Loading branch information
bjsowa committed Jul 23, 2024
1 parent eaaaeab commit 280113d
Show file tree
Hide file tree
Showing 6 changed files with 74 additions and 12 deletions.
4 changes: 4 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,10 @@ ament_auto_find_build_dependencies()
# Build
##############################################################################

if($ENV{ROS_DISTRO} STREQUAL "humble")
add_compile_definitions(IS_HUMBLE)
endif()

ament_auto_add_library(laser_scan_filters SHARED src/laser_scan_filters.cpp)
ament_auto_add_library(laser_filter_chains SHARED
src/scan_to_cloud_filter_chain.cpp
Expand Down
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
<depend>rclcpp</depend>
<depend>rclcpp_lifecycle</depend>
<depend>rclcpp_components</depend>
<depend>ros_environment</depend>
<depend>sensor_msgs</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
Expand Down
40 changes: 32 additions & 8 deletions src/scan_to_cloud_filter_chain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,7 @@ ScanToCloudFilterChain::ScanToCloudFilterChain(
laser_max_range_(DBL_MAX),
buffer_(this->get_clock()),
tf_(buffer_),
sub_(this, "scan", rmw_qos_profile_sensor_data),
filter_(sub_, buffer_, "", 50, this->get_node_logging_interface(),
filter_(scan_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 All @@ -55,13 +54,19 @@ ScanToCloudFilterChain::ScanToCloudFilterChain(
read_only_desc.read_only = true;

// Declare parameters
#ifndef IS_HUMBLE
this->declare_parameter("lazy_subscription", false, read_only_desc);
#endif
this->declare_parameter("high_fidelity", false, read_only_desc);
this->declare_parameter("notifier_tolerance", 0.03, read_only_desc);
this->declare_parameter("target_frame", "base_link", read_only_desc);
this->declare_parameter("incident_angle_correction", true, read_only_desc);
this->declare_parameter("laser_max_range", DBL_MAX, read_only_desc);

// Get parameters
#ifndef IS_HUMBLE
this->get_parameter("lazy_subscription", lazy_subscription_);
#endif
this->get_parameter("high_fidelity", high_fidelity_);
this->get_parameter("notifier_tolerance", tf_tolerance_);
this->get_parameter("target_frame", target_frame_);
Expand All @@ -80,11 +85,30 @@ ScanToCloudFilterChain::ScanToCloudFilterChain(
this->get_node_timers_interface());
buffer_.setCreateTimerInterface(timer_interface);

sub_.subscribe(this, "scan", rmw_qos_profile_sensor_data);

filter_.connectInput(sub_);

cloud_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("cloud_filtered", 10);
#ifndef IS_HUMBLE
if (lazy_subscription_) {
rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
[this](rclcpp::MatchedInfo & s)
{
if (s.current_count == 0) {
scan_sub_.unsubscribe();
} else if (!scan_sub_.getSubscriber()) {
scan_sub_.subscribe(this, "scan", rmw_qos_profile_sensor_data);
}
};
cloud_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("cloud_filtered",
rclcpp::SensorDataQoS(), pub_options);
} else {
cloud_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("cloud_filtered",
rclcpp::SensorDataQoS());
scan_sub_.subscribe(this, "scan", rmw_qos_profile_sensor_data);
}
#else
cloud_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>(
"cloud_filtered", rclcpp::SensorDataQoS());
scan_sub_.subscribe(this, "scan", rmw_qos_profile_sensor_data);
#endif

cloud_filter_chain_.configure(
"cloud_filter_chain",
Expand Down
5 changes: 4 additions & 1 deletion src/scan_to_cloud_filter_chain.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,14 +62,17 @@ class ScanToCloudFilterChain : public rclcpp::Node
tf2_ros::Buffer buffer_;
tf2_ros::TransformListener tf_;

message_filters::Subscriber<sensor_msgs::msg::LaserScan> sub_;
message_filters::Subscriber<sensor_msgs::msg::LaserScan> scan_sub_;
tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan> filter_;

filters::FilterChain<sensor_msgs::msg::PointCloud2> cloud_filter_chain_;
filters::FilterChain<sensor_msgs::msg::LaserScan> scan_filter_chain_;
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr cloud_pub_;

// Parameters
#ifndef IS_HUMBLE
bool lazy_subscription_;
#endif
bool high_fidelity_; // High fidelity (interpolating time across scan)
double tf_tolerance_;
std::string target_frame_; // Target frame for high fidelity result
Expand Down
33 changes: 30 additions & 3 deletions src/scan_to_scan_filter_chain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@ ScanToScanFilterChain::ScanToScanFilterChain(
: rclcpp::Node("scan_to_scan_filter_chain", ns, options),
tf_(NULL),
buffer_(this->get_clock()),
scan_sub_(this, "scan", rmw_qos_profile_sensor_data),
tf_filter_(NULL),
filter_chain_("sensor_msgs::msg::LaserScan")
{
Expand All @@ -51,10 +50,16 @@ ScanToScanFilterChain::ScanToScanFilterChain(
read_only_desc.read_only = true;

// Declare parameters
#ifndef IS_HUMBLE
this->declare_parameter("lazy_subscription", false, read_only_desc);
#endif
this->declare_parameter("tf_message_filter_target_frame", "", read_only_desc);
this->declare_parameter("tf_message_filter_tolerance", 0.03, read_only_desc);

// Get parameters
#ifndef IS_HUMBLE
this->get_parameter("lazy_subscription", lazy_subscription_);
#endif
this->get_parameter("tf_message_filter_target_frame", tf_message_filter_target_frame_);
this->get_parameter("tf_message_filter_tolerance", tf_filter_tolerance_);

Expand All @@ -80,8 +85,30 @@ ScanToScanFilterChain::ScanToScanFilterChain(
std::placeholders::_1));
}

// Advertise output
output_pub_ = this->create_publisher<sensor_msgs::msg::LaserScan>("scan_filtered", 1000);
#ifndef IS_HUMBLE
if (lazy_subscription_) {
rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
[this](rclcpp::MatchedInfo & s)
{
if (s.current_count == 0) {
scan_sub_.unsubscribe();
} else if (!scan_sub_.getSubscriber()) {
scan_sub_.subscribe(this, "scan", rmw_qos_profile_sensor_data);
}
};
output_pub_ = this->create_publisher<sensor_msgs::msg::LaserScan>("scan_filtered",
rclcpp::SensorDataQoS(), pub_options);
} else {
output_pub_ = this->create_publisher<sensor_msgs::msg::LaserScan>("scan_filtered",
rclcpp::SensorDataQoS());
scan_sub_.subscribe(this, "scan", rmw_qos_profile_sensor_data);
}
#else
output_pub_ = this->create_publisher<sensor_msgs::msg::LaserScan>(
"scan_filtered", rclcpp::SensorDataQoS());
scan_sub_.subscribe(this, "scan", rmw_qos_profile_sensor_data);
#endif
}

// Destructor
Expand Down
3 changes: 3 additions & 0 deletions src/scan_to_scan_filter_chain.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,9 @@ class ScanToScanFilterChain : public rclcpp::Node
rclcpp::Publisher<sensor_msgs::msg::LaserScan>::SharedPtr output_pub_;

// Parameters
#ifndef IS_HUMBLE
bool lazy_subscription_;
#endif
std::string tf_message_filter_target_frame_;
double tf_filter_tolerance_;

Expand Down

0 comments on commit 280113d

Please sign in to comment.