pointcloud_viewer.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id: pointcloud_online_viewer.cpp 33238 2010-03-11 00:46:58Z rusu $
00035  *
00036  */
00037 
00038 // ROS core
00039 #include <signal.h>
00040 #include <ros/ros.h>
00041 #include <std_msgs/String.h>
00042 #include <boost/thread/mutex.hpp>
00043 #include <boost/thread.hpp>
00044 // PCL includes
00045 #include <pcl/common/centroid.h>
00046 #include <pcl/point_types.h>
00047 #include <pcl_ros/point_cloud.h>
00048 #include <pcl/visualization/pcl_visualizer.h>
00049 #include <pcl/features/feature.h>
00050 #include <pcl/io/pcd_io.h>
00051 #include <pcl/filters/voxel_grid.h>
00052 #include <pcl/filters/passthrough.h>
00053 
00054 using pcl::visualization::PointCloudColorHandlerGenericField;
00055 
00056 typedef pcl::PointXYZ             Point;
00057 typedef pcl::PointCloud<Point>    PointCloud;
00058 typedef pcl::PointXYZRGB          PointRGB;
00059 typedef pcl::PointCloud<PointRGB> PointCloudRGB;
00060 
00061 // Global data
00062 sensor_msgs::PointCloud2ConstPtr cloud_, cloud_old_;
00063 boost::mutex m;
00064 bool viewer_initialized_;
00065 bool save_cloud_;
00066 std::string pcd_filename_;
00067 int counter_;
00068 
00069 void cloud_cb(const sensor_msgs::PointCloud2ConstPtr& cloud)
00070 {
00071   m.lock ();
00072   printf("\rPointCloud with %d data points (%s), stamp %f, and frame %s.",
00073       cloud->width * cloud->height, pcl::getFieldsList(*cloud).c_str(), 
00074       cloud->header.stamp.toSec(), cloud->header.frame_id.c_str());
00075   cloud_ = cloud;
00076   m.unlock();
00077 }
00078 
00079 PointCloudRGB::Ptr filter(PointCloudRGB::Ptr cloud, double voxel_size)
00080 {
00081   PointCloudRGB::Ptr cloud_filtered_ptr(new PointCloudRGB);
00082 
00083   // Downsampling using voxel grid
00084   pcl::VoxelGrid<PointRGB> grid_;
00085   PointCloudRGB::Ptr cloud_downsampled_ptr(new PointCloudRGB);
00086 
00087   grid_.setLeafSize(voxel_size,
00088                     voxel_size,
00089                     voxel_size);
00090   grid_.setDownsampleAllData(true);
00091   grid_.setInputCloud(cloud);
00092   grid_.filter(*cloud_downsampled_ptr);
00093 
00094   return cloud_downsampled_ptr;
00095 }
00096 
00097 void keyboardEventOccurred(const pcl::visualization::KeyboardEvent& event, void* nothing)
00098 {
00099   if (event.getKeySym() == "space" && event.keyDown())
00100     save_cloud_ = true;
00101 }
00102 
00103 void updateVisualization()
00104 {
00105   PointCloud                    cloud_xyz;
00106   PointCloudRGB                 cloud_xyz_rgb;
00107   EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
00108   Eigen::Vector4f               xyz_centroid;
00109 
00110   ros::WallDuration d(0.01);
00111   bool rgb = false;
00112   //std::vector<sensor_msgs::PointField> fields;
00113   std::vector<pcl::PCLPointField> fields;
00114   
00115   // Create the visualizer
00116   pcl::visualization::PCLVisualizer viewer("Point Cloud Viewer");
00117 
00118   // Add a coordinate system to screen
00119   viewer.addCoordinateSystem(0.1);
00120   viewer.registerKeyboardCallback(&keyboardEventOccurred);
00121 
00122   while(true)
00123   {
00124     d.sleep();
00125 
00126     // If no cloud received yet, continue
00127     if(!cloud_ || cloud_->width<=0)
00128       continue;
00129 
00130     viewer.spinOnce(1);
00131 
00132     if(cloud_old_ == cloud_)
00133       continue;
00134     m.lock ();
00135     
00136     // Convert to PointCloud<T>
00137     if(pcl::getFieldIndex(*cloud_, "rgb") != -1)
00138     {
00139       rgb = true;
00140       pcl::fromROSMsg(*cloud_, cloud_xyz_rgb);
00141     }
00142     else
00143     {
00144       rgb = false;
00145       pcl::fromROSMsg(*cloud_, cloud_xyz);
00146       pcl::getFields(cloud_xyz, fields);
00147     }
00148     cloud_old_ = cloud_;
00149     m.unlock();
00150 
00151     // Delete the previous point cloud
00152     viewer.removePointCloud("cloud");
00153     
00154     // If no RGB data present, use a simpler white handler
00155     if(rgb && pcl::getFieldIndex(cloud_xyz_rgb, "rgb", fields) != -1 && 
00156       cloud_xyz_rgb.points[0].rgb != 0)
00157     {
00158       // Initialize the camera view
00159       if(!viewer_initialized_)
00160       {
00161         pcl::computeMeanAndCovarianceMatrix(cloud_xyz_rgb, covariance_matrix, xyz_centroid);
00162         viewer.initCameraParameters();
00163         viewer.setCameraPosition(xyz_centroid(0), xyz_centroid(1), xyz_centroid(2)+3.0, 0, -1, 0);
00164         ROS_INFO_STREAM("[PointCloudViewer:] Point cloud viewer camera initialized in: [" << 
00165           xyz_centroid(0) << ", " << xyz_centroid(1) << ", " << xyz_centroid(2)+3.0 << "]");
00166         viewer_initialized_ = true;
00167       }
00168       // Show the point cloud
00169       pcl::visualization::PointCloudColorHandlerRGBField<PointRGB> color_handler(
00170         cloud_xyz_rgb.makeShared());
00171       viewer.addPointCloud(cloud_xyz_rgb.makeShared(), color_handler, "cloud");
00172 
00173       // Save pcd
00174       if (save_cloud_ && cloud_xyz_rgb.size() > 0)
00175       {
00176         if (pcl::io::savePCDFile(pcd_filename_, cloud_xyz_rgb) == 0)
00177           ROS_INFO_STREAM("[PointCloudViewer:] Pointcloud saved into: " << pcd_filename_);
00178         else 
00179           ROS_ERROR_STREAM("[PointCloudViewer:] Problem saving " << pcd_filename_.c_str());
00180         save_cloud_ = false;
00181       }
00182 
00183     }
00184     else
00185     {
00186       // Initialize the camera view
00187       if(!viewer_initialized_)
00188       {
00189         pcl::computeMeanAndCovarianceMatrix(cloud_xyz_rgb, covariance_matrix, xyz_centroid);
00190         viewer.initCameraParameters();
00191         viewer.setCameraPosition(xyz_centroid(0), xyz_centroid(1), xyz_centroid(2)+3.0, 0, -1, 0);
00192         ROS_INFO_STREAM("[PointCloudViewer:] Point cloud viewer camera initialized in: [" << 
00193           xyz_centroid(0) << ", " << xyz_centroid(1) << ", " << xyz_centroid(2)+3.0 << "]");
00194         viewer_initialized_ = true;
00195       }
00196 
00197       // Some xyz_rgb point clouds have incorrect rgb field. Detect and convert to xyz.
00198       if(pcl::getFieldIndex(cloud_xyz_rgb, "rgb", fields) != -1)
00199       {
00200         if(cloud_xyz_rgb.points[0].rgb == 0)
00201         {
00202           pcl::copyPointCloud(cloud_xyz_rgb, cloud_xyz);
00203         }
00204       }
00205       
00206       // Show the xyz point cloud
00207       PointCloudColorHandlerGenericField<Point> color_handler (cloud_xyz.makeShared(), "z");
00208       if (!color_handler.isCapable ())
00209       {
00210         ROS_WARN_STREAM("[PointCloudViewer:] Cannot create curvature color handler!");
00211         pcl::visualization::PointCloudColorHandlerCustom<Point> color_handler(
00212         cloud_xyz.makeShared(), 255, 0, 255);
00213       }
00214       viewer.addPointCloud(cloud_xyz.makeShared(), color_handler, "cloud");
00215 
00216       // Save pcd
00217       if (save_cloud_ && cloud_xyz.size() > 0)
00218       {
00219         if (pcl::io::savePCDFile(pcd_filename_, cloud_xyz) == 0)
00220           ROS_INFO_STREAM("[PointCloudViewer:] Pointcloud saved into: " << pcd_filename_);
00221         else 
00222           ROS_ERROR_STREAM("[PointCloudViewer:] Problem saving " << pcd_filename_.c_str());
00223         save_cloud_ = false;
00224       }
00225     }
00226 
00227     counter_++;
00228   }
00229 }
00230 
00231 void sigIntHandler(int sig)
00232 {
00233   exit(0);
00234 }
00235 
00236 /* ---[ */
00237 int main(int argc, char** argv)
00238 {
00239   ros::init(argc, argv, "pointcloud_viewer", ros::init_options::NoSigintHandler);
00240   ros::NodeHandle nh;
00241   ros::NodeHandle nh_priv("~");
00242   viewer_initialized_ = false;
00243   save_cloud_ = false;
00244   counter_ = 0;
00245 
00246   // Read parameters
00247   nh_priv.param("pcd_filename", pcd_filename_, std::string("pointcloud_file.pcd"));
00248 
00249   // Create a ROS subscriber
00250   ros::Subscriber sub = nh.subscribe("input", 30, cloud_cb);
00251 
00252   ROS_INFO("Subscribing to %s for PointCloud2 messages...", nh.resolveName ("input").c_str ());
00253 
00254   signal(SIGINT, sigIntHandler);
00255 
00256   boost::thread visualization_thread(&updateVisualization);
00257 
00258   // Spin
00259   ros::spin();
00260 
00261   // Join, delete, exit
00262   visualization_thread.join();
00263   return (0);
00264 }
00265 /* ]--- */


pointcloud_tools
Author(s): Pep Lluis Negre
autogenerated on Fri Aug 28 2015 13:15:25