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_visualization/cloud_viewer.h>
00039 #include <pcl_visualization/pcl_visualizer.h>
00040
00041 #include <boost/thread.hpp>
00042 #include <boost/thread/mutex.hpp>
00043 #include <boost/foreach.hpp>
00044
00045 struct pcl_visualization::CloudViewer::CloudViewer_impl
00046 {
00047 CloudViewer_impl (const std::string& window_name) :
00048 window_name_ (window_name), has_cloud_ (false), quit_ (false), cloud_ (0), gray_cloud_ (0)
00049 {
00050 viewer_thread_ = boost::thread (boost::ref (*this));
00051 while (!viewer_)
00052 {
00053 boost::thread::yield ();
00054 }
00055 }
00056 ~CloudViewer_impl ()
00057 {
00058 quit_ = true;
00059 viewer_thread_.join ();
00060 }
00061
00062 void
00063 block_post_cloud (const CloudViewer::ColorCloud* cloud, const std::string& name)
00064 {
00065 {
00066 boost::mutex::scoped_lock (mtx_);
00067 cloud_ = cloud;
00068 color_name_ = name;
00069 has_cloud_ = true;
00070 }
00071 while (cloud_ != NULL)
00072 {
00073 boost::thread::yield ();
00074 }
00075 }
00076 void
00077 block_post_cloud (const CloudViewer::GrayCloud* cloud, const std::string& name)
00078 {
00079 {
00080 boost::mutex::scoped_lock (mtx_);
00081 gray_cloud_ = cloud;
00082 gray_name_ = name;
00083 has_cloud_ = true;
00084 }
00085 while (gray_cloud_ != NULL)
00086 {
00087 boost::thread::yield ();
00088 }
00089
00090 }
00091 void
00092 operator() ()
00093 {
00094 viewer_ = boost::shared_ptr<pcl_visualization::PCLVisualizer> (new pcl_visualization::PCLVisualizer (window_name_));
00095 viewer_->setBackgroundColor (0.1, 0.1, 0.1);
00096 viewer_->addCoordinateSystem (0.1);
00097
00098 while (!quit_)
00099 {
00100 viewer_thread_.yield ();
00101 if (!has_cloud_)
00102 continue;
00103 {
00104 {
00105 boost::mutex::scoped_lock (mtx_);
00106 if (gray_cloud_ != NULL)
00107 {
00108 pcl_visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> handler (*gray_cloud_, 255, 0, 255);
00109 viewer_->removePointCloud (gray_name_);
00110 viewer_->addPointCloud (*gray_cloud_, handler, gray_name_);
00111 gray_cloud_ = 0;
00112 }
00113 else if (cloud_ != NULL)
00114 {
00115 pcl_visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> handler (*cloud_);
00116 viewer_->removePointCloud (color_name_);
00117 viewer_->addPointCloud (*cloud_, handler, color_name_);
00118 cloud_ = 0;
00119 }
00120 }
00121
00122 {
00123 boost::mutex::scoped_lock (c_mtx);
00124 BOOST_FOREACH(CallableMap::value_type& x, callables)
00125 {
00126 (x.second) (*viewer_);
00127 }
00128 }
00129 if (viewer_->wasStopped ())
00130 {
00131 return;
00132 }
00133 {
00134 boost::mutex::scoped_lock (spin_mtx_);
00135
00136
00137 viewer_->spinOnce ();
00138 }
00139 }
00140 }
00141 }
00142 void
00143 post (VizCallable x, const std::string& key)
00144 {
00145 boost::mutex::scoped_lock (c_mtx);
00146 callables[key] = x;
00147 }
00148 void
00149 remove (const std::string& key)
00150 {
00151 boost::mutex::scoped_lock (c_mtx);
00152 if (callables.find (key) != callables.end ())
00153 {
00154 callables.erase (key);
00155 }
00156 }
00157 std::string window_name_;
00158 boost::shared_ptr<pcl_visualization::PCLVisualizer> viewer_;
00159 boost::mutex mtx_, spin_mtx_, c_mtx;
00160 boost::thread viewer_thread_;
00161 bool has_cloud_;
00162 bool quit_;
00163 const CloudViewer::ColorCloud* cloud_;
00164 const CloudViewer::GrayCloud* gray_cloud_;
00165 std::string gray_name_, color_name_;
00166 typedef std::map<std::string, VizCallable> CallableMap;
00167 CallableMap callables;
00168
00169 };
00170
00171 pcl_visualization::CloudViewer::CloudViewer (const std::string& window_name) :
00172 impl_ (new CloudViewer_impl (window_name))
00173 {
00174
00175 }
00176
00177 pcl_visualization::CloudViewer::~CloudViewer ()
00178 {
00179 delete impl_;
00180 }
00181
00182 void
00183 pcl_visualization::CloudViewer::showCloud (const CloudViewer::ColorCloud& cloud, const std::string& cloudname)
00184 {
00185 if (!impl_->viewer_ || impl_->viewer_->wasStopped ())
00186 return;
00187 impl_->block_post_cloud (&cloud, cloudname);
00188 }
00189
00190 void
00191 pcl_visualization::CloudViewer::showCloud (const CloudViewer::GrayCloud& cloud, const std::string& cloudname)
00192 {
00193 if (!impl_->viewer_ || impl_->viewer_->wasStopped ())
00194 return;
00195 impl_->block_post_cloud (&cloud, cloudname);
00196 }
00197 void
00198 pcl_visualization::CloudViewer::runOnVisualizationThread (VizCallable x, const std::string& key)
00199 {
00200 impl_->post (x, key);
00201 }
00202
00203 void
00204 pcl_visualization::CloudViewer::removeVisualizationCallable (const std::string& key)
00205 {
00206 impl_->remove (key);
00207 }
00208
00209 bool
00210 pcl_visualization::CloudViewer::wasStopped (int millis)
00211 {
00212 boost::thread::yield ();
00213 if (impl_->viewer_)
00214 return (impl_->viewer_->wasStopped ());
00215 else
00216 return false;
00217 }