Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add Lazy subscription #195

Merged
merged 3 commits into from
Jul 28, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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()
bjsowa marked this conversation as resolved.
Show resolved Hide resolved

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>
bjsowa marked this conversation as resolved.
Show resolved Hide resolved
<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);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It looks like SensorDataQoS sets the "depth" (number of messages to hang on to in case publishing gets backed up) to 5. If there's not a good reason to change it, I'd prefer to keep it to 10 (see the original create_publisher call). There are also some other QoS settings that differ in SensorDataQoS from just what you get if you just pass in the depth as a number. I think that for this PR, it would be better not to change those. You could do so in a separate PR, but we'd want to go over each element of the QoS struct and discuss why it should be changed.

} else {
cloud_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("cloud_filtered",
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same thing - prefer not to change QoS in this PR unless there is a strong reason

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",
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same thing as in the scan_to_cloud_filter_chain.cpp - I'd prefer we just pass in 1000 as the QoS for this PR.

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>(
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same

"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
Loading