You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
I am using ros2 humble and installed this packages and implemented so that it will publish the compressed topic. Here is the implementation of a simple node
#include "sensor_msgs/msg/point_cloud2.hpp"
#include "point_cloud_transport/point_cloud_transport.hpp"
class pointcloudCompressor : public rclcpp::Node{
public:
pointcloudCompressor() : Node("pointcloud_compressor_node"){
RCLCPP_INFO(this->get_logger(), "pointcloud compressor node has been started");
// Create a reqular ROS2 subscriber for PointCloud2
raw_subscriber_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"/ouster_front/points", rclcpp::QoS{1}.best_effort(),
std::bind(&pointcloudCompressor::compressCallback, this, std::placeholders::_1));
}
protected:
void compressCallback(const sensor_msgs::msg::PointCloud2 &msg);
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr raw_subscriber_;
// std::shared_ptr<point_cloud_transport::PointCloudTransport> point_cloud_transport_;
// point_cloud_transport::Publisher pcl_compress_publisher_;
// rclcpp::TimerBase::SharedPtr timer_;
point_cloud_transport::Publisher compressed_publisher_;
point_cloud_transport::Subscriber subscriber_;
};
void pointcloudCompressor::compressCallback(const sensor_msgs::msg::PointCloud2 &msg){
RCLCPP_INFO(this->get_logger(), "Received point cloud with %lu bytes:", msg.data.size());
// // Initialize the PointCloudTransport
// point_cloud_transport_ = std::make_shared<point_cloud_transport::PointCloudTransport>(shared_from_this());
// // Advertise the compressed point cloud topic
// pcl_compress_publisher_ = point_cloud_transport_->advertise("/ouster_front/compressed_points", 10);
// Create a compressed point cloud publisher
compressed_publisher_ = point_cloud_transport::create_publisher(shared_from_this(), "/ouster_front/compressed_points");
compressed_publisher_.publish(msg);
}
int main(int argc, char *argv[]){
rclcpp::init(argc, argv);
auto node = std::make_shared<pointcloudCompressor>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
When i see the topic by "ros2 topic list", it shows the topic name but when i try to echo, i can not and try to check bandwindth also.
You could see i followed different examples, so would there be any problem in the above implementation? Thanks!
The text was updated successfully, but these errors were encountered:
Hi,
I am using ros2 humble and installed this packages and implemented so that it will publish the compressed topic. Here is the implementation of a simple node
When i see the topic by "ros2 topic list", it shows the topic name but when i try to echo, i can not and try to check bandwindth also.
You could see i followed different examples, so would there be any problem in the above implementation? Thanks!
The text was updated successfully, but these errors were encountered: