#include <memory>
#include <point_cloud_transport/point_cloud_transport.hpp>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
class CloudiniPluginPublisherTestNode : public rclcpp::Node {
public:
CloudiniPluginPublisherTestNode() : Node("cloudini_plugin_publisher_test") {
this->declare_parameter<std::string>("input_topic", "/points");
this->declare_parameter<std::string>("output_topic", "/points_pct");
}
void init() {
std::string input_topic = this->get_parameter("input_topic").as_string();
std::string output_topic = this->get_parameter("output_topic").as_string();
RCLCPP_INFO(this->get_logger(), "Starting Cloudini plugin publisher test node");
RCLCPP_INFO(this->get_logger(), "Subscribing to: %s", input_topic.c_str());
RCLCPP_INFO(this->get_logger(), "Publishing to: %s", output_topic.c_str());
pct_ = std::make_shared<point_cloud_transport::PointCloudTransport>(shared_from_this());
transport_publisher_ = pct_->advertise(output_topic, 10);
subscription_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
input_topic, 10, [this](const sensor_msgs::msg::PointCloud2::SharedPtr msg) { this->pointCloudCallback(msg); });
RCLCPP_INFO(this->get_logger(), "Cloudini plugin publisher test node initialized successfully");
RCLCPP_INFO(this->get_logger(), "Point cloud transport will create compressed topics automatically");
}
private:
void pointCloudCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg) {
message_count_++;
transport_publisher_.publish(msg);
if (message_count_ % 10 == 0) {
RCLCPP_INFO(
this->get_logger(), "Published point cloud #%ld: %u points", message_count_, msg->width * msg->height);
}
}
std::shared_ptr<point_cloud_transport::PointCloudTransport> pct_;
point_cloud_transport::Publisher transport_publisher_;
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr subscription_;
size_t message_count_ = 0;
};
int main(int argc, char** argv) {
rclcpp::init(argc, argv);
auto node = std::make_shared<CloudiniPluginPublisherTestNode>();
node->init();
RCLCPP_INFO(node->get_logger(), "Cloudini plugin publisher 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(), "Cloudini plugin publisher test node shutting down");
return 0;
}