Go to the documentation of this file.00001 #include <ros/ros.h>
00002 
00003 #include <std_msgs/String.h>
00004 
00005 #include <pcl/point_types.h>
00006 #include <pcl_ros/point_cloud.h>
00007 #include <pcl/io/pcd_io.h>
00008 #include <pcl/filters/voxel_grid.h>
00009 #include <pcl/common/centroid.h>
00010 
00011 class PointCloudToWebgl {
00012 
00013 
00014 ros::NodeHandle nh_;
00015 ros::NodeHandle nh_private_;
00016 
00017 std::string pcd_filename_;
00018 double max_ascii_file_size_;
00019 int pcd_type_;
00020 
00021 public:
00022 
00026   PointCloudToWebgl() : nh_private_("~")
00027   {
00028     
00029     nh_private_.param("pcd_filename", pcd_filename_, std::string("pointcloud_file.pcd"));
00030     nh_private_.param("max_ascii_file_size", max_ascii_file_size_, 4.0);  
00031     nh_private_.param("pcd_type", pcd_type_, 0);  
00032 
00033     ROS_INFO_STREAM("[PointCloudToWebgl:] Opening file " << pcd_filename_);
00034 
00035     
00036     if (pcd_type_ == 0)
00037     {
00038       
00039       pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ptr (new pcl::PointCloud<pcl::PointXYZ>);
00040       if (pcl::io::loadPCDFile<pcl::PointXYZ> (pcd_filename_, *cloud_ptr) == -1) 
00041       {
00042         ROS_ERROR_STREAM("[PointCloudToWebgl:] Couldn't read file " << pcd_filename_);
00043       }
00044       else
00045       {
00046         
00047         pcl::PointCloud<pcl::PointXYZ> cloud = *cloud_ptr;
00048         int file_point_size = 27;
00049         int max_bytes = (int)round(max_ascii_file_size_ * 1024 * 1024);
00050         int desired_points = max_bytes / file_point_size;
00051         double voxel_size = 0.001;
00052         double offset = 0.0002;
00053         while ((int)cloud.size() > desired_points)
00054         {
00055           pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_downsampled = filter(cloud.makeShared(), voxel_size);
00056           cloud = *cloud_downsampled;
00057           voxel_size = voxel_size + offset;
00058         }
00059 
00060         
00061         Eigen::Vector4f centroid; 
00062         pcl::compute3DCentroid(cloud, centroid);
00063 
00064         
00065         int lastindex = pcd_filename_.find_last_of("."); 
00066         std::string filename = pcd_filename_.substr(0, lastindex); 
00067         filename = filename + ".txt";
00068         ROS_INFO_STREAM("[PointCloudToWebgl:] Saving webgl file to " << filename);
00069         std::fstream f_webgl(filename.c_str(), std::ios::out);
00070         for (unsigned int i=0; i<cloud.size(); i++)
00071         {
00072           f_webgl << cloud[i].x - centroid[0] << "," << 
00073                      cloud[i].y - centroid[1] << "," << 
00074                      cloud[i].z - centroid[2] << "," << 
00075                      (int)(224) << "," << 
00076                      (int)(224) << "," << 
00077                      (int)(224) << std::endl;
00078         }
00079         f_webgl.close();
00080         ROS_INFO("[PointCloudToWebgl:] Saved!");
00081       }
00082     }
00083     else
00084     {
00085       
00086       pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_ptr (new pcl::PointCloud<pcl::PointXYZRGB>);
00087       if (pcl::io::loadPCDFile<pcl::PointXYZRGB> (pcd_filename_, *cloud_ptr) == -1) 
00088       {
00089         ROS_ERROR_STREAM("[PointCloudToWebgl:] Couldn't read file " << pcd_filename_);
00090       }
00091       else
00092       {
00093         
00094         pcl::PointCloud<pcl::PointXYZRGB> cloud = *cloud_ptr;
00095         int file_point_size = 37;
00096         int max_bytes = (int)round(max_ascii_file_size_ * 1024 * 1024);
00097         int desired_points = max_bytes / file_point_size;
00098         double voxel_size = 0.001;
00099         double offset = 0.0002;
00100         while ((int)cloud.size() > desired_points)
00101         {
00102           pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_downsampled = filter(cloud.makeShared(), voxel_size);
00103           cloud = *cloud_downsampled;
00104           voxel_size = voxel_size + offset;
00105         }
00106 
00107         
00108         Eigen::Vector4f centroid; 
00109         pcl::compute3DCentroid(cloud, centroid);
00110 
00111         
00112         int lastindex = pcd_filename_.find_last_of("."); 
00113         std::string filename = pcd_filename_.substr(0, lastindex); 
00114         filename = filename + ".txt";
00115         ROS_INFO_STREAM("[PointCloudToWebgl:] Saving webgl file to " << filename);
00116         std::fstream f_webgl(filename.c_str(), std::ios::out);
00117         for (unsigned int i=0; i<cloud.size(); i++)
00118         {
00119           f_webgl << cloud[i].x - centroid[0] << "," << 
00120                      cloud[i].y - centroid[1] << "," << 
00121                      cloud[i].z - centroid[2] << "," << 
00122                      (int)cloud[i].r << "," << 
00123                      (int)cloud[i].g << "," << 
00124                      (int)cloud[i].b << std::endl;
00125         }
00126         f_webgl.close();
00127         ROS_INFO("[PointCloudToWebgl:] Saved!");
00128       }
00129     }
00130   }
00131 
00132   pcl::PointCloud<pcl::PointXYZ>::Ptr filter(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, double voxel_size)
00133   {
00134     
00135     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered_ptr(new pcl::PointCloud<pcl::PointXYZ>);
00136     pcl::VoxelGrid<pcl::PointXYZ> grid_;
00137     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_downsampled_ptr(new pcl::PointCloud<pcl::PointXYZ>);
00138     grid_.setLeafSize(voxel_size,
00139                       voxel_size,
00140                       voxel_size);
00141     grid_.setDownsampleAllData(true);
00142     grid_.setInputCloud(cloud);
00143     grid_.filter(*cloud_downsampled_ptr);
00144     return cloud_downsampled_ptr;
00145   }
00146 
00147   pcl::PointCloud<pcl::PointXYZRGB>::Ptr filter(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud, double voxel_size)
00148   {
00149     
00150     pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_filtered_ptr(new pcl::PointCloud<pcl::PointXYZRGB>);
00151     pcl::VoxelGrid<pcl::PointXYZRGB> grid_;
00152     pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_downsampled_ptr(new pcl::PointCloud<pcl::PointXYZRGB>);
00153 
00154     grid_.setLeafSize(voxel_size,
00155                       voxel_size,
00156                       voxel_size);
00157     grid_.setDownsampleAllData(true);
00158     grid_.setInputCloud(cloud);
00159     grid_.filter(*cloud_downsampled_ptr);
00160     return cloud_downsampled_ptr;
00161   }
00162 
00163 };
00164 
00168 int main(int argc, char **argv)
00169 {
00170   ros::init(argc, argv, "pointcloud_to_webgl");
00171   PointCloudToWebgl node;
00172   ros::spin();
00173   return 0;
00174 }
00175