00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, 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: bag_read.cpp 30899 2010-07-16 04:56:51Z rusu $ 00035 * 00036 */ 00037 00046 #include <pcl_ros/io/bag_io.h> 00047 #include <pcl/point_types.h> 00048 00049 /* ---[ */ 00050 int 00051 main (int argc, char** argv) 00052 { 00053 sensor_msgs::PointCloud2ConstPtr cloud_blob, cloud_blob_prev; 00054 pcl::PointCloud<pcl::PointXYZ> cloud; 00055 00056 pcl_ros::BAGReader reader; 00057 if (!reader.open ("./test_io_bag.bag", "/narrow_stereo_textured/points2")) 00058 { 00059 ROS_ERROR ("Couldn't read file test_io_bag.bag. Try doing a 'make tests' in pcl, or download the file manually from http://pr.willowgarage.com/data/pcl/test_io_bag.bag"); 00060 return (-1); 00061 } 00062 00063 int cnt = 0; 00064 do 00065 { 00066 cloud_blob_prev = cloud_blob; 00067 cloud_blob = reader.getNextCloud (); 00068 if (cloud_blob_prev != cloud_blob) 00069 { 00070 pcl::fromROSMsg (*cloud_blob, cloud); 00071 ROS_INFO ("PointCloud with %d data points and frame %s (%f) received.", (int)cloud.points.size (), cloud.header.frame_id.c_str (), cloud.header.stamp.toSec ()); 00072 cnt++; 00073 } 00074 } 00075 while (cloud_blob != cloud_blob_prev); 00076 00077 ROS_INFO ("Total number of PointCloud messages processed: %d", cnt); 00078 00079 return (0); 00080 } 00081 /* ]--- */