00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #include <pcl/point_types.h>
00040 #include <pcl_ros/point_cloud.h>
00041 #include <pcl/ros/conversions.h>
00042 #include <pcl/io/io.h>
00043 #include <iostream>
00044 #include <boost/foreach.hpp>
00045 #include <rosbag/bag.h>
00046 #include <rosbag/view.h>
00047 #include <sensor_msgs/PointCloud2.h>
00048 #include <pcl_visualization/cloud_viewer.h>
00049
00050 void
00051 printHelp (int argc, char **argv)
00052 {
00053 std::cout << "Syntax is:" << argv[0] << " <file_name>.pcd [cloud topic name = points2]\n";
00054 }
00055
00056
00057 int
00058 main (int argc, char** argv)
00059 {
00060 if (argc < 2)
00061 {
00062 printHelp (argc, argv);
00063 return (-1);
00064 }
00065
00066 std::string cloud_topic = "points2";
00067 if (argc > 2)
00068 {
00069 cloud_topic = argv[2];
00070 }
00071
00072 rosbag::Bag bag;
00073 bag.open (argv[1], rosbag::bagmode::Read);
00074
00075 std::vector<std::string> topics;
00076 topics.push_back (cloud_topic);
00077
00078 pcl_visualization::CloudViewer viewer ("Simple Cloud Viewer");
00079
00080 while (!viewer.wasStopped ())
00081 {
00082 rosbag::View view (bag, rosbag::TopicQuery (topics));
00083
00084 BOOST_FOREACH(rosbag::MessageInstance const m, view)
00085 {
00086 if (viewer.wasStopped ())
00087 {
00088 std::cout << "quiting ..." << std::endl;
00089 return 0;
00090 }
00091 {
00092 pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr cloud = m.instantiate<pcl::PointCloud<pcl::PointXYZRGB> > ();
00093 if (cloud)
00094 viewer.showCloud (*cloud);
00095 }
00096 {
00097 pcl::PointCloud<pcl::PointXYZ>::ConstPtr cloud = m.instantiate<pcl::PointCloud<pcl::PointXYZ> > ();
00098 if (cloud)
00099 viewer.showCloud (*cloud);
00100 }
00101
00102 }
00103 }
00104 return 0;
00105 }
00106