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
00039
00040 #define SHOW_FPS 1
00041 #include <pcl/apps/timer.h>
00042 #include <pcl/common/common.h>
00043 #include <pcl/common/angles.h>
00044 #include <pcl/io/openni_grabber.h>
00045 #include <pcl/io/pcd_io.h>
00046 #include <pcl/keypoints/susan.h>
00047 #include <pcl/filters/extract_indices.h>
00048 #include <pcl/visualization/pcl_visualizer.h>
00049 #include <pcl/visualization/image_viewer.h>
00050 #include <pcl/console/print.h>
00051 #include <pcl/console/parse.h>
00052
00053 using namespace pcl;
00054 using namespace std;
00055
00056 typedef PointXYZRGBA PointT;
00057 typedef PointXYZRGBL KeyPointT;
00058
00060 class SUSANDemo
00061 {
00062 public:
00063 typedef PointCloud<PointT> Cloud;
00064 typedef Cloud::Ptr CloudPtr;
00065 typedef Cloud::ConstPtr CloudConstPtr;
00066
00067 SUSANDemo (Grabber& grabber)
00068 : cloud_viewer_ ("SUSAN 2D Keypoints -- PointCloud")
00069 , grabber_ (grabber)
00070 , image_viewer_ ("SUSAN 2D Keypoints -- Image")
00071 {
00072 }
00073
00075 void
00076 cloud_callback (const CloudConstPtr& cloud)
00077 {
00078 FPS_CALC ("cloud callback");
00079 boost::mutex::scoped_lock lock (cloud_mutex_);
00080 cloud_ = cloud;
00081
00082
00083 SUSANKeypoint<PointT, KeyPointT> susan;
00084 susan.setInputCloud (cloud);
00085 susan.setNumberOfThreads (6);
00086 susan.setNonMaxSupression (true);
00087 keypoints_.reset (new PointCloud<KeyPointT>);
00088 susan.compute (*keypoints_);
00089 }
00090
00092 void
00093 init ()
00094 {
00095 boost::function<void (const CloudConstPtr&) > cloud_cb = boost::bind (&SUSANDemo::cloud_callback, this, _1);
00096 cloud_connection = grabber_.registerCallback (cloud_cb);
00097 }
00098
00100 string
00101 getStrBool (bool state)
00102 {
00103 stringstream ss;
00104 ss << state;
00105 return (ss.str ());
00106 }
00107
00109 void
00110 run ()
00111 {
00112 grabber_.start ();
00113
00114 bool image_init = false, cloud_init = false;
00115 bool keypts = true;
00116
00117 while (!cloud_viewer_.wasStopped () && !image_viewer_.wasStopped ())
00118 {
00119 PointCloud<KeyPointT>::Ptr keypoints;
00120 CloudConstPtr cloud;
00121
00122 if (cloud_mutex_.try_lock ())
00123 {
00124 cloud_.swap (cloud);
00125 keypoints_.swap (keypoints);
00126
00127 cloud_mutex_.unlock ();
00128 }
00129
00130 if (cloud)
00131 {
00132 if (!cloud_init)
00133 {
00134 cloud_viewer_.setPosition (0, 0);
00135 cloud_viewer_.setSize (cloud->width, cloud->height);
00136 cloud_init = !cloud_init;
00137 }
00138
00139 if (!cloud_viewer_.updatePointCloud (cloud, "OpenNICloud"))
00140 {
00141 cloud_viewer_.addPointCloud (cloud, "OpenNICloud");
00142 cloud_viewer_.resetCameraViewpoint ("OpenNICloud");
00143 }
00144
00145 if (!image_init)
00146 {
00147 image_viewer_.setPosition (cloud->width, 0);
00148 image_viewer_.setSize (cloud->width, cloud->height);
00149 image_init = !image_init;
00150 }
00151
00152 image_viewer_.addRGBImage<PointT> (cloud);
00153
00154 if (keypoints && !keypoints->empty ())
00155 {
00156 image_viewer_.removeLayer (getStrBool (keypts));
00157 for (size_t i = 0; i < keypoints->size (); ++i)
00158 {
00159 int u = int (keypoints->points[i].label % cloud->width);
00160 int v = cloud->height - int (keypoints->points[i].label / cloud->width);
00161 image_viewer_.markPoint (u, v, visualization::red_color, visualization::blue_color, 10, getStrBool (!keypts));
00162 }
00163 keypts = !keypts;
00164
00165 visualization::PointCloudColorHandlerCustom<KeyPointT> blue (keypoints, 0, 0, 255);
00166 if (!cloud_viewer_.updatePointCloud (keypoints, blue, "keypoints"))
00167 cloud_viewer_.addPointCloud (keypoints, blue, "keypoints");
00168 cloud_viewer_.setPointCloudRenderingProperties (visualization::PCL_VISUALIZER_POINT_SIZE, 20, "keypoints");
00169 cloud_viewer_.setPointCloudRenderingProperties (visualization::PCL_VISUALIZER_OPACITY, 0.5, "keypoints");
00170 }
00171 }
00172
00173 cloud_viewer_.spinOnce ();
00174 image_viewer_.spinOnce ();
00175 boost::this_thread::sleep (boost::posix_time::microseconds (100));
00176 }
00177
00178 grabber_.stop ();
00179 cloud_connection.disconnect ();
00180 }
00181
00182 visualization::PCLVisualizer cloud_viewer_;
00183 Grabber& grabber_;
00184 boost::mutex cloud_mutex_;
00185 CloudConstPtr cloud_;
00186
00187 visualization::ImageViewer image_viewer_;
00188
00189 PointCloud<KeyPointT>::Ptr keypoints_;
00190
00191 private:
00192 boost::signals2::connection cloud_connection;
00193 };
00194
00195
00196 int
00197 main (int, char**)
00198 {
00199 string device_id ("#1");
00200 OpenNIGrabber grabber (device_id);
00201 SUSANDemo openni_viewer (grabber);
00202
00203 openni_viewer.init ();
00204 openni_viewer.run ();
00205
00206 return (0);
00207 }
00208