$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: pointimage_msgto_pcd.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 #include <pcl/range_image/range_image_planar.h> 00046 #include <sensor_msgs/Image.h> 00047 #include <stereo_msgs/DisparityImage.h> 00048 #include <sensor_msgs/CameraInfo.h> 00049 #include <pcl/common/common_headers.h> 00050 00051 #include <pcl_visualization/pcl_visualizer.h> 00052 #include "pcl_visualization/range_image_visualizer.h" 00053 00054 using namespace std; 00055 using namespace pcl; 00056 using namespace pcl_visualization; 00057 typedef PointXYZ PointType; 00058 00059 float angular_resolution = 0.5f, // Resolution of the range image 00060 noise_level = 0.0f, // Distance in which the z-buffer averages instead of taking the minimum 00061 min_range = 0.0f; // Minimum range for the range image creation 00062 int border_size = 0; // Additional border around the range image 00063 RangeImage::CoordinateFrame coordinate_frame = RangeImage::CAMERA_FRAME; 00064 int source = 0; // Default: Use PointCloud2 00065 00066 void printUsage (const char* progName) 00067 { 00068 cout << "\n\nUsage: "<<progName<<" [options] input:=<yourInput>\n\n" 00069 << "Options:\n" 00070 << "-------------------------------------------\n" 00071 << "-c <int> source coordinate frame (default "<<coordinate_frame<<")\n" 00072 << "-s source used to create the range image: " 00073 << "0 PointCloud2 (default), 1 depth image, 2 disparity image .\n" 00074 << "-r <float> angular resolution in degrees (default "<<angular_resolution<<")\n" 00075 << "-h this help\n" 00076 << "\n\n"; 00077 } 00078 00079 sensor_msgs::PointCloud2ConstPtr cloud_msg, old_cloud_msg; 00080 sensor_msgs::ImageConstPtr depth_image_msg, old_depth_image_msg; 00081 stereo_msgs::DisparityImageConstPtr disparity_image_msg, old_disparity_image_msg; 00082 sensor_msgs::CameraInfoConstPtr camera_info_msg; 00083 boost::mutex m; 00084 00085 void 00086 disparity_image_msg_cb (const stereo_msgs::DisparityImageConstPtr& msg) 00087 { 00088 m.lock (); 00089 disparity_image_msg = msg; 00090 m.unlock (); 00091 } 00092 00093 void 00094 depth_image_msg_cb (const sensor_msgs::ImageConstPtr& msg) 00095 { 00096 m.lock (); 00097 //std::cout << "Received depth image of size "<<msg->width<<"x"<<msg->height<<".\n"; 00098 depth_image_msg = msg; 00099 m.unlock (); 00100 } 00101 00102 void 00103 cloud_msg_cb (const sensor_msgs::PointCloud2ConstPtr& msg) 00104 { 00105 m.lock (); 00106 cloud_msg = msg; 00107 m.unlock (); 00108 } 00109 00110 void 00111 camera_info_msg_cb (const sensor_msgs::CameraInfoConstPtr& msg) 00112 { 00113 m.lock (); 00114 //std::cout << "Received camera info: " << "width="<<msg->width<<", height="<<msg->height<<", " 00115 //<< "center_x="<<msg->P[2]<<", center_y="<<msg->P[6]<<", " 00116 //<<"fl_x="<<msg->P[0]<<", fl_y="<<msg->P[5]<<".\n"; 00117 camera_info_msg = msg; 00118 m.unlock (); 00119 } 00120 00121 int 00122 main (int argc, char** argv) 00123 { 00124 // Read command line arguments. 00125 for (char c; (c = getopt (argc, argv, "s:hc:r:")) != -1; ) { 00126 switch (c) { 00127 case 'c': 00128 coordinate_frame = RangeImage::CoordinateFrame (strtol (optarg, NULL, 0)); 00129 break; 00130 case 'r': 00131 { 00132 angular_resolution = strtod (optarg, NULL); 00133 cout << PVARN(angular_resolution); 00134 break; 00135 } 00136 case 's': 00137 { 00138 source = strtol (optarg, NULL, 0); 00139 if (source < 0 || source > 2) 00140 { 00141 cout << "Source "<<source<<" is unknown.\n"; 00142 exit (0); 00143 } 00144 cout << "Receiving "<<(source==0 ? "point clouds" : (source==1 ? "depth images" : "disparity images"))<<".\n"; 00145 break; 00146 } 00147 case 'h': 00148 default: 00149 printUsage (argv[0]); 00150 exit (0); 00151 } 00152 } 00153 angular_resolution = deg2rad (angular_resolution); 00154 00155 ros::init (argc, argv, "tutorial_range_image_live_viewer"); 00156 ros::NodeHandle node_handle; 00157 ros::Subscriber subscriber, subscriber2; 00158 00159 if (node_handle.resolveName("input")=="/input") 00160 std::cerr << "Did you forget input:=<your topic>?\n"; 00161 00162 if (source==0) 00163 subscriber = node_handle.subscribe ("input", 1, cloud_msg_cb); 00164 else if (source==1) 00165 { 00166 if (node_handle.resolveName("input2")=="/input2") 00167 std::cerr << "Did you forget input2:=<your camera_info_topic>?\n"; 00168 subscriber = node_handle.subscribe ("input", 1, depth_image_msg_cb); 00169 subscriber2 = node_handle.subscribe ("input2", 1, camera_info_msg_cb); 00170 } 00171 else if (source==2) 00172 subscriber = node_handle.subscribe ("input", 1, disparity_image_msg_cb); 00173 00174 PCLVisualizer viewer (argc, argv, "Live viewer - point cloud"); 00175 RangeImageVisualizer range_image_widget("Live viewer - range image"); 00176 00177 RangeImagePlanar* range_image_planar; 00178 RangeImage* range_image; 00179 if (source==0) 00180 range_image = new RangeImage; 00181 else 00182 { 00183 range_image_planar = new RangeImagePlanar; 00184 range_image = range_image_planar; 00185 } 00186 00187 while (node_handle.ok ()) 00188 { 00189 usleep (10000); 00190 viewer.spinOnce (10); 00191 RangeImageVisualizer::spinOnce (); 00192 ros::spinOnce (); 00193 00194 if (source==0) 00195 { 00196 // If no new message received: continue 00197 if (!cloud_msg || cloud_msg == old_cloud_msg) 00198 continue; 00199 old_cloud_msg = cloud_msg; 00200 00201 Eigen::Affine3f sensor_pose(Eigen::Affine3f::Identity()); 00202 PointCloud<PointWithViewpoint> far_ranges; 00203 RangeImage::extractFarRanges(*cloud_msg, far_ranges); 00204 if (pcl::getFieldIndex(*cloud_msg, "vp_x")>=0) 00205 { 00206 PointCloud<PointWithViewpoint> tmp_pc; 00207 fromROSMsg(*cloud_msg, tmp_pc); 00208 Eigen::Vector3f average_viewpoint = RangeImage::getAverageViewPoint(tmp_pc); 00209 sensor_pose = Eigen::Translation3f(average_viewpoint) * sensor_pose; 00210 } 00211 PointCloud<PointType> point_cloud; 00212 fromROSMsg(*cloud_msg, point_cloud); 00213 range_image->createFromPointCloud(point_cloud, angular_resolution, deg2rad(360.0f), deg2rad(180.0f), 00214 sensor_pose, coordinate_frame, noise_level, min_range, border_size); 00215 } 00216 else if (source==1) 00217 { 00218 // If no new message received: continue 00219 if (!depth_image_msg || depth_image_msg == old_depth_image_msg || !camera_info_msg) 00220 continue; 00221 old_depth_image_msg = depth_image_msg; 00222 range_image_planar->setDepthImage(reinterpret_cast<const float*> (&depth_image_msg->data[0]), 00223 depth_image_msg->width, depth_image_msg->height, 00224 camera_info_msg->P[2], camera_info_msg->P[6], 00225 camera_info_msg->P[0], camera_info_msg->P[5], angular_resolution); 00226 } 00227 else if (source==2) 00228 { 00229 // If no new message received: continue 00230 if (!disparity_image_msg || disparity_image_msg == old_disparity_image_msg) 00231 continue; 00232 old_disparity_image_msg = disparity_image_msg; 00233 range_image_planar->setDisparityImage(reinterpret_cast<const float*> (&disparity_image_msg->image.data[0]), 00234 disparity_image_msg->image.width, disparity_image_msg->image.height, 00235 disparity_image_msg->f, disparity_image_msg->T, angular_resolution); 00236 } 00237 00238 range_image_widget.setRangeImage (*range_image); 00239 viewer.removePointCloud ("range image cloud"); 00240 pcl_visualization::PointCloudColorHandlerCustom<pcl::PointWithRange> color_handler_cloud(*range_image, 00241 200, 200, 200); 00242 viewer.addPointCloud (*range_image, color_handler_cloud, "range image cloud"); 00243 } 00244 }