00001 #include <string> 00002 #include <pcl/ros/register_point_struct.h> 00003 #include <pcl/io/pcd_io.h> 00004 #include <pcl/io/vtk_lib_io.h> 00005 #include <pcl/filters/voxel_grid.h> 00006 #include <pcl/point_types.h> 00007 #include <pcl/console/parse.h> 00008 00009 #include <vtkMath.h> 00010 #include <vtkGeneralTransform.h> 00011 #include <vtkPlatonicSolidSource.h> 00012 #include <vtkLoopSubdivisionFilter.h> 00013 #include <vtkPLYReader.h> 00014 #include <vtkSmartPointer.h> 00015 #include <vtkCellLocator.h> 00016 #include <vtkPolyData.h> 00017 #include <boost/random.hpp> 00018 00019 00020 #include <pcl/visualization/pcl_visualizer.h> 00021 #include <pcl/visualization/image_viewer.h> 00022 00023 using namespace pcl; 00024 00025 00026 int 00027 main (int argc, char ** argv) 00028 { 00029 pcl::PCDReader reader; 00030 sensor_msgs::PointCloud2 cloud; 00031 reader.read (argv[1], cloud); 00032 00033 pcl::PointCloud<pcl::PointXYZ> xyz; 00034 pcl::fromROSMsg (cloud, xyz); 00035 00036 pcl::visualization::ImageViewer depth_image_viewer_; 00037 float* img = new float[cloud.width * cloud.height]; 00038 for (int i = 0; i < xyz.points.size (); ++i) 00039 img[i] = xyz.points[i].z; 00040 00041 depth_image_viewer_.showFloatImage (img, 00042 cloud.width, cloud.height, 00043 std::numeric_limits<float>::min (), 00044 // Scale so that the colors look brigher on screen 00045 std::numeric_limits<float>::max () / 10, 00046 true); 00047 depth_image_viewer_.spin (); 00048 return (0); 00049 }