#include <pcl/conversions.h>
#include <pcl/point_types.h>
#include <cloudini_ros/cloudini_subscriber_pcl.hpp>
#include <memory>
#include <rclcpp/rclcpp.hpp>
class CloudiniSubscriberTestNode : public rclcpp::Node {
public:
CloudiniSubscriberTestNode() : Node("cloudini_subscriber_test") {
this->declare_parameter<std::string>("topic", "/points/compressed");
std::string topic = this->get_parameter("topic").as_string();
RCLCPP_INFO(this->get_logger(), "Starting CloudiniSubscriberPCL test node");
RCLCPP_INFO(this->get_logger(), "Subscribing to topic: %s", topic.c_str());
subscriber_ = std::make_shared<cloudini_ros::CloudiniSubscriberPCL>(
this, topic, std::bind(&CloudiniSubscriberTestNode::pointCloudCallback, this, std::placeholders::_1),
rclcpp::QoS(10));
RCLCPP_INFO(this->get_logger(), "CloudiniSubscriberPCL test node initialized successfully");
}
private:
void pointCloudCallback(const pcl::PCLPointCloud2::Ptr& cloud);
std::shared_ptr<cloudini_ros::CloudiniSubscriberPCL> subscriber_;
size_t message_count_ = 0;
};
void CloudiniSubscriberTestNode::pointCloudCallback(const pcl::PCLPointCloud2::Ptr& cloud) {
message_count_++;
uint32_t num_points = cloud->width * cloud->height;
size_t cloud_size_bytes = cloud->data.size();
bool is_organized = cloud->height > 1;
std::string fields_str;
for (const auto& field : cloud->fields) {
if (!fields_str.empty()) {
fields_str += ", ";
}
fields_str += field.name;
}
if (message_count_ % 10 == 0) {
RCLCPP_INFO(
this->get_logger(), "Received %ld point clouds. %u points (%ux%u), %.2f KB, fields: [%s]", message_count_,
num_points, cloud->width, cloud->height, cloud_size_bytes / 1024.0, fields_str.c_str());
}
}
int main(int argc, char** argv) {
rclcpp::init(argc, argv);
auto node = std::make_shared<CloudiniSubscriberTestNode>();
RCLCPP_INFO(node->get_logger(), "CloudiniSubscriberPCL test node is running...");
RCLCPP_INFO(node->get_logger(), "Press Ctrl+C to exit");
try {
rclcpp::spin(node);
} catch (const std::exception& e) {
RCLCPP_ERROR(node->get_logger(), "Exception during spin: %s", e.what());
}
rclcpp::shutdown();
RCLCPP_INFO(node->get_logger(), "CloudiniSubscriberPCL test node shutting down");
return 0;
}