cloud_viewer.cpp
Go to the documentation of this file.
00001 
00038 #include <pcl/visualization/cloud_viewer.h>
00039 #include <pcl/visualization/pcl_visualizer.h>
00040 #include <pcl/visualization/boost.h>
00041 
00042 namespace pcl
00043 {
00044   struct cloud_show_base
00045   {
00046     virtual void pop () = 0;
00047     virtual bool popped () const = 0;
00048     typedef boost::shared_ptr<cloud_show_base> Ptr;
00049   };
00050 
00051   template <typename CloudT> 
00052   struct cloud_show : cloud_show_base
00053   {
00054     cloud_show (const std::string &cloud_name, typename CloudT::ConstPtr cloud,
00055       boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer) :
00056       cloud_name (cloud_name), cloud (cloud), viewer (viewer),popped_ (false)
00057     {}
00058 
00059     template <typename Handler> void
00060     pop (const Handler &handler)
00061     {
00062       double psize = 1.0, opacity = 1.0, linesize =1.0;
00063       viewer->getPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_LINE_WIDTH, linesize, cloud_name);
00064       viewer->getPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_OPACITY, opacity, cloud_name);
00065       viewer->getPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, psize, cloud_name);
00066 
00067       if (!viewer->updatePointCloud (cloud, handler, cloud_name))
00068       {
00069         viewer->addPointCloud (cloud, handler, cloud_name);
00070         viewer->resetCameraViewpoint (cloud_name);
00071       }
00072 
00073       // viewer->removePointCloud (cloud_name);
00074       viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_LINE_WIDTH, linesize, cloud_name);
00075       viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_OPACITY, opacity, cloud_name);
00076       viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, psize, cloud_name);
00077       popped_ = true;
00078     }
00079 
00080     virtual void pop ();
00081     
00082     virtual bool
00083     popped () const
00084     {
00085       return popped_;
00086     }
00087     
00088     std::string cloud_name;
00089     typename CloudT::ConstPtr cloud;
00090     boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer;
00091     bool popped_;
00092   };
00093   
00094   typedef pcl::PointCloud<pcl::PointXYZRGBA> cca;
00095   typedef pcl::PointCloud<pcl::PointXYZRGB> cc;
00096   typedef pcl::PointCloud<pcl::PointXYZI> gc;
00097   typedef pcl::PointCloud<pcl::PointXYZ> mc;
00098 
00099   template <> void
00100   cloud_show<cca>::pop ()
00101   {
00102     pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGBA> handler (cloud);
00103     pop (handler);
00104   }
00105   
00106   template <> void
00107   cloud_show<cc>::pop ()
00108   {
00109     pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> handler (cloud);
00110     pop (handler);
00111   }
00112   
00113   template <> void
00114   cloud_show<gc>::pop ()
00115   {
00116     pcl::visualization::PointCloudColorHandlerGenericField<pcl::PointXYZI> handler (cloud, "intensity");
00117     pop (handler);
00118   }
00119   
00120   template <> void
00121   cloud_show<mc>::pop ()
00122   {
00123     pcl::visualization::PointCloudGeometryHandlerXYZ<pcl::PointXYZ> handler (cloud);
00124     pop (handler);
00125   }
00126 }
00127 
00128 struct pcl::visualization::CloudViewer::CloudViewer_impl
00129 {
00131   CloudViewer_impl (const std::string& window_name) :
00132     window_name_ (window_name), has_cloud_ (false), quit_ (false)
00133   {
00134     viewer_thread_ = boost::thread (boost::ref (*this));
00135     while (!viewer_)
00136     {
00137       boost::thread::yield ();
00138     }
00139   }
00140 
00141   ~CloudViewer_impl ()
00142   {
00143   }
00144 
00146   template <typename T> void
00147   block_post_cloud (const typename T::ConstPtr &cloud, const std::string &name)
00148   {
00149     cloud_show_base::Ptr cs (new cloud_show<T>(name,cloud,viewer_));
00150     {
00151       boost::mutex::scoped_lock lock (mtx_);
00152       cloud_shows_.push_back (cs);
00153     }
00154     while (!cs->popped ())
00155     {
00156       boost::thread::yield ();
00157     }
00158   }
00159 
00160   template <typename T> void
00161   nonblock_post_cloud (const typename T::ConstPtr &cloud, const std::string &name)
00162   {
00163     cloud_show_base::Ptr cs (new cloud_show<T>(name,cloud,viewer_));
00164     {
00165       boost::mutex::scoped_lock lock (mtx_);
00166 
00167       cloud_shows_.push_back (cs);
00168     }
00169   }
00170 
00172   void
00173   operator() ()
00174   {
00175     using namespace pcl::visualization;
00176 
00177 #if ((VTK_MAJOR_VERSION == 5) && (VTK_MINOR_VERSION <= 4))
00178     viewer_ = boost::shared_ptr<PCLVisualizer>(new PCLVisualizer (window_name_));
00179 #else
00180     viewer_ = boost::shared_ptr<PCLVisualizer>(new PCLVisualizer (window_name_, true));
00181 #endif
00182     viewer_->setBackgroundColor (0.1, 0.1, 0.1);
00183     viewer_->addCoordinateSystem (0.1);
00184 
00185     while (!quit_)
00186     {
00187       {
00188         boost::mutex::scoped_lock lock (mtx_);
00189         while (!cloud_shows_.empty ())
00190         {
00191           cloud_shows_.back ()->pop ();
00192           cloud_shows_.pop_back ();
00193         }
00194       }
00195       {
00196         boost::mutex::scoped_lock lock (once_mtx);
00197         BOOST_FOREACH (CallableList::value_type& x, callables_once)
00198         {
00199           (x)(*viewer_);
00200         }
00201         callables_once.clear ();
00202       }
00203       {
00204         boost::mutex::scoped_lock lock (c_mtx);
00205         BOOST_FOREACH (CallableMap::value_type& x, callables)
00206         {
00207           (x.second)(*viewer_);
00208         }
00209       }
00210       if (viewer_->wasStopped ())
00211       {
00212           quit_ = true;
00213       }else
00214       {
00215         boost::mutex::scoped_lock lock (spin_mtx_);
00216         //TODO some smart waitkey like stuff here, so that wasStoped() can hold for a long time
00217         //maybe a counter
00218         viewer_->spinOnce (10); // Give the GUI millis to handle events, then return
00219       }
00220 
00221     }
00222     viewer_.reset ();
00223   }
00224 
00226   void
00227   post (VizCallable x, const std::string &key)
00228   {
00229     boost::mutex::scoped_lock lock (c_mtx);
00230     callables[key] = x;
00231   }
00232 
00233   void
00234   post (VizCallable x)
00235   {
00236     boost::mutex::scoped_lock lock (once_mtx);
00237     callables_once.push_back (x);
00238   }
00239 
00241   void
00242   remove (const std::string &key)
00243   {
00244     boost::mutex::scoped_lock lock (c_mtx);
00245     if (callables.find (key) != callables.end ())
00246       callables.erase (key);
00247   }
00248 
00249   std::string window_name_;
00250   boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer_;
00251   boost::mutex mtx_, spin_mtx_, c_mtx, once_mtx;
00252   boost::thread viewer_thread_;
00253   bool has_cloud_;
00254   bool quit_;
00255   std::list<boost::shared_ptr<cloud_show_base> > cloud_shows_;
00256   typedef std::map<std::string, VizCallable> CallableMap;
00257   CallableMap callables;
00258   typedef std::list<VizCallable> CallableList;
00259   CallableList callables_once;
00260 };
00261 
00263 pcl::visualization::CloudViewer::CloudViewer (const std::string &window_name) :
00264   impl_ (new CloudViewer_impl (window_name))
00265 {}
00266 
00267 pcl::visualization::CloudViewer::~CloudViewer ()
00268 {
00269   impl_->quit_ = true;
00270   impl_->viewer_thread_.join();
00271 }
00272 
00274 void
00275 pcl::visualization::CloudViewer::showCloud (const ColorACloud::ConstPtr &cloud,
00276                                             const std::string &cloudname)
00277 {
00278   if (!impl_->viewer_ || impl_->viewer_->wasStopped ())
00279     return;
00280   impl_->block_post_cloud<ColorACloud>(cloud, cloudname);
00281 }
00282 
00284 void
00285 pcl::visualization::CloudViewer::showCloud (const ColorCloud::ConstPtr &cloud,
00286                                             const std::string &cloudname)
00287 {
00288   if (!impl_->viewer_ || impl_->viewer_->wasStopped ())
00289     return;
00290   impl_->block_post_cloud<ColorCloud>(cloud, cloudname);
00291 }
00292 
00294 void
00295 pcl::visualization::CloudViewer::showCloud (const GrayCloud::ConstPtr &cloud,
00296                                             const std::string &cloudname)
00297 {
00298   if (!impl_->viewer_ || impl_->viewer_->wasStopped ())
00299     return;
00300   impl_->block_post_cloud<GrayCloud>(cloud, cloudname);
00301 }
00302 
00304 void
00305 pcl::visualization::CloudViewer::showCloud (const MonochromeCloud::ConstPtr &cloud,
00306                                             const std::string &cloudname)
00307 {
00308   if (!impl_->viewer_ || impl_->viewer_->wasStopped ())
00309     return;
00310   impl_->block_post_cloud<MonochromeCloud>(cloud, cloudname);
00311 }
00312 
00314 void
00315 pcl::visualization::CloudViewer::runOnVisualizationThread (VizCallable x, const std::string &key)
00316 {
00317   impl_->post (x, key);
00318 }
00319 
00321 void
00322 pcl::visualization::CloudViewer::runOnVisualizationThreadOnce (VizCallable x)
00323 {
00324   impl_->post (x);
00325 }
00326 
00328 void
00329 pcl::visualization::CloudViewer::removeVisualizationCallable (const std::string &key)
00330 {
00331   impl_->remove (key);
00332 }
00333 
00335 bool
00336 pcl::visualization::CloudViewer::wasStopped (int)
00337 {
00338   boost::thread::yield (); //allow this to be called in a loop
00339   return !impl_->viewer_;
00340 }
00341 
00343 boost::signals2::connection
00344 pcl::visualization::CloudViewer::registerKeyboardCallback (boost::function<void (const pcl::visualization::KeyboardEvent&)> callback)
00345 {
00346   return impl_->viewer_->registerKeyboardCallback (callback);
00347 }
00348 
00350 boost::signals2::connection
00351 pcl::visualization::CloudViewer::registerMouseCallback (boost::function<void (const pcl::visualization::MouseEvent&)> callback)
00352 {
00353   return impl_->viewer_->registerMouseCallback (callback);
00354 }
00355 
00357 boost::signals2::connection
00358 pcl::visualization::CloudViewer::registerPointPickingCallback (boost::function<void (const pcl::visualization::PointPickingEvent&)> callback)
00359 {
00360   return (impl_->viewer_->registerPointPickingCallback (callback));
00361 }
00362 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:22:46