ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
here is the api to convert into pcl data structure .After this we can use Pcl_conversion to convert the cloud into sensor_msg::pointcloud2
#include "velodyne_pointcloud/calibration.h"
#include "velodyne_msgs/VelodynePacket.h"
#include "velodyne_msgs/VelodyneScan.h"
#include "velodyne_pointcloud/rawdata.h"
#include "velodyne_pointcloud/point_types.h"
#include "velodyne_pointcloud/VelodyneConfigConfig.h"
#include "velodyne_pointcloud/point_types.h"
#include "velodyne_pointcloud/calibration.h"
#include <pcl_conversions/pcl_conversions.h>
void save_3d_lidar(velodyne_msgs::VelodyneScan::ConstPtr v_scan,nav_msgs::Odometry::ConstPtr gps_pose)
{
pcl::PointCloud<pcl::PointXYZI> cloud_3d;
pcl::PointXYZI point;
velodyne_rawdata::RawData data;
cloud_3d.clear();
for(int i=0;i<v_scan->packets.size();i++)
{
pcl::PointCloud<velodyne_pointcloud::PointXYZIR> v_point_cloud;
data.setParameters(0.9,130.0,0.0,6.28);
data.setupOffline("file adresss",130.0,0.9);
data.unpack(v_scan->packets[i],v_point_cloud);
for(int j=0;j<v_point_cloud.size();j++)
{
point.x=v_point_cloud.points[j].x;
point.y=v_point_cloud.points[j].y;
point.z=v_point_cloud.points[j].z;
point.intensity=v_point_cloud.points[j].intensity;
cloud_3d.push_back(point);
}
}
}