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/statistical_outlier_removal.h>
00052 
00053 using pcl::visualization::PointCloudColorHandlerGenericField;
00054 
00055 typedef pcl::PointXYZ             Point;
00056 typedef pcl::PointCloud<Point>    PointCloud;
00057 typedef pcl::PointXYZRGB          PointRGB;
00058 typedef pcl::PointCloud<PointRGB> PointCloudRGB;
00059 
00060 // Global data
00061 sensor_msgs::PointCloud2ConstPtr cloud_, cloud_old_;
00062 boost::mutex m_;
00063 bool viewer_initialized_;
00064 bool save_cloud_;
00065 std::string pcd_filename_;
00066 int counter_;
00067 ros::WallTimer save_timer_;
00068 
00069 PointCloud cloud_xyz_;
00070 PointCloudRGB cloud_xyz_rgb_;
00071 
00072 void cloud_cb(const sensor_msgs::PointCloud2ConstPtr& cloud)
00073 {
00074   m_.lock ();
00075   ROS_INFO_STREAM("[PointCloudViewer:] Pointcloud received.");
00076   cloud_ = cloud;
00077   m_.unlock();
00078 }
00079 
00080 void keyboardEventOccurred(const pcl::visualization::KeyboardEvent& event, void* nothing)
00081 {
00082   if (event.getKeySym() == "space" && event.keyDown()) {
00083     ROS_INFO("[PointCloudViewer:] Saving pointcloud, please wait...");
00084     save_cloud_ = true;
00085   }
00086 }
00087 
00088 void updateVisualization()
00089 {
00090   EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
00091   Eigen::Vector4f               xyz_centroid;
00092 
00093   ros::WallDuration d(0.01);
00094   bool rgb = false;
00095   std::vector<pcl::PCLPointField> fields;
00096 
00097   // Create the visualizer
00098   pcl::visualization::PCLVisualizer viewer("Point Cloud Viewer");
00099 
00100   // Add a coordinate system to screen
00101   viewer.addCoordinateSystem(0.1);
00102   viewer.registerKeyboardCallback(&keyboardEventOccurred);
00103 
00104   while(true)
00105   {
00106     d.sleep();
00107 
00108     // If no cloud received yet, continue
00109     if(!cloud_ || cloud_->width<=0)
00110       continue;
00111 
00112     viewer.spinOnce(1);
00113 
00114     if(cloud_old_ == cloud_)
00115       continue;
00116 
00117     // Convert to PointCloud<T>
00118     m_.lock ();
00119     if(pcl::getFieldIndex(*cloud_, "rgb") != -1)
00120     {
00121       rgb = true;
00122       pcl::fromROSMsg(*cloud_, cloud_xyz_rgb_);
00123     }
00124     else
00125     {
00126       rgb = false;
00127       pcl::fromROSMsg(*cloud_, cloud_xyz_);
00128       pcl::getFields(cloud_xyz_, fields);
00129     }
00130     cloud_old_ = cloud_;
00131     m_.unlock();
00132 
00133     // Delete the previous point cloud
00134     viewer.removePointCloud("cloud");
00135 
00136     // If no RGB data present, use a simpler white handler
00137     if(rgb && pcl::getFieldIndex(cloud_xyz_rgb_, "rgb", fields) != -1 &&
00138       cloud_xyz_rgb_.points[0].rgb != 0)
00139     {
00140       // Initialize the camera view
00141       if(!viewer_initialized_)
00142       {
00143         pcl::computeMeanAndCovarianceMatrix(cloud_xyz_rgb_, covariance_matrix, xyz_centroid);
00144         viewer.initCameraParameters();
00145         viewer.setCameraPosition(xyz_centroid(0), xyz_centroid(1), xyz_centroid(2)+3.0, 0, -1, 0);
00146         ROS_INFO_STREAM("[PointCloudViewer:] Point cloud viewer camera initialized in: [" <<
00147           xyz_centroid(0) << ", " << xyz_centroid(1) << ", " << xyz_centroid(2)+3.0 << "]");
00148         viewer_initialized_ = true;
00149       }
00150       // Show the point cloud
00151       pcl::visualization::PointCloudColorHandlerRGBField<PointRGB> color_handler(
00152         cloud_xyz_rgb_.makeShared());
00153       viewer.addPointCloud(cloud_xyz_rgb_.makeShared(), color_handler, "cloud");
00154     }
00155     else
00156     {
00157       // Initialize the camera view
00158       if(!viewer_initialized_)
00159       {
00160         pcl::computeMeanAndCovarianceMatrix(cloud_xyz_, covariance_matrix, xyz_centroid);
00161         viewer.initCameraParameters();
00162         viewer.setCameraPosition(xyz_centroid(0), xyz_centroid(1), xyz_centroid(2)+3.0, 0, -1, 0);
00163         ROS_INFO_STREAM("[PointCloudViewer:] Point cloud viewer camera initialized in: [" <<
00164           xyz_centroid(0) << ", " << xyz_centroid(1) << ", " << xyz_centroid(2)+3.0 << "]");
00165         viewer_initialized_ = true;
00166       }
00167 
00168       // Show the xyz point cloud
00169       PointCloudColorHandlerGenericField<Point> color_handler (cloud_xyz_.makeShared(), "z");
00170       if (!color_handler.isCapable ())
00171       {
00172         ROS_WARN_STREAM("[PointCloudViewer:] Cannot create curvature color handler!");
00173         pcl::visualization::PointCloudColorHandlerCustom<Point> color_handler(
00174         cloud_xyz_.makeShared(), 255, 0, 255);
00175       }
00176       viewer.addPointCloud(cloud_xyz_.makeShared(), color_handler, "cloud");
00177     }
00178 
00179     counter_++;
00180   }
00181 }
00182 
00183 void saveCallback(const ros::WallTimerEvent&)
00184 {
00185   if (!save_cloud_) return;
00186 
00187   if (cloud_xyz_rgb_.size() > 0)
00188   {
00189     // Remove outliers
00190     pcl::PointCloud<PointRGB>::Ptr cloud_filtered (new pcl::PointCloud<PointRGB>);
00191     pcl::StatisticalOutlierRemoval<PointRGB> sor;
00192     sor.setInputCloud (cloud_xyz_rgb_.makeShared());
00193     sor.setMeanK (50);
00194     sor.setStddevMulThresh (1.0);
00195     sor.filter (*cloud_filtered);
00196 
00197     if (pcl::io::savePCDFile(pcd_filename_, *cloud_filtered) == 0)
00198       ROS_INFO_STREAM("[PointCloudViewer:] Pointcloud saved into: " << pcd_filename_);
00199     else
00200       ROS_ERROR_STREAM("[PointCloudViewer:] Problem saving " << pcd_filename_.c_str());
00201     save_cloud_ = false;
00202   }
00203 
00204   if (cloud_xyz_.size() > 0)
00205   {
00206     // Remove outliers
00207     pcl::PointCloud<Point>::Ptr cloud_filtered (new pcl::PointCloud<Point>);
00208     pcl::StatisticalOutlierRemoval<Point> sor;
00209     sor.setInputCloud (cloud_xyz_.makeShared());
00210     sor.setMeanK (50);
00211     sor.setStddevMulThresh (1.0);
00212     sor.filter (*cloud_filtered);
00213 
00214     if (pcl::io::savePCDFile(pcd_filename_, *cloud_filtered) == 0)
00215       ROS_INFO_STREAM("[PointCloudViewer:] Pointcloud saved into: " << pcd_filename_);
00216     else
00217       ROS_ERROR_STREAM("[PointCloudViewer:] Problem saving " << pcd_filename_.c_str());
00218     save_cloud_ = false;
00219   }
00220 }
00221 
00222 // void sigIntHandler(int sig)
00223 // {
00224 //   exit(0);
00225 // }
00226 
00227 /* ---[ */
00228 int main(int argc, char** argv)
00229 {
00230   ros::init(argc, argv, "pointcloud_viewer");//, ros::init_options::NoSigintHandler);
00231   ros::NodeHandle nh;
00232   ros::NodeHandle nh_priv("~");
00233   viewer_initialized_ = false;
00234   save_cloud_ = false;
00235   counter_ = 0;
00236 
00237   // Read parameters
00238   nh_priv.param("pcd_filename", pcd_filename_, std::string("pointcloud_file.pcd"));
00239 
00240   // Create a ROS subscriber
00241   ros::Subscriber sub = nh.subscribe("input", 30, cloud_cb);
00242 
00243   ROS_INFO("[PointCloudViewer:] Subscribing to %s for PointCloud2 messages...", nh.resolveName ("input").c_str ());
00244 
00245   // signal(SIGINT, sigIntHandler);
00246   boost::thread visualization_thread(&updateVisualization);
00247   save_timer_ = nh.createWallTimer(ros::WallDuration(1), &saveCallback);
00248 
00249   // Spin
00250   ros::spin();
00251 
00252   // Join, delete, exit
00253   visualization_thread.join();
00254   return (0);
00255 }
00256 /* ]--- */


pointcloud_tools
Author(s): Pep Lluis Negre
autogenerated on Sat Jun 8 2019 20:10:22