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 #include <boost/thread/thread.hpp>
00038 #include <boost/date_time/posix_time/posix_time.hpp>
00039 #include <pcl/point_cloud.h>
00040 #include <pcl/point_types.h>
00041 #include <pcl/io/openni_grabber.h>
00042 #include <pcl/visualization/cloud_viewer.h>
00043 #include <pcl/io/openni_camera/openni_driver.h>
00044 #include <pcl/filters/color.h>
00045 #include <pcl/console/parse.h>
00046 #include <pcl/common/time.h>
00047
00048 #define FPS_CALC(_WHAT_) \
00049 do \
00050 { \
00051 static unsigned count = 0;\
00052 static double last = pcl::getTime ();\
00053 double now = pcl::getTime (); \
00054 ++count; \
00055 if (now - last >= 1.0) \
00056 { \
00057 std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" << std::endl; \
00058 count = 0; \
00059 last = now; \
00060 } \
00061 }while(false)
00062
00063
00064 template <typename PointType>
00065 class OpenNIPassthrough
00066 {
00067 public:
00068 typedef pcl::PointCloud<PointType> Cloud;
00069 typedef typename Cloud::Ptr CloudPtr;
00070 typedef typename Cloud::ConstPtr CloudConstPtr;
00071
00072 OpenNIPassthrough (pcl::OpenNIGrabber& grabber, unsigned char red, unsigned char green, unsigned char blue, unsigned char radius)
00073 : viewer ("PCL OpenNI ColorFilter Viewer")
00074 , grabber_(grabber)
00075 {
00076 boost::function<void (const CloudConstPtr&)> f = boost::bind (&OpenNIPassthrough::cloud_cb_, this, _1);
00077 boost::signals2::connection c = grabber_.registerCallback (f);
00078
00079 std::vector<bool> lookup(1<<24, false);
00080 fillLookup (lookup, red, green, blue, radius);
00081 unsigned set = 0;
00082 for (unsigned i = 0; i < (1<<24); ++i)
00083 if (lookup[i])
00084 ++set;
00085
00086 cout << "used colors: " << set << endl;
00087
00088 color_filter_.setLookUpTable (lookup);
00089 }
00090
00091 void fillLookup (std::vector<bool>& lookup, unsigned char red, unsigned char green, unsigned char blue, unsigned radius)
00092 {
00093 unsigned radius_sqr = radius * radius;
00094 pcl::RGB color;
00095 for (color.rgba = 0; color.rgba < (1<<24); ++color.rgba)
00096 {
00097 unsigned dist = (unsigned(color.r) - unsigned(red)) * (unsigned(color.r) - unsigned(red)) +
00098 (unsigned(color.g) - unsigned(green)) * (unsigned(color.g) - unsigned(green)) +
00099 (unsigned(color.b) - unsigned(blue)) * (unsigned(color.b) - unsigned(blue));
00100 if (dist < radius_sqr)
00101 lookup [color.rgba] = true;
00102 else
00103 lookup [color.rgba] = false;
00104 }
00105 }
00106
00107 void
00108 cloud_cb_ (const CloudConstPtr& cloud)
00109 {
00110 boost::mutex::scoped_lock lock (mtx_);
00111 FPS_CALC ("computation");
00112
00113 cloud_color_.reset (new Cloud);
00114
00115 color_filter_.setInputCloud (cloud);
00116 color_filter_.filter (*cloud_color_);
00117 cloud_ = cloud;
00118 }
00119
00120 void
00121 run ()
00122 {
00123
00124 grabber_.start ();
00125
00126 while (!viewer.wasStopped ())
00127 {
00128 if (cloud_color_)
00129 {
00130 boost::mutex::scoped_lock lock (mtx_);
00131
00132 FPS_CALC ("visualization");
00133 CloudPtr temp_cloud;
00134 temp_cloud.swap (cloud_color_);
00135 viewer.showCloud (temp_cloud);
00136 }
00137 }
00138
00139 grabber_.stop ();
00140 }
00141
00142 pcl::ColorFilter<PointType> color_filter_;
00143 pcl::visualization::CloudViewer viewer;
00144 pcl::OpenNIGrabber& grabber_;
00145 std::string device_id_;
00146 boost::mutex mtx_;
00147 CloudConstPtr cloud_;
00148 CloudPtr cloud_color_;
00149 };
00150
00151 void
00152 usage (char ** argv)
00153 {
00154 std::cout << "usage: " << argv[0] << " <device_id> [-rgb <red> <green> <blue> [-radius <radius>] ]\n\n" << std::endl;
00155
00156 openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00157 if (driver.getNumberDevices () > 0)
00158 {
00159 for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00160 {
00161 cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00162 << ", connected: " << (int)driver.getBus (deviceIdx) << " @ " << (int)driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00163 cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
00164 << " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
00165 << " <serial-number> (only in Linux and for devices which provide serial numbers)" << endl;
00166 }
00167 }
00168 else
00169 cout << "No devices connected." << endl;
00170 }
00171
00172 int
00173 main (int argc, char ** argv)
00174 {
00175 if (argc < 2)
00176 {
00177 usage (argv);
00178 return 1;
00179 }
00180
00181 std::string arg (argv[1]);
00182
00183 if (arg == "--help" || arg == "-h")
00184 {
00185 usage (argv);
00186 return 1;
00187 }
00188
00189 unsigned char red = 0, green = 0, blue = 0;
00190 int rr, gg, bb;
00191 unsigned char radius = 442;
00192 int rad;
00193
00194 if (pcl::console::parse_3x_arguments (argc, argv, "-rgb", rr, gg, bb, true) != -1 )
00195 {
00196 cout << "-rgb present" << endl;
00197 int idx = pcl::console::parse_argument (argc, argv, "-radius", rad);
00198 if (idx != -1)
00199 {
00200 if (rad > 0)
00201 radius = rad;
00202 }
00203 if (rr >= 0 && rr < 256)
00204 red = (unsigned char) rr;
00205 if (gg >= 0 && gg < 256)
00206 green = (unsigned char) gg;
00207 if (bb >= 0 && bb < 256)
00208 blue = (unsigned char) bb;
00209 }
00210
00211 pcl::OpenNIGrabber grabber (arg);
00212
00213 if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba> ())
00214 {
00215 OpenNIPassthrough<pcl::PointXYZRGBA> v (grabber, red, green, blue, radius);
00216 v.run ();
00217 }
00218 else
00219 {
00220 cout << "device does not provide rgb stream" << endl;
00221 }
00222
00223 return (0);
00224 }