$search
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 <ros/ros.h> 00040 #include <boost/thread/mutex.hpp> 00041 // PCL includes 00042 #include <pcl/io/io.h> 00043 #include <pcl/io/pcd_io.h> 00044 #include <pcl/point_types.h> 00045 00046 #include <pcl_visualization/pcl_visualizer.h> 00047 #include <pcl/console/print.h> 00048 #include <pcl/console/parse.h> 00049 00050 using namespace std; 00051 00052 typedef pcl::PointXYZ Point; 00053 typedef pcl_visualization::PointCloudColorHandler<sensor_msgs::PointCloud2> ColorHandler; 00054 typedef ColorHandler::Ptr ColorHandlerPtr; 00055 typedef ColorHandler::ConstPtr ColorHandlerConstPtr; 00056 00057 sensor_msgs::PointCloud2ConstPtr cloud_, cloud_old_; 00058 boost::mutex m; 00059 00060 void 00061 cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud) 00062 { 00063 ROS_INFO ("PointCloud with %d data points (%s), stamp %f, and frame %s.", cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str ()); 00064 m.lock (); 00065 cloud_ = cloud; 00066 m.unlock (); 00067 } 00068 00069 /* ---[ */ 00070 int 00071 main (int argc, char** argv) 00072 { 00073 ros::init (argc, argv, "pointcloud_online_viewer"); 00074 ros::NodeHandle nh; 00075 00076 // Get the queue size from the command line 00077 int queue_size = 1; 00078 pcl::console::parse_argument (argc, argv, "-qsize", queue_size); 00079 pcl::console::print_highlight ("Using a queue size of %d\n", queue_size); 00080 00081 // Get the number of clouds to keep on screen 00082 int nr_clouds = 1; 00083 pcl::console::parse_argument (argc, argv, "-nclouds", nr_clouds); 00084 00085 // Create a ROS subscriber 00086 ros::Subscriber sub = nh.subscribe ("input", queue_size, cloud_cb); 00087 00088 pcl_visualization::PCLVisualizer p (argc, argv, "Online PointCloud2 Viewer"); 00089 pcl::PointCloud<Point> cloud_xyz; 00090 ColorHandlerPtr color_handler; 00091 00092 int color_handler_idx = 0; 00093 double psize = 0; 00094 while (nh.ok ()) 00095 { 00096 // Spin 00097 ros::spinOnce (); 00098 ros::Duration (0.001).sleep (); 00099 p.spinOnce (10); 00100 00101 // If no cloud received yet, continue 00102 if (!cloud_) 00103 continue; 00104 00105 if (cloud_ == cloud_old_) 00106 continue; 00107 00108 // Save the last color handler used 00109 color_handler_idx = p.getColorHandlerIndex ("cloud"); 00110 // Save the last point size used 00111 p.getPointCloudRenderingProperties (pcl_visualization::PCL_VISUALIZER_POINT_SIZE, psize, "cloud"); 00112 00113 p.removePointCloud ("cloud"); 00114 // Convert to PointCloud<T> 00115 m.lock (); 00116 00117 { 00118 pcl::fromROSMsg (*cloud_, cloud_xyz); 00119 00120 // Add a random color handler 00121 color_handler.reset (new pcl_visualization::PointCloudColorHandlerCustom<sensor_msgs::PointCloud2> (*cloud_, 255, 255, 255)); 00122 p.addPointCloud (cloud_xyz, color_handler, "cloud"); 00123 00124 // Add a color handler for each field 00125 for (size_t i = 0; i < cloud_->fields.size (); ++i) 00126 { 00127 if (cloud_->fields[i].name == "rgb" || cloud_->fields[i].name == "rgba") 00128 color_handler.reset (new pcl_visualization::PointCloudColorHandlerRGBField<sensor_msgs::PointCloud2> (*cloud_)); 00129 else 00130 color_handler.reset (new pcl_visualization::PointCloudColorHandlerGenericField<sensor_msgs::PointCloud2> (*cloud_, cloud_->fields[i].name)); 00131 p.addPointCloud (cloud_xyz, color_handler, "cloud"); 00132 } 00133 00134 // Set the point size 00135 p.setPointCloudRenderingProperties (pcl_visualization::PCL_VISUALIZER_POINT_SIZE, psize, "cloud"); 00136 00137 // Set the old color handler index 00138 if (color_handler_idx != -1) 00139 p.updateColorHandlerIndex ("cloud", color_handler_idx); 00140 cloud_old_ = cloud_; 00141 } 00142 m.unlock (); 00143 } 00144 00145 return (0); 00146 } 00147 /* ]--- */