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

Conversation

bjsowa
Copy link
Contributor

@bjsowa bjsowa commented Jul 16, 2024

Implements #194 .

this requires Matched publisher events, which are supported from ROS Iron onward, so a separate branch for ROS Humble is required.

This PR also fixes some issues with parameters in scan filter chains:

  1. Explicitly declare all parameters , otherwise get_parameter won't work.
  2. Remove unused parameters.
  3. Add read-only flag to all parameters as the filter chains don't support dynamically changing them.

I also changed spin_some to spin as I see absolutely no reason to use the first method.

I can split this PR into multiple ones if needed,

@jonbinney
Copy link
Contributor

This seems like a good feature, thanks @bjsowa ! I've got a couple other PRs to review first, but hoping to get to this soon.

@jonbinney
Copy link
Contributor

Actually looks like #188 created some merge conflicts for this PR when I merged it. Could you fix those before I review the code?

@bjsowa
Copy link
Contributor Author

bjsowa commented Jul 16, 2024

I manually reapplied the changes as there were too many conflicts.

The first 2 commits are not related to lazy subscription functionality. I can split them into separate PRs.

The third commit adds the lazy subscription and drops support for ROS Humble.

@bjsowa bjsowa marked this pull request as draft July 17, 2024 11:31
@bjsowa
Copy link
Contributor Author

bjsowa commented Jul 17, 2024

I split this PR to only include the lazy subscription part. @jonbinney I would appreciate if you could look at #197, #198 and #199 first

@jonbinney
Copy link
Contributor

Thanks for splitting this up, that will make it easier to review. Quick question - is it feasible to change this to avoid branching for humble (for example by using preprocessor macros?). As soon as we branch for humble we've got to start cherry picking bug fixes, which gets painful quickly.

@bjsowa
Copy link
Contributor Author

bjsowa commented Jul 17, 2024

This should now build on Humble. I took some inspiration from depthai-ros, though I'm now 100% sure it will work on the buildfarm

@bjsowa bjsowa marked this pull request as ready for review July 23, 2024 22:09
@bjsowa
Copy link
Contributor Author

bjsowa commented Jul 23, 2024

@jonbinney As all the "child" PR are merged, this one is ready for review. I squashed all commits as it was mostly resolving merge conflicts.

CMakeLists.txt Show resolved Hide resolved
package.xml Outdated Show resolved Hide resolved
@bjsowa bjsowa requested a review from jonbinney July 25, 2024 03:55
Copy link
Contributor

@jonbinney jonbinney left a comment

Choose a reason for hiding this comment

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

Looks good except for making sure we keep the QoS settings the same. After that is fixed, this should be good to merge!

}
};
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.

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

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.

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

CMakeLists.txt Show resolved Hide resolved
@bjsowa
Copy link
Contributor Author

bjsowa commented Jul 27, 2024

@jonbinney I kept the old QoS settings. A depth value of 1000 seems like an overkill (especially for a reliable publisher) but I'll stick to changes only related to lazy subscription.

@bjsowa bjsowa requested a review from jonbinney July 27, 2024 20:57
@jonbinney
Copy link
Contributor

Looks good! Yes, 1000 is a lot of scans to keep. I suspect the original thought was "lets keep as many as we can without using crazy amounts of memory". Typical 2D scanners may have around 1000 ranges and intensities per scan, which would be about (1000 points) * (4 bytes for intensity + 4 bytes for range) = 8000 bytes per scan. So 1000 scans would be around 8 MB, which would probably be fine even on most single board computers.

As far as reliability, even if the QoS is set to "reliable", if you are streaming data over wifi (say running SLAM on a desktop while a mobile robot drives around a building) you may lose connection here and there, especially when transitioning between access points. It's nice not to lose those scans.

Thanks for this PR! And the others you made - they are big improvements!

@jonbinney jonbinney merged commit 9dbd42e into ros-perception:ros2 Jul 28, 2024
5 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants