Convert PCD files to Pointcloud2

asked 2022-02-08 08:45:24 -0500

catkinclean gravatar image

Hello,

I have many pcd files that were collected from a lidar. I'm trying to convert these pcd files to pointcloud2 format to create a rosbag. I've already used

rosrun pcl_ros pcd_to_pointcloud Lidar-0.pcd

It works nice but since i have many pcd files, it is not possible to convert it one by one in 10 Hz. Therefore, i wanted to code it by myself.

#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
#include <pcl/io/pcd_io.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>

#include <pcl/common/transforms.h>
#include <tf/transform_listener.h>


int main(int argc, char **argv)
{

  // Initialize ROS
  ros::init (argc, argv, "example");



 ros::NodeHandle nh;

  ros::Rate loop_rate(10);

  pcl::PCLPointCloud2 pcl_pc;

  sensor_msgs::PointCloud2 output;

  tf::TransformListener tf_obj;

  // Create a ROS publisher for the output point cloud

  ros::Publisher pub = nh.advertise<pcl::PointCloud<pcl::PointXYZ>>("my_pc", 1);

  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);

  if (pcl::io::loadPCDFile<pcl::PointXYZ> ("/home/user/Desktop/Lidar-0.pcd",*cloud) == -1)
   {
     PCL_ERROR("Could not read file");
     return (-1);
   }


  std::cout<<"Loaded"
           <<cloud->width * cloud->height
           <<" data points from test_pcd.pcd with the following fields"
           <<std::endl;

  pcl::toPCLPointCloud2(*cloud, pcl_pc);

  while (ros::ok())

    {

      pcl::toROSMsg(*cloud, output);
      pub.publish (output);

      ros::spinOnce();
      loop_rate.sleep();

    }

    return  0;
}

I tried to follow the tutorials, however i'm getting error as,

required from here
/opt/ros/melodic/include/ros/message_traits.h:120:28: error: ‘__s_getMD5Sum’ is not a member of ‘pcl::PointCloud<pcl::PointXYZ>’
     return M::__s_getMD5Sum().c_str();
            ~~~~~~~~~~~~~~~~^~

Which format should i use to achieve what i want? Thank you for your help.

edit retag flag offensive close merge delete