Skip to content

Commit de820a3

Browse files
committed
feat(pcl_ros): port pointcloud_to_pcd to ROS 2, backport combined_pointcloud_to_pcd from ros2 branch
- pointcloud_to_pcd was never ported from ROS 1; its CMakeLists entry was also commented out. Port replaces ros/ros.h, ros::NodeHandle, boost::shared_ptr with rclcpp equivalents, uses pcl/common/io.h for PCL >= 1.12 compatibility, and registers as an rclcpp component. - combined_pointcloud_to_pcd backported from ros2 branch with two Humble-compatible adaptations: pcl_ros::transformPointCloud replaces the unavailable pcl::transformPointCloud(PCLPointCloud2) overload; direct buffer append replaces the conflicting pcl::concatenatePointCloud overload. Accumulates as pcl::PCLPointCloud2 to preserve all fields. - CMakeLists.txt: add both tools as shared libs via rclcpp_components. - package.xml: add tf2_eigen dependency.
1 parent 67a5c2b commit de820a3

4 files changed

Lines changed: 356 additions & 106 deletions

File tree

pcl_ros/CMakeLists.txt

Lines changed: 29 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@ find_package(rclcpp_components REQUIRED)
2020
find_package(sensor_msgs REQUIRED)
2121
find_package(geometry_msgs REQUIRED)
2222
find_package(tf2 REQUIRED)
23+
find_package(tf2_eigen REQUIRED)
2324
find_package(tf2_geometry_msgs REQUIRED)
2425
find_package(tf2_ros REQUIRED)
2526

@@ -29,6 +30,7 @@ set(dependencies
2930
sensor_msgs
3031
geometry_msgs
3132
tf2
33+
tf2_eigen
3234
tf2_geometry_msgs
3335
tf2_ros
3436
EIGEN3
@@ -133,8 +135,31 @@ rclcpp_components_register_node(pcd_to_pointcloud_lib
133135
PLUGIN "pcl_ros::PCDPublisher"
134136
EXECUTABLE pcd_to_pointcloud)
135137
#
136-
#add_executable(pointcloud_to_pcd tools/pointcloud_to_pcd.cpp)
137-
#target_link_libraries(pointcloud_to_pcd ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${PCL_LIBRARIES})
138+
add_library(pointcloud_to_pcd_lib SHARED tools/pointcloud_to_pcd.cpp)
139+
target_link_libraries(pointcloud_to_pcd_lib
140+
pcl_ros_tf
141+
${PCL_LIBRARIES})
142+
target_include_directories(pointcloud_to_pcd_lib PUBLIC
143+
${PCL_INCLUDE_DIRS})
144+
ament_target_dependencies(pointcloud_to_pcd_lib
145+
${dependencies}
146+
rclcpp_components)
147+
rclcpp_components_register_node(pointcloud_to_pcd_lib
148+
PLUGIN "pcl_ros::PointCloudToPCD"
149+
EXECUTABLE pointcloud_to_pcd)
150+
151+
add_library(combined_pointcloud_to_pcd_lib SHARED tools/combined_pointcloud_to_pcd.cpp)
152+
target_link_libraries(combined_pointcloud_to_pcd_lib
153+
pcl_ros_tf
154+
${PCL_LIBRARIES})
155+
target_include_directories(combined_pointcloud_to_pcd_lib PUBLIC
156+
${PCL_INCLUDE_DIRS})
157+
ament_target_dependencies(combined_pointcloud_to_pcd_lib
158+
${dependencies}
159+
rclcpp_components)
160+
rclcpp_components_register_node(combined_pointcloud_to_pcd_lib
161+
PLUGIN "pcl_ros::CombinedPointCloudToPCD"
162+
EXECUTABLE combined_pointcloud_to_pcd)
138163
#
139164
#add_executable(bag_to_pcd tools/bag_to_pcd.cpp)
140165
#target_link_libraries(bag_to_pcd pcl_ros_tf ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${PCL_LIBRARIES})
@@ -182,6 +207,8 @@ install(
182207
TARGETS
183208
pcl_ros_tf
184209
pcd_to_pointcloud_lib
210+
pointcloud_to_pcd_lib
211+
combined_pointcloud_to_pcd_lib
185212
# pcl_ros_io
186213
# pcl_ros_features
187214
# pcl_ros_filters

pcl_ros/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,7 @@
3838
<depend>sensor_msgs</depend>
3939
<depend>geometry_msgs</depend>
4040
<depend>tf2</depend>
41+
<depend>tf2_eigen</depend>
4142
<depend>tf2_geometry_msgs</depend>
4243
<depend>tf2_ros</depend>
4344

Lines changed: 246 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,246 @@
1+
/*
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2009, Willow Garage, Inc.
5+
* All rights reserved.
6+
*
7+
* Redistribution and use in source and binary forms, with or without
8+
* modification, are permitted provided that the following conditions
9+
* are met:
10+
*
11+
* * Redistributions of source code must retain the above copyright
12+
* notice, this list of conditions and the following disclaimer.
13+
* * Redistributions in binary form must reproduce the above
14+
* copyright notice, this list of conditions and the following
15+
* disclaimer in the documentation and/or other materials provided
16+
* with the distribution.
17+
* * Neither the name of Willow Garage, Inc. nor the names of its
18+
* contributors may be used to endorse or promote products derived
19+
* from this software without specific prior written permission.
20+
*
21+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22+
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23+
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24+
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25+
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26+
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27+
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28+
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30+
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31+
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32+
* POSSIBILITY OF SUCH DAMAGE.
33+
*/
34+
35+
/**
36+
* \author Radu Bogdan Rusu
37+
* \author Valerio Passamano
38+
*
39+
* @b combined_pointcloud_to_pcd is a node that accumulates multiple incoming
40+
* point cloud messages into a single PCD file, optionally transforming them
41+
* into a fixed frame.
42+
*/
43+
44+
#include <pcl/common/io.h>
45+
#include <pcl/io/pcd_io.h>
46+
#include <pcl/point_types.h>
47+
#include <pcl_conversions/pcl_conversions.h>
48+
49+
#include <pcl_ros/transforms.hpp>
50+
#include <rclcpp/rclcpp.hpp>
51+
#include <rclcpp_components/register_node_macro.hpp>
52+
#include <sensor_msgs/msg/point_cloud2.hpp>
53+
#include <tf2_eigen/tf2_eigen.hpp>
54+
#include <tf2_ros/buffer.hpp>
55+
#include <tf2_ros/transform_listener.hpp>
56+
57+
namespace pcl_ros
58+
{
59+
60+
class CombinedPointCloudToPCD : public rclcpp::Node
61+
{
62+
public:
63+
explicit CombinedPointCloudToPCD(const rclcpp::NodeOptions & options)
64+
: rclcpp::Node("combined_pointcloud_to_pcd", options),
65+
binary_(false),
66+
compressed_(false),
67+
save_on_shutdown_(true),
68+
fixed_frame_(""),
69+
tf_buffer_(this->get_clock()),
70+
tf_listener_(tf_buffer_),
71+
save_triggered_(false)
72+
{
73+
// Declare parameters
74+
this->declare_parameter<std::string>("prefix", "combined_");
75+
this->declare_parameter<std::string>("fixed_frame", "");
76+
this->declare_parameter<bool>("binary", false);
77+
this->declare_parameter<bool>("compressed", false);
78+
this->declare_parameter<bool>("save_on_shutdown", true);
79+
this->declare_parameter<double>("save_timer_sec", 0.0); // 0.0 = disabled
80+
81+
// Retrieve parameter values
82+
prefix_ = this->get_parameter("prefix").as_string();
83+
fixed_frame_ = this->get_parameter("fixed_frame").as_string();
84+
binary_ = this->get_parameter("binary").as_bool();
85+
compressed_ = this->get_parameter("compressed").as_bool();
86+
save_on_shutdown_ = this->get_parameter("save_on_shutdown").as_bool();
87+
double save_timer_sec = this->get_parameter("save_timer_sec").as_double();
88+
89+
RCLCPP_INFO(this->get_logger(), "prefix: %s", prefix_.c_str());
90+
RCLCPP_INFO(this->get_logger(), "fixed_frame: %s", fixed_frame_.c_str());
91+
RCLCPP_INFO(this->get_logger(), "binary: %s", binary_ ? "true" : "false");
92+
RCLCPP_INFO(this->get_logger(), "compressed: %s", compressed_ ? "true" : "false");
93+
RCLCPP_INFO(this->get_logger(), "save_on_shutdown: %s", save_on_shutdown_ ? "true" : "false");
94+
if (save_timer_sec > 0.0) {
95+
RCLCPP_INFO(
96+
this->get_logger(),
97+
"PCD file will be automatically saved after %.2f seconds (save_timer_sec).",
98+
save_timer_sec);
99+
} else {
100+
RCLCPP_INFO(
101+
this->get_logger(),
102+
"PCD file will not be automatically saved. Will be saved on the shutdown of the node.");
103+
}
104+
105+
// Create a subscription with SensorDataQoS
106+
auto sensor_qos = rclcpp::SensorDataQoS();
107+
sub_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
108+
"input", sensor_qos,
109+
std::bind(&CombinedPointCloudToPCD::cloudCb, this, std::placeholders::_1));
110+
111+
// Create a timer if the user wants a periodic check for saving
112+
if (save_timer_sec > 0.0) {
113+
save_timer_ = this->create_wall_timer(
114+
std::chrono::duration<double>(save_timer_sec),
115+
std::bind(&CombinedPointCloudToPCD::checkAndSave, this));
116+
}
117+
118+
RCLCPP_INFO(this->get_logger(), "Initialized CombinedPointCloudToPCD node");
119+
}
120+
121+
~CombinedPointCloudToPCD() override
122+
{
123+
// Optionally save on node shutdown
124+
if (!save_triggered_ && save_on_shutdown_) {
125+
RCLCPP_INFO(this->get_logger(), "Node is shutting down; saving accumulated cloud.");
126+
saveAccumulatedCloud();
127+
}
128+
}
129+
130+
private:
131+
// Parameters
132+
std::string prefix_;
133+
bool binary_;
134+
bool compressed_;
135+
bool save_on_shutdown_;
136+
std::string fixed_frame_;
137+
138+
tf2_ros::Buffer tf_buffer_;
139+
tf2_ros::TransformListener tf_listener_;
140+
141+
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr sub_;
142+
rclcpp::TimerBase::SharedPtr save_timer_;
143+
144+
// Internal state
145+
pcl::PCLPointCloud2 accumulated_cloud_;
146+
bool save_triggered_;
147+
148+
/**
149+
* @brief Point cloud callback. Accumulates all incoming messages in an internal cloud.
150+
*/
151+
void cloudCb(const sensor_msgs::msg::PointCloud2::SharedPtr cloud_msg)
152+
{
153+
if (cloud_msg->data.empty()) {
154+
RCLCPP_WARN(this->get_logger(), "Received empty point cloud message. Skipping.");
155+
return;
156+
}
157+
158+
pcl::PCLPointCloud2 pcl_pc2;
159+
160+
if (!fixed_frame_.empty()) {
161+
sensor_msgs::msg::PointCloud2 transformed_ros;
162+
if (pcl_ros::transformPointCloud(fixed_frame_, *cloud_msg, transformed_ros, tf_buffer_)) {
163+
pcl_conversions::toPCL(transformed_ros, pcl_pc2);
164+
} else {
165+
RCLCPP_WARN(
166+
this->get_logger(), "Transform to frame '%s' failed. Using original frame.",
167+
fixed_frame_.c_str());
168+
pcl_conversions::toPCL(*cloud_msg, pcl_pc2);
169+
}
170+
} else {
171+
pcl_conversions::toPCL(*cloud_msg, pcl_pc2);
172+
}
173+
174+
if (accumulated_cloud_.data.empty()) {
175+
accumulated_cloud_ = pcl_pc2;
176+
} else {
177+
accumulated_cloud_.data.insert(
178+
accumulated_cloud_.data.end(),
179+
pcl_pc2.data.begin(),
180+
pcl_pc2.data.end());
181+
accumulated_cloud_.width += pcl_pc2.width;
182+
accumulated_cloud_.row_step =
183+
accumulated_cloud_.point_step * accumulated_cloud_.width;
184+
}
185+
186+
RCLCPP_INFO(
187+
this->get_logger(), "Accumulated cloud size: %u",
188+
accumulated_cloud_.width * accumulated_cloud_.height);
189+
}
190+
191+
/**
192+
* @brief Timer-based or event-based function to check if we need to save the cloud.
193+
*/
194+
void checkAndSave()
195+
{
196+
if (!save_triggered_) {
197+
saveAccumulatedCloud();
198+
}
199+
}
200+
201+
/**
202+
* @brief Writes the accumulated point cloud to disk in a single PCD file.
203+
*/
204+
void saveAccumulatedCloud()
205+
{
206+
if (save_triggered_) {
207+
return;
208+
}
209+
save_triggered_ = true; // Prevent multiple saves
210+
211+
// Create a filename
212+
std::stringstream ss;
213+
ss << prefix_ << "combined_" << this->now().seconds() << ".pcd";
214+
std::string filename = ss.str();
215+
216+
RCLCPP_INFO(this->get_logger(), "Saving accumulated point cloud to: %s", filename.c_str());
217+
218+
if (accumulated_cloud_.data.empty()) {
219+
RCLCPP_WARN(this->get_logger(), "No points in accumulated cloud to save.");
220+
} else {
221+
pcl::PCDWriter writer;
222+
if (binary_) {
223+
if (compressed_) {
224+
writer.writeBinaryCompressed(filename, accumulated_cloud_);
225+
} else {
226+
writer.writeBinary(filename, accumulated_cloud_);
227+
}
228+
} else {
229+
writer.writeASCII(filename, accumulated_cloud_);
230+
}
231+
RCLCPP_INFO(
232+
this->get_logger(),
233+
"Saved %u points to %s",
234+
accumulated_cloud_.width * accumulated_cloud_.height,
235+
filename.c_str());
236+
}
237+
// Shut down the node after saving the cloud.
238+
RCLCPP_INFO(this->get_logger(), "Shutting down the node.");
239+
rclcpp::shutdown();
240+
}
241+
};
242+
243+
} // namespace pcl_ros
244+
245+
// Register as a component
246+
RCLCPP_COMPONENTS_REGISTER_NODE(pcl_ros::CombinedPointCloudToPCD)

0 commit comments

Comments
 (0)