Go to the documentation of this file.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 #include <pcl/point_cloud.h>
00039 #include <pcl/point_types.h>
00040 #include <pcl/io/openni_grabber.h>
00041 #include <pcl/io/pcd_io.h>
00042 #include <pcl/common/time.h>
00043 #include <pcl/console/print.h>
00044 #include <pcl/console/parse.h>
00045 #include <boost/filesystem.hpp>
00046 #include <pcl/visualization/pcl_visualizer.h>
00047
00048
00049 using namespace pcl::console;
00050 using namespace boost::filesystem;
00051
00052 template<typename PointType>
00053 class OpenNIGrabFrame
00054 {
00055 typedef pcl::PointCloud<PointType> Cloud;
00056 typedef typename Cloud::ConstPtr CloudConstPtr;
00057 public:
00058 OpenNIGrabFrame ()
00059 : visualizer_ (new pcl::visualization::PCLVisualizer ("OpenNI Viewer"))
00060 , writer_ ()
00061 , quit_ (false)
00062 , trigger_ (false)
00063 , continuous_ (false)
00064 , file_name_ ("")
00065 , dir_name_ ("")
00066 , format_ (4)
00067 {
00068 }
00069
00070 void
00071 cloud_cb_ (const CloudConstPtr& cloud)
00072 {
00073 if (quit_)
00074 return;
00075
00076 boost::mutex::scoped_lock lock (cloud_mutex_);
00077 cloud_ = cloud;
00078
00079 if (continuous_ || trigger_)
00080 saveCloud ();
00081
00082 trigger_ = false;
00083 }
00084
00085 void
00086 keyboard_callback (const pcl::visualization::KeyboardEvent& event, void*)
00087 {
00088 if (event.keyUp ())
00089 {
00090 switch (event.getKeyCode ())
00091 {
00092 case 27:
00093 case 'Q':
00094 case 'q': quit_ = true; visualizer_->close ();
00095 break;
00096 case ' ': continuous_ = !continuous_;
00097 break;
00098 }
00099 }
00100 }
00101
00102 void
00103 mouse_callback (const pcl::visualization::MouseEvent& mouse_event, void*)
00104 {
00105 if (mouse_event.getType() == pcl::visualization::MouseEvent::MouseButtonPress && mouse_event.getButton() == pcl::visualization::MouseEvent::LeftButton)
00106 {
00107 trigger_ = true;
00108 }
00109 }
00110
00111 CloudConstPtr
00112 getLatestCloud ()
00113 {
00114
00115 boost::mutex::scoped_lock lock(cloud_mutex_);
00116 CloudConstPtr temp_cloud;
00117 temp_cloud.swap (cloud_);
00118
00119
00120 return (temp_cloud);
00121 }
00122
00123 void saveCloud ()
00124 {
00125 std::stringstream ss;
00126 ss << dir_name_ << "/" << file_name_ << "_" << boost::posix_time::to_iso_string (boost::posix_time::microsec_clock::local_time ()) << ".pcd";
00127
00128 if (format_ & 1)
00129 {
00130 writer_.writeBinary<PointType> (ss.str (), *cloud_);
00131 std::cerr << "Data saved in BINARY format to " << ss.str () << std::endl;
00132 }
00133
00134 if (format_ & 2)
00135 {
00136 writer_.writeBinaryCompressed<PointType> (ss.str (), *cloud_);
00137 std::cerr << "Data saved in BINARY COMPRESSED format to " << ss.str () << std::endl;
00138 }
00139
00140 if (format_ & 4)
00141 {
00142 writer_.writeBinaryCompressed<PointType> (ss.str (), *cloud_);
00143 std::cerr << "Data saved in BINARY COMPRESSED format to " << ss.str () << std::endl;
00144 }
00145 }
00146
00147 void
00148 run ()
00149 {
00150
00151 visualizer_->registerMouseCallback (&OpenNIGrabFrame::mouse_callback, *this);
00152 visualizer_->registerKeyboardCallback(&OpenNIGrabFrame::keyboard_callback, *this);
00153
00154
00155 pcl::Grabber* interface = new pcl::OpenNIGrabber ();
00156
00157
00158 boost::function<void (const CloudConstPtr&)> f =
00159 boost::bind (&OpenNIGrabFrame::cloud_cb_, this, _1);
00160
00161
00162 boost::signals2::connection c = interface->registerCallback (f);
00163
00164
00165 interface->start ();
00166
00167
00168 while (!visualizer_->wasStopped())
00169 {
00170 visualizer_->spinOnce ();
00171 if (cloud_)
00172 {
00173 CloudConstPtr cloud = getLatestCloud ();
00174 if (!visualizer_->updatePointCloud (cloud, "OpenNICloud"))
00175 {
00176 visualizer_->addPointCloud (cloud, "OpenNICloud");
00177 visualizer_->resetCameraViewpoint ("OpenNICloud");
00178 }
00179 }
00180 boost::this_thread::sleep (boost::posix_time::microseconds (100));
00181 }
00182
00183
00184
00185
00186
00187 interface->stop ();
00188 }
00189
00190 void
00191 setOptions (std::string filename, std::string pcd_format, bool paused)
00192 {
00193 boost::filesystem::path path(filename);
00194
00195 if (filename.empty ())
00196 {
00197 dir_name_ = ".";
00198 file_name_ = "frame";
00199 }
00200 else
00201 {
00202 dir_name_ = path.parent_path ().string ();
00203
00204 if (!dir_name_.empty () && !boost::filesystem::exists (path.parent_path ()))
00205 {
00206 std::cerr << "directory \"" << path.parent_path () << "\" does not exist!\n";
00207 exit (1);
00208 }
00209 #if BOOST_FILESYSTEM_VERSION == 3
00210 file_name_ = path.stem ().string ();
00211 #else
00212 file_name_ = path.stem ();
00213 #endif
00214 }
00215
00216 std::cout << "dir: " << dir_name_ << " :: " << path.parent_path () << std::endl;
00217 #if BOOST_FILESYSTEM_VERSION == 3
00218 std::cout << "file: " << file_name_ << " :: " << path.stem (). string () << std::endl;
00219 #else
00220 std::cout << "file: " << file_name_ << " :: " << path.stem () << std::endl;
00221 #endif
00222
00223 if (pcd_format == "b" || pcd_format == "all")
00224 format_ |= 1;
00225 else if (pcd_format == "ascii" || pcd_format == "all")
00226 format_ |= 2;
00227 else if (pcd_format == "bc" || pcd_format == "all")
00228 format_ |= 4;
00229
00230 continuous_ = !paused;
00231 }
00232
00233 boost::shared_ptr<pcl::visualization::PCLVisualizer> visualizer_;
00234 pcl::PCDWriter writer_;
00235 bool quit_;
00236 bool continuous_;
00237 bool trigger_;
00238 std::string file_name_;
00239 std::string dir_name_;
00240 unsigned format_;
00241 CloudConstPtr cloud_;
00242 mutable boost::mutex cloud_mutex_;
00243 };
00244
00245 void
00246 usage (char ** argv)
00247 {
00248 std::cout << "usage: " << argv[0] << " <filename> <options>\n\n";
00249
00250 print_info (" filename: if no filename is provided a generic timestamp will be set as filename\n\n");
00251 print_info (" where options are:\n");
00252 print_info (" -format = PCD file format (b=binary; bc=binary compressed; ascii=ascii; all=all) (default: bc)\n");
00253 print_info (" -XYZ = store just a XYZ cloud\n");
00254 print_info (" -paused = start grabber in paused mode. Toggle pause by pressing the space bar\n");
00255 print_info (" or grab single frames by just pressing the left mouse button.\n");
00256 }
00257
00258 int
00259 main (int argc, char** argv)
00260 {
00261 std::string arg;
00262 if (argc > 1)
00263 arg = std::string (argv[1]);
00264
00265 if (arg == "--help" || arg == "-h")
00266 {
00267 usage (argv);
00268 return 1;
00269 }
00270
00271 std::string format = "bc";
00272 std::string filename;
00273 bool paused = false;
00274 bool xyz = false;
00275 if (argc > 1)
00276 {
00277
00278 std::vector<int> p_file_indices;
00279 p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00280 if (p_file_indices.size () > 0)
00281 filename = argv[p_file_indices[0]];
00282
00283 std::cout << "fname: " << filename << std::endl;
00284
00285 parse_argument (argc, argv, "-format", format);
00286 xyz = find_switch (argc, argv, "-XYZ");
00287 paused = find_switch (argc, argv, "-paused");
00288 }
00289
00290 if (xyz)
00291 {
00292 OpenNIGrabFrame<pcl::PointXYZ> grab_frame;
00293 grab_frame.setOptions (filename, format, paused);
00294 grab_frame.run ();
00295 }
00296 else
00297 {
00298 OpenNIGrabFrame<pcl::PointXYZRGBA> grab_frame;
00299 grab_frame.setOptions (filename, format, paused);
00300 grab_frame.run ();
00301 }
00302 return (0);
00303 }
00304