Skip to content

Conversation

@AntoBrandi
Copy link
Contributor

@AntoBrandi AntoBrandi commented Aug 26, 2025

Replaces #505 and #501 by properly cherry-picking ros2 commits into humble.

Addresses: #423

Additionally, to fix the build on Humble, small fixes were required:

  • QoS profiles to use .get_rmw_qos_profile() in subscribers
  • Disable lazy subscribers as pub_options.event_callbacks.matched_callback = [this](rclcpp::MatchedInfo & /*info*/) ... is not available in Humble

ivanpauno and others added 30 commits August 26, 2025 10:35
* Migrate pcl_ros pcd_to_pointcloud tool

Signed-off-by: Ivan Santiago Paunovic <[email protected]>

* Remove log used for debugging

Signed-off-by: Ivan Santiago Paunovic <[email protected]>

* Undo unnecessary changes

Signed-off-by: Ivan Santiago Paunovic <[email protected]>

* Remove commented out code

Signed-off-by: Ivan Santiago Paunovic <[email protected]>

* Address peer review comments

Signed-off-by: Ivan Santiago Paunovic <[email protected]>

* rename node

Signed-off-by: Ivan Santiago Paunovic <[email protected]>
…ption#374)

* Remove name of nonexistent PCL component (core)
Probably, common is meant, which is also requested

* Add boost include, missing in upcoming PCL versions
Was removed in pcl/conversion.h here: PointCloudLibrary/pcl@292593a
* migrate pcl_nodelet.hpp to pcl_node.hpp
TODOs
- lazy subscription
- cpplint, uncrustify
- type adaptation

Signed-off-by: Daisuke Sato <[email protected]>

* rename latched_indices to transient_local_indices

Signed-off-by: Daisuke Sato <[email protected]>

* - remove some TODOs
- change pub_output_ type

Signed-off-by: Daisuke Sato <[email protected]>

* remove TODOs

Signed-off-by: Daisuke Sato <[email protected]>

* use template instead of PublisherBase

Signed-off-by: Daisuke Sato <[email protected]>

Signed-off-by: Daisuke Sato <[email protected]>
* migrate abstract filter node

Signed-off-by: Daisuke Sato <[email protected]>

* remove use_frame_params from constructor and make a function for the logic

Signed-off-by: Daisuke Sato <[email protected]>

Signed-off-by: Daisuke Sato <[email protected]>
* - migrate extract_indices filter
- add test to check if filter node/component output result

Signed-off-by: Daisuke Sato <[email protected]>

* add test_depend to package.xml

Signed-off-by: Daisuke Sato <[email protected]>

* add launch_testing_ros as test_depend too

Signed-off-by: Daisuke Sato <[email protected]>

* fixed test not to depend on ros2cli

Signed-off-by: Daisuke Sato <[email protected]>

---------

Signed-off-by: Daisuke Sato <[email protected]>
* migrate passthrough and project_inliers filters

Signed-off-by: Daisuke Sato <[email protected]>

* - remove throwing runtime_error (result always true)
- use get_subscription_count()

Signed-off-by: Daisuke Sato <[email protected]>

* change comparison operator

Signed-off-by: Daisuke Sato <[email protected]>

---------

Signed-off-by: Daisuke Sato <[email protected]>
…rception#399)

* Add the RadiusOutlierRemoval filter.

* Lint

* PLay iit again, Linty Sam.

* Header order

* This is now just getting embarrassing

* Move parameter to class constructor.
* Add squashed commit for CropBox filter

* Lint
…s-perception#398)

* Add the VoxelGrid filter (squash commit)

* Revert the change that brings in separate leaf sizes
…s-perception#406)

* Lint!

* Fix flake8 errors

* Fix clang-tidy errors

* Remove [[maybe_unused]]
* Set sensor data QoS to filter subscribers

* Fix format for consistency

* Fix type

* Fix style format
* porting pointcoud_to_pcd to ros2

* and rgb option and swich format

* fix exception handling
…on#452)

* Fix `Could NOT find Boost (missing: Boost_INCLUDE_DIR)`

Fix ros-perception#446
See the discussion at ros-perception#447

* Fix ament_cpplint

* Fix ament_lint_cmake
* Add lazy feature

* Call createPublishers() from derived class

* Check subscriber
Adraub and others added 13 commits August 26, 2025 10:43
)

* Fix pcd timestamp format output in pointcloud_to_pcd

Fix pcd timestamp indentation offset if nanosec value is less than 100000000 ns

* Fix coding style

Fixes uncrustify CI error
…ds into a Single PCD (ros-perception#479)

- Introduces CombinedPointCloudToPCD, a ROS 2 component node that:
  - Subscribes to sensor_msgs/PointCloud2 and accumulates multiple clouds.
  - Optionally transforms each cloud to a fixed frame.
  - Allows saving a combined PCD file in either binary, compressed, or ASCII format.
  - Permits saving on node shutdown or at a configurable timer interval.
- Preserves the BSD License from Willow Garage and references original authors.
- Useful for aggregating data from multiple scans into one dataset.
…on#494)

`bag_to_pcd_lib` was linked publicly to `rosbag2_transport`, which
caused downstream packages to also try linking against it. However,
`rosbag2_transport` is an internal dependency, and we don't want to
expose it to downstream packages.

Since `bag_to_pcd_lib` is a tool with no public headers, it doesn't need
to expose this dependency. Switching to private linking resolves the
issue and keeps the dependency internal.
`ament_target_dependencies` is deprecated rolling, so we should convert
all usages to `target_link_libraries`. See also the following
discussion:

ament/ament_cmake#572
@AntoBrandi AntoBrandi changed the title Humble Humble Porting Aug 26, 2025
@AntoBrandi
Copy link
Contributor Author

AntoBrandi commented Aug 26, 2025

A note on my last commit: I can try to make it work on different ROS distros so that it can be cherry-picked in the master. I can use the same approach used in the laser_filters package.
Alternatively, the simpler ros2_control approach can also be used.

This way, future syncs should be easier

@Rayman
Copy link
Contributor

Rayman commented Aug 29, 2025

Thank you for putting the effort to cherry-pick all relevant commits to humble

I have questions about two specific commits:

  1. Modern CMake: This changes the exported targets. Will this cause downstream compilation failures?
  2. Fix warning: 'subscribe<>' is deprecated: This commit is only needed for jazzy and higher. You corrected this in a lter commit but it might be better to just remove this commit from this PR so you don't need to correct it
  3. In your last commit you did a linter fix. Does it make more sense to disable uncrustify so we can freely cherry-pick from the ros2 branch?

In general I'm a bit worries the changes will lead to downstream compilation failures. Can @SteveMacenski maybe give his opinion about this PR?

Btw, I'm going on vacation for 3 weeks so it might take a while before I come back to this.

@AntoBrandi
Copy link
Contributor Author

My original idea was to minimize the differences between the ros2 branch and the humble branch, so that future commits could be easily backported to humble.
However, I understand your point, especially for the possible downstream compilation failures.
In that case, we can follow a different approach: Making the ros2 branch buildable on humble, like the humble_main branch in Nav2

@SteveMacenski
Copy link
Member

I wouldn't change the exported targets / variables in an already released distribution. Rclcpp I see still uses the old ament macro for this in Humble https://github.com/ros2/rclcpp/blob/humble/rclcpp/CMakeLists.txt#L193-L207 so that makes me further think we shouldn't backport that to humble as a ABI breaking change.

P.S. I don't particularly recommend the humble_main strategy, its a pain in the ass to keep synced up and I've actually already since decided to stop after introducing nav2_ros_common due to extensive use of ROS 2 advanced features not available in Humble at all. It won't be updated post-July 2025 (though up to date in a broad sense compared to humble itself). The changes for targets + APIs makes keeping Humble x Rolling unrealistically difficult to maintain compatibility for in a project unless someone wants to take explicit ownership for it as a prime objective with regular care and upkeep.

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.