This package provides ROS 2 service servers and/or action servers that wrap lower-level utilities (e.g., PCL, perception, planning, or motion helpers) into reusable ROS 2 nodes.
These nodes are intended to be used as modular building blocks in larger systems such as state machines, behavior trees, or task planners.
This package is built for ROS 2 and has been tested on ROS 2 Jazzy.
- Implements one or more ROS 2 service servers and/or action servers
- Designed to be called by higher-level coordination logic (FlexBE, SMACH, Behavior Trees, etc.)
- Focuses on wrapping non-ROS utilities into clean ROS 2 interfaces
- Intended for composition into larger manipulation or perception pipelines
This package depends on the following:
- Ubuntu 24.04 (tested)
- ROS 2 Jazzy
- rclcpp
- sensor_msgs
- geometry_msgs
- tf2_ros
- tf2_sensor_msgs
- tf2_geometry_msgs
- pcl_ros
- pcl_conversions
- PCL
From the root of your ROS 2 workspace:
colcon build --packages-select pcl_ros2
source install/setup.bashThe nodes can be run directlyor implemented into a launch file as demonstrated below:
ros2 run pcl_ros2 get_pointcloud_serviceexample.launch.py
def launch_setup(context, *args, **kwargs):
robot_description = ...
...
# example launch file implementation for get_pointcloud_service node
get_pointcloud_service_node = Node(
package="pcl_ros2",
executable="get_pointcloud_service",
name="get_pointcloud_service",
output="screen",
parameters=[
{"default_camera_topic": "/camera/depth/points"},
{"target_frame": "panda_link0"},
{"timeout_sec": 3.0},
],
)
return [
get_pointcloud_service,
]A full example launch file implementation can be found at gazebo_move_group_flexbe.launch.py
| Service Name | Type | Description |
|---|---|---|
/euclidean_clustering_service |
srv/EuclideanClustering |
Given a sensor_msgs/PointCloud2 input and a geometry_msgs/PoseStamped camera_pose, extract clusters of points and return the pcl_msgs/PointIndices target_cluster_indices and pcl_msgs/PointIndices[] obstacle_cluster_indices |
/filter_by_indices_service |
srv/FilterByIndices |
Given a sensor_msgs/PointCloud2 input_cloud and pcl_msgs/PointIndices target_indices, return the sensor_msgs/PointCloud2 filtered_cloud which can be found at the specified set of indices |
/get_point_cloud_service |
srv/GetPointCloud |
Given a string camera_topic, string target_frame, and float32 timeout_sec, capture a pointcloud snapshot and return the sensor_msgs/PointCloud2 cloud_out and geometry_msgs/PoseStamped camera_pose |
/passthrough_filter_service |
srv/PassthroughFilter |
Given a sensor_msgs/PointCloud2 input, float32 upper_limit, float32 lower_limit and string field, remove points which exist beyond the upper and lower limits on the field axis and return sensor_msgs/PointCloud2 filtered |
/plane_segmentation_service |
srv/PlaneSegmentation |
Given a sensor_msgs/PointCloud2 input, segment out a plane and return sensor_msgs/PointCloud2 without_plane |
/voxel_grid_service |
srv/VoxelGridFilter |
Given a sensor_msgs/PointCloud2 input, downsample and return sensor_msgs/PointCloud2 filtered |
The following strategy is used when implementing a PCL utility by wrapping it within ROS2
Utilities are written in an object-oriented style in whichever language their API exists, in this case PCL utilities are C++
#include ...
// create a class for your utility
class MyFilterNode : public rclcpp::Node
{
public:
MyFilterNode() : Node("my_filter_node")
{
// instantiate a service in your object constructor
service_ = this->create_service<pcl_ros2::srv::MyFilter>(
"my_filter",
std::bind(&VoxelGridFilterNode::handle_request, this, std::placeholders::_1, std::placeholders::_2)
);
RCLCPP_INFO(this->get_logger(), "My Filter service ready.");
}
private:
rclcpp::Service<pcl_ros2::srv::MyFilter>::SharedPtr service_;
// generic "handle_request" function to perform the expected filtering operation
void handle_request(
const std::shared_ptr<pcl_ros2::srv::MyFilter::Request> request,
std::shared_ptr<pcl_ros2::srv::MyFilter::Response> response)
{
// read the request (a ros2 message type), and convert FROM ROS2 TO PCL
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in(new pcl::PointCloud<pcl::PointXYZ>());
pcl::fromROSMsg(request->input, *cloud_in);
/* perform filtering functions here
*
* this could be downsampling, filtering out a segment, etc., tutorials and examples can be found at:
* https://pcl.readthedocs.io/projects/tutorials/en/master/
* ...
*
*/
// after processing, turn your PCL message TO a ROS2 message
pcl::toROSMsg(*cloud_out, response->filtered);
response->filtered.header = request->input.header;
}
};
int main(int argc, char **argv)
{
// initialize and spin your node in the background
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<VoxelGridFilterNode>());
rclcpp::shutdown();
return 0;
}The simplest example implemented in this package is likely src/voxel_grid_filter_service.cpp, check out that code for more information or visit the Point Cloud Library Documentation page for more information and tutorials