$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2011 Willow Garage, Inc. 00005 * Suat Gedikli <gedikli@willowgarage.com> 00006 * Patrick Michelich <michelich@willowgarage.com> 00007 * Radu Bogdan Rusu <rusu@willowgarage.com> 00008 * 00009 * All rights reserved. 00010 * 00011 * Redistribution and use in source and binary forms, with or without 00012 * modification, are permitted provided that the following conditions 00013 * are met: 00014 * 00015 * * Redistributions of source code must retain the above copyright 00016 * notice, this list of conditions and the following disclaimer. 00017 * * Redistributions in binary form must reproduce the above 00018 * copyright notice, this list of conditions and the following 00019 * disclaimer in the documentation and/or other materials provided 00020 * with the distribution. 00021 * * Neither the name of Willow Garage, Inc. nor the names of its 00022 * contributors may be used to endorse or promote products derived 00023 * from this software without specific prior written permission. 00024 * 00025 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00026 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00027 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00028 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00029 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00030 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00031 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00032 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00033 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00034 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00035 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00036 * POSSIBILITY OF SUCH DAMAGE. 00037 * 00038 */ 00039 #include <pluginlib/class_list_macros.h> 00040 #include "openni_nodelet.h" 00041 #include "openni_camera/openni_device_kinect.h" 00042 #include "openni_camera/openni_image.h" 00043 #include "openni_camera/openni_depth_image.h" 00044 #include <sensor_msgs/image_encodings.h> 00045 #include <pcl_ros/point_cloud.h> 00046 #include <pcl/point_types.h> 00047 #include <stereo_msgs/DisparityImage.h> 00048 00049 #if ROS_VERSION_MINIMUM(1, 3, 0) 00050 #include <sensor_msgs/distortion_models.h> 00051 #endif 00052 00053 using namespace std; 00054 using namespace openni_wrapper; 00055 namespace openni_camera 00056 { 00057 inline bool operator == (const XnMapOutputMode& mode1, const XnMapOutputMode& mode2) 00058 { 00059 return (mode1.nXRes == mode2.nXRes && mode1.nYRes == mode2.nYRes && mode1.nFPS == mode2.nFPS); 00060 } 00061 inline bool operator != (const XnMapOutputMode& mode1, const XnMapOutputMode& mode2) 00062 { 00063 return !(mode1 == mode2); 00064 } 00065 00066 00067 PLUGINLIB_DECLARE_CLASS (openni_camera, OpenNINodelet, openni_camera::OpenNINodelet, nodelet::Nodelet); 00068 00069 typedef union 00070 { 00071 struct /*anonymous*/ 00072 { 00073 unsigned char Blue; 00074 unsigned char Green; 00075 unsigned char Red; 00076 unsigned char Alpha; 00077 }; 00078 float float_value; 00079 long long_value; 00080 } RGBValue; 00081 00082 OpenNINodelet::~OpenNINodelet () 00083 { 00084 device_->stopDepthStream (); 00085 device_->stopImageStream (); 00086 } 00087 00088 void OpenNINodelet::onInit () 00089 { 00090 // NOTE: This version (mistakenly) creates a new NodeHandle independent of nodelet::getNodeHandle(). 00091 // It uses the default ROS callback queue instead of the nodelet manager's callback queue. On the 00092 // bright side, this happened to avoid various threading issues. 00093 ros::NodeHandle comm_nh(getNodeHandle ().resolveName ("camera")); // for topics, services 00094 ros::NodeHandle param_nh = getPrivateNodeHandle (); // for parameters 00095 00096 updateModeMaps (); // registering mapping from config modes to XnModes and vice versa 00097 device_ = boost::shared_ptr<openni_wrapper::OpenNIDevice > ((openni_wrapper::OpenNIDevice*)NULL); 00098 setupDevice (param_nh); // will change config_ to default values or user given values from param server 00099 00100 param_nh.param ("rgb_frame_id", rgb_frame_id_, string ("")); 00101 if (rgb_frame_id_.empty ()) 00102 { 00103 rgb_frame_id_ = "/openni_rgb_optical_frame"; 00104 NODELET_INFO ("'rgb_frame_id' not set. using default: '%s'", rgb_frame_id_.c_str()); 00105 } 00106 else 00107 NODELET_INFO ("rgb_frame_id = '%s' ", rgb_frame_id_.c_str()); 00108 00109 param_nh.param ("depth_frame_id", depth_frame_id_, string ("")); 00110 if (depth_frame_id_.empty ()) 00111 { 00112 depth_frame_id_ = "/openni_depth_optical_frame"; 00113 NODELET_INFO ("'depth_frame_id' not set. using default: '%s'", depth_frame_id_.c_str()); 00114 } 00115 else 00116 NODELET_INFO ("depth_frame_id = '%s' ", depth_frame_id_.c_str()); 00117 00118 param_nh.param ("use_indices", use_indices_, false); 00119 00120 image_transport::ImageTransport imageTransport (comm_nh); 00121 image_transport::SubscriberStatusCallback subscriberChanged = boost::bind(&OpenNINodelet::subscriberChangedEvent, this); 00122 pub_rgb_image_ = imageTransport.advertise ("rgb/image_color", 5, subscriberChanged, subscriberChanged ); 00123 pub_image_raw_ = imageTransport.advertise ("rgb/image_raw", 5, subscriberChanged, subscriberChanged ); 00124 pub_gray_image_ = imageTransport.advertise ("rgb/image_mono" , 5, subscriberChanged, subscriberChanged ); 00125 pub_depth_image_ = imageTransport.advertise ("depth/image" , 5, subscriberChanged, subscriberChanged ); 00126 pub_depth_raw_ = imageTransport.advertise ("depth/image_raw", 5, subscriberChanged, subscriberChanged ); 00127 00128 ros::SubscriberStatusCallback subscriberChanged2 = boost::bind(&OpenNINodelet::subscriberChangedEvent, this); 00129 pub_disparity_ = comm_nh.advertise<stereo_msgs::DisparityImage > ("depth/disparity", 5, subscriberChanged2, subscriberChanged2); 00130 pub_rgb_info_ = comm_nh.advertise<sensor_msgs::CameraInfo > ("rgb/camera_info", 5, subscriberChanged2, subscriberChanged2); 00131 pub_depth_info_ = comm_nh.advertise<sensor_msgs::CameraInfo > ("depth/camera_info", 5, subscriberChanged2, subscriberChanged2); 00132 pub_point_cloud_ = comm_nh.advertise<pcl::PointCloud<pcl::PointXYZ> > ("depth/points", 5, subscriberChanged2, subscriberChanged2); 00133 pub_point_cloud_rgb_ = comm_nh.advertise<pcl::PointCloud<pcl::PointXYZRGB> > ("rgb/points", 5, subscriberChanged2, subscriberChanged2); 00134 00135 if (use_indices_) 00136 sub_mask_indices_ = comm_nh.subscribe("depth/indices", 5, &OpenNINodelet::maskIndicesCb, this); 00137 00138 SyncPolicy sync_policy (4); // queue size 00139 depth_rgb_sync_.reset (new Synchronizer (sync_policy)); 00140 depth_rgb_sync_->registerCallback (boost::bind (&OpenNINodelet::publishXYZRGBPointCloud, this, _1, _2)); 00141 00142 // initialize dynamic reconfigure 00143 reconfigure_server_.reset (new ReconfigureServer (reconfigure_mutex_, param_nh)); 00144 reconfigure_mutex_.lock (); 00145 reconfigure_server_->updateConfig (config_); 00146 reconfigure_server_->setCallback (boost::bind (&OpenNINodelet::configCallback, this, _1, _2)); 00147 reconfigure_mutex_.unlock (); 00148 } 00149 00150 void OpenNINodelet::setupDevice (ros::NodeHandle& param_nh) 00151 { 00152 // Initialize the openni device 00153 OpenNIDriver& driver = OpenNIDriver::getInstance (); 00154 00155 do { 00156 // Don't requie sigkill when waiting for device. 00157 if (!ros::ok()) 00158 exit(-1); 00159 00160 driver.updateDeviceList (); 00161 00162 if (driver.getNumberDevices () == 0) 00163 { 00164 NODELET_INFO ("[%s] No devices connected.... waiting for devices to be connected", getName ().c_str ()); 00165 sleep(1); 00166 continue; 00167 } 00168 00169 NODELET_INFO ("[%s] Number devices connected: %d", getName ().c_str (), driver.getNumberDevices ()); 00170 for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx) 00171 { 00172 NODELET_INFO ("[%s] %u. device on bus %03u:%02u is a %s (%03x) from %s (%03x) with serial id \'%s\'" 00173 , getName ().c_str (), deviceIdx + 1, driver.getBus (deviceIdx), driver.getAddress (deviceIdx) 00174 , driver.getProductName (deviceIdx), driver.getProductID (deviceIdx), driver.getVendorName (deviceIdx) 00175 , driver.getVendorID (deviceIdx), driver.getSerialNumber (deviceIdx)); 00176 } 00177 00178 string device_id; 00179 param_nh.param ("device_id", device_id, std::string ()); 00180 00181 try { 00182 if (device_id.empty ()) 00183 { 00184 NODELET_WARN ("[%s] device_id is not set! Using first device.", getName ().c_str ()); 00185 device_ = driver.getDeviceByIndex (0); 00186 } 00187 else if (device_id.find ('@') != string::npos) 00188 { 00189 size_t pos = device_id.find ('@'); 00190 unsigned bus = atoi (device_id.substr (0, pos).c_str ()); 00191 unsigned address = atoi (device_id.substr (pos + 1, device_id.length () - pos - 1).c_str ()); 00192 NODELET_INFO ("[%s] searching for device with bus@address = %d@%d", getName ().c_str (), bus, address); 00193 device_ = driver.getDeviceByAddress (bus, address); 00194 } 00195 else if (device_id[0] == '#') 00196 { 00197 unsigned index = atoi (device_id.c_str () + 1); 00198 NODELET_INFO ("[%s] searching for device with index = %d", getName ().c_str (), index); 00199 device_ = driver.getDeviceByIndex (index - 1); 00200 } 00201 else 00202 { 00203 NODELET_INFO ("[%s] searching for device with serial number = %s", getName ().c_str (), device_id.c_str ()); 00204 device_ = driver.getDeviceBySerialNumber (device_id); 00205 } 00206 } 00207 catch (const OpenNIException& exception) 00208 { 00209 if (!device_) 00210 { 00211 NODELET_INFO ("[%s] No matching device found.... waiting for devices. Reason: %s", getName ().c_str (), exception.what ()); 00212 sleep (1); 00213 continue; 00214 } 00215 else 00216 { 00217 NODELET_ERROR ("[%s] could not retrieve device. Reason %s", getName ().c_str (), exception.what ()); 00218 exit (-1); 00219 } 00220 } 00221 } while (!device_); 00222 00223 NODELET_INFO ("[%s] Opened '%s' on bus %d:%d with serial number '%s'", getName ().c_str (), 00224 device_->getProductName (), device_->getBus (), device_->getAddress (), device_->getSerialNumber ()); 00225 00226 device_->registerImageCallback (&OpenNINodelet::imageCallback, *this); 00227 device_->registerDepthCallback (&OpenNINodelet::depthCallback, *this); 00228 00229 bool registration = false; 00230 param_nh.param ("depth_registration", registration, false ); 00231 config_.depth_registration = registration; 00232 00233 int debayering_method = 0; 00234 param_nh.param ("debayering", debayering_method, 0 ); 00235 if(debayering_method > 2 || debayering_method < 0) 00236 { 00237 NODELET_ERROR ("Unknown debayering method %d. Only Folowing values are available: Bilinear (0), EdgeAware (1), EdgeAwareWeighted (2). Falling back to Bilinear (0).", debayering_method); 00238 debayering_method = 0; 00239 } 00240 config_.debayering = debayering_method; 00241 00242 param_nh.param ("depth_time_offset", config_.depth_time_offset, 0.0 ); 00243 if(config_.depth_time_offset > 1.0 || config_.depth_time_offset < -1.0) 00244 { 00245 NODELET_ERROR ("depth time offset is % 2.5f seconds. Thats unlikely... setting back to 0.0 seconds", config_.depth_time_offset); 00246 config_.depth_time_offset = 0.0; 00247 } 00248 00249 param_nh.param ("image_time_offset", config_.image_time_offset, 0.0 ); 00250 if(config_.image_time_offset > 1.0 || config_.image_time_offset < -1.0) 00251 { 00252 NODELET_ERROR ("image time offset is % 2.5f seconds. Thats unlikely... setting back to 0.0 seconds", config_.image_time_offset); 00253 config_.image_time_offset = 0.0; 00254 } 00255 00256 int image_mode = mapXnMode2ConfigMode (device_->getDefaultImageMode ()); 00257 param_nh.param ("image_mode", image_mode, image_mode ); 00258 if (image_mode < config_.__getMin__().image_mode || image_mode > config_.__getMax__ ().image_mode || 00259 !isImageModeSupported (image_mode)) 00260 { 00261 XnMapOutputMode image_md = device_->getDefaultImageMode (); 00262 NODELET_ERROR ("Unknown or unsopported image mode %d. Falling back to default mode %dx%d@%d.", image_mode, image_md.nXRes, image_md.nYRes, image_md.nFPS); 00263 image_mode = mapXnMode2ConfigMode (image_md); 00264 } 00265 config_.image_mode = image_mode; 00266 00267 int depth_mode = mapXnMode2ConfigMode (device_->getDefaultDepthMode ()); 00268 param_nh.param ("depth_mode", depth_mode, depth_mode ); 00269 if (depth_mode < OpenNI_VGA_30Hz || depth_mode > config_.__getMax__ ().image_mode || 00270 !isDepthModeSupported (depth_mode)) 00271 { 00272 XnMapOutputMode depth_md = device_->getDefaultImageMode (); 00273 NODELET_ERROR ("Unknown or unsopported depth mode %d. Falling back to default mode %dx%d@%d.", depth_mode, depth_md.nXRes, depth_md.nYRes, depth_md.nFPS); 00274 depth_mode = mapXnMode2ConfigMode (depth_md); 00275 } 00276 config_.depth_mode = depth_mode; 00277 00278 XnMapOutputMode image_md = mapConfigMode2XnMode ( config_.image_mode); 00279 image_width_ = image_md.nXRes; 00280 image_height_ = image_md.nYRes; 00281 00282 XnMapOutputMode depth_md = mapConfigMode2XnMode ( config_.depth_mode); 00283 depth_width_ = depth_md.nXRes; 00284 depth_height_ = depth_md.nYRes; 00285 } 00286 00287 void OpenNINodelet::imageCallback (boost::shared_ptr<openni_wrapper::Image> image, void* cookie) 00288 { 00289 ros::Time time = ros::Time::now () + ros::Duration(config_.image_time_offset); 00290 00291 // mode is switching -> probably image sizes are not consistend... skip this frame 00292 //if (!image_mutex_.try_lock ()) 00293 // return; 00294 00295 if (pub_rgb_info_.getNumSubscribers () > 0) 00296 pub_rgb_info_.publish (fillCameraInfo (time, true)); 00297 00298 if (pub_image_raw_.getNumSubscribers () > 0) 00299 publishRgbImageRaw (*image, time); 00300 00301 if (pub_rgb_image_.getNumSubscribers () > 0 || pub_point_cloud_rgb_.getNumSubscribers () > 0 ) 00302 publishRgbImage (*image, time); 00303 00304 if (pub_gray_image_.getNumSubscribers () > 0) 00305 publishGrayImage (*image, time); 00306 00307 //image_mutex_.unlock (); 00308 } 00309 00310 void OpenNINodelet::depthCallback (boost::shared_ptr<openni_wrapper::DepthImage> depth_image, void* cookie) 00311 { 00312 ros::Time time = ros::Time::now () + ros::Duration(config_.depth_time_offset); 00313 //if (!depth_mutex_.try_lock ()) 00314 // return; 00315 00316 // Camera info for depth image 00317 if (pub_depth_info_.getNumSubscribers () > 0) 00318 pub_depth_info_.publish (fillCameraInfo (time, false)); 00319 00320 // Depth image 00321 if (pub_depth_raw_.getNumSubscribers () > 0) 00322 publishDepthImageRaw (*depth_image, time); 00323 00324 // Depth image 00325 if (pub_depth_image_.getNumSubscribers () > 0 || (pub_point_cloud_rgb_.getNumSubscribers () > 0 )) 00326 publishDepthImage (*depth_image, time); 00327 00328 // Disparity image 00329 if (pub_disparity_.getNumSubscribers () > 0) 00330 publishDisparity (*depth_image, time); 00331 00332 // Unregistered point cloud 00333 if (pub_point_cloud_.getNumSubscribers () > 0 ) 00334 publishXYZPointCloud (*depth_image, time); 00335 00336 //depth_mutex_.unlock (); 00337 } 00338 00339 void OpenNINodelet::subscriberChangedEvent () 00340 { 00341 // chek if we need to start/stop any stream 00342 if (isImageStreamRequired () && !device_->isImageStreamRunning ()) 00343 { 00344 device_->startImageStream (); 00345 startSynchronization (); 00346 } 00347 else if (!isImageStreamRequired () && device_->isImageStreamRunning ()) 00348 { 00349 stopSynchronization (); 00350 device_->stopImageStream (); 00351 if (pub_rgb_info_.getNumSubscribers() > 0) 00352 NODELET_WARN("Camera Info for rgb stream has subscribers, but stream has stopped."); 00353 } 00354 00355 if (isDepthStreamRequired () && !device_->isDepthStreamRunning ()) 00356 { 00357 device_->startDepthStream (); 00358 startSynchronization (); 00359 } 00360 else if ( !isDepthStreamRequired () && device_->isDepthStreamRunning ()) 00361 { 00362 stopSynchronization (); 00363 device_->stopDepthStream (); 00364 if (pub_depth_info_.getNumSubscribers() > 0) 00365 NODELET_WARN("Camera Info for depth stream has subscribers, but stream has stopped."); 00366 } 00367 00368 // if PointcloudXYZRGB is subscribed, we have to assure that depth stream is registered and 00369 // image stream size is at least as big as the depth image size 00370 if (pub_point_cloud_rgb_.getNumSubscribers() > 0) 00371 { 00372 Config config = config_; 00373 00374 reconfigure_mutex_.lock (); 00375 if (!device_->isDepthRegistered ()) 00376 { 00377 NODELET_WARN ("turning on depth registration, since PointCloudXYZRGB has subscribers."); 00378 device_->setDepthRegistration (true); 00379 config.depth_registration = true; 00380 } 00381 00382 XnMapOutputMode depth_mode = mapConfigMode2XnMode (config_.depth_mode); 00383 XnMapOutputMode image_mode = mapConfigMode2XnMode (config_.image_mode); 00384 if (depth_mode.nXRes > image_mode.nXRes || depth_mode.nYRes > image_mode.nYRes) 00385 { 00386 NODELET_WARN ("PointCloudXYZRGB need at least the same image size for mapping rgb values to the points"); 00387 config.image_mode = config_.depth_mode; 00388 } 00389 00390 reconfigure_server_->updateConfig (config); 00391 configCallback (config, 0); 00392 reconfigure_mutex_.unlock (); 00393 } 00394 } 00395 00396 void OpenNINodelet::publishRgbImage (const Image& image, ros::Time time) const 00397 { 00398 sensor_msgs::ImagePtr rgb_msg = boost::make_shared<sensor_msgs::Image > (); 00399 rgb_msg->header.stamp = time; 00400 rgb_msg->header.frame_id = rgb_frame_id_; 00401 rgb_msg->encoding = sensor_msgs::image_encodings::RGB8; 00402 rgb_msg->height = image_height_; 00403 rgb_msg->width = image_width_; 00404 rgb_msg->step = image_width_ * 3; 00405 rgb_msg->data.resize (rgb_msg->height * rgb_msg->step); 00406 image.fillRGB (rgb_msg->width, rgb_msg->height, &rgb_msg->data[0], rgb_msg->step); 00407 00408 if (pub_rgb_image_.getNumSubscribers () > 0) 00409 pub_rgb_image_.publish (rgb_msg); 00410 00411 if (pub_point_cloud_rgb_.getNumSubscribers () > 0) 00412 depth_rgb_sync_->add < 1 > (rgb_msg); 00413 } 00414 00415 void OpenNINodelet::publishRgbImageRaw (const Image& image, ros::Time time) const 00416 { 00417 sensor_msgs::ImagePtr rgb_msg = boost::make_shared<sensor_msgs::Image > (); 00418 rgb_msg->header.stamp = time; 00419 rgb_msg->header.frame_id = rgb_frame_id_; 00420 if (image.getEncoding () == openni_wrapper::Image::BAYER_GRBG) 00421 { 00422 rgb_msg->encoding = sensor_msgs::image_encodings::BAYER_GRBG8; 00423 rgb_msg->step = image_width_ * 1; 00424 } 00425 else if (image.getEncoding () == openni_wrapper::Image::YUV422) 00426 { 00427 rgb_msg->encoding = sensor_msgs::image_encodings::YUV422; 00428 rgb_msg->step = image_width_ * 2; // 4 bytes for 2 pixels 00429 } 00430 rgb_msg->height = image_height_; 00431 rgb_msg->width = image_width_; 00432 rgb_msg->data.resize (rgb_msg->height * rgb_msg->step); 00433 image.fillRaw (&rgb_msg->data[0]); 00434 00435 if (pub_image_raw_.getNumSubscribers () > 0) 00436 pub_image_raw_.publish (rgb_msg); 00437 } 00438 00439 void OpenNINodelet::publishGrayImage (const Image& image, ros::Time time) const 00440 { 00441 sensor_msgs::ImagePtr gray_msg = boost::make_shared<sensor_msgs::Image > (); 00442 gray_msg->header.stamp = time; 00443 gray_msg->header.frame_id = rgb_frame_id_; 00444 gray_msg->encoding = sensor_msgs::image_encodings::MONO8; 00445 gray_msg->height = image_height_; 00446 gray_msg->width = image_width_; 00447 gray_msg->step = image_width_; 00448 gray_msg->data.resize (gray_msg->height * gray_msg->step); 00449 image.fillGrayscale (gray_msg->width, gray_msg->height, &gray_msg->data[0], gray_msg->step); 00450 00451 pub_gray_image_.publish (gray_msg); 00452 } 00453 00454 void OpenNINodelet::publishDepthImage (const DepthImage& depth, ros::Time time) const 00455 { 00456 sensor_msgs::ImagePtr depth_msg = boost::make_shared<sensor_msgs::Image > (); 00457 depth_msg->header.stamp = time; 00458 depth_msg->header.frame_id = device_->isDepthRegistered () ? rgb_frame_id_ : depth_frame_id_; 00459 depth_msg->encoding = sensor_msgs::image_encodings::TYPE_32FC1; 00460 depth_msg->height = depth_height_; 00461 depth_msg->width = depth_width_; 00462 depth_msg->step = depth_msg->width * sizeof (float); 00463 depth_msg->data.resize (depth_msg->height * depth_msg->step); 00464 00465 depth.fillDepthImage (depth_width_, depth_height_, reinterpret_cast<float*>(&depth_msg->data[0]), depth_msg->step); 00466 00467 if (pub_depth_image_.getNumSubscribers () > 0) 00468 pub_depth_image_.publish (depth_msg); 00469 00470 if (pub_point_cloud_rgb_.getNumSubscribers () > 0) 00471 depth_rgb_sync_->add < 0 > (depth_msg); 00472 } 00473 00474 void OpenNINodelet::publishDepthImageRaw (const DepthImage& depth, ros::Time time) const 00475 { 00476 sensor_msgs::ImagePtr depth_msg = boost::make_shared<sensor_msgs::Image > (); 00477 depth_msg->header.stamp = time; 00478 depth_msg->header.frame_id = device_->isDepthRegistered () ? rgb_frame_id_ : depth_frame_id_; 00479 depth_msg->encoding = sensor_msgs::image_encodings::TYPE_16UC1; // should actually be unsigned! 00480 depth_msg->height = depth_height_; 00481 depth_msg->width = depth_width_; 00482 depth_msg->step = depth_msg->width * sizeof (short); 00483 depth_msg->data.resize (depth_msg->height * depth_msg->step); 00484 00485 depth.fillDepthImageRaw (depth_width_, depth_height_, 00486 reinterpret_cast<unsigned short*>(&depth_msg->data[0]), depth_msg->step); 00487 00488 if (pub_depth_raw_.getNumSubscribers () > 0) 00489 pub_depth_raw_.publish (depth_msg); 00490 } 00491 00492 void OpenNINodelet::publishDisparity (const DepthImage& depth, ros::Time time) const 00493 { 00494 stereo_msgs::DisparityImagePtr disp_msg = boost::make_shared<stereo_msgs::DisparityImage > (); 00495 disp_msg->header.stamp = time; 00496 disp_msg->header.frame_id = device_->isDepthRegistered () ? rgb_frame_id_ : depth_frame_id_; 00497 disp_msg->image.header = disp_msg->header; 00498 disp_msg->image.encoding = sensor_msgs::image_encodings::TYPE_32FC1; 00499 disp_msg->image.height = depth_height_; 00500 disp_msg->image.width = depth_width_; 00501 disp_msg->image.step = disp_msg->image.width * sizeof (float); 00502 disp_msg->image.data.resize (disp_msg->image.height * disp_msg->image.step); 00503 disp_msg->T = depth.getBaseline (); 00504 disp_msg->f = depth.getFocalLength () * depth_width_ / depth.getWidth (); 00505 00507 disp_msg->min_disparity = 0.0; 00508 disp_msg->max_disparity = disp_msg->T * disp_msg->f / 0.3; 00509 disp_msg->delta_d = 0.125; 00510 00511 depth.fillDisparityImage (depth_width_, depth_height_, reinterpret_cast<float*>(&disp_msg->image.data[0]), disp_msg->image.step); 00512 00513 pub_disparity_.publish (disp_msg); 00514 } 00515 00516 void OpenNINodelet::publishXYZPointCloud (const DepthImage& depth, ros::Time time) const 00517 { 00518 const xn::DepthMetaData& depth_md = depth.getDepthMetaData (); 00519 00520 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_msg (new pcl::PointCloud<pcl::PointXYZ>() ); 00521 cloud_msg->header.stamp = time; 00522 00523 bool do_masking = (use_indices_ and (mask_indices_.size() != 0)); 00524 00525 float centerX, centerY; 00526 unsigned depthStep = 1, depthSkip = 0; 00527 if (not do_masking) 00528 { 00529 cloud_msg->height = depth_height_; 00530 cloud_msg->width = depth_width_; 00531 centerX = (cloud_msg->width >> 1) - 0.5f; 00532 centerY = (cloud_msg->height >> 1) - 0.5f; 00533 depthStep = depth_md.XRes() / cloud_msg->width; 00534 depthSkip = (depth_md.YRes() / cloud_msg->height - 1) * depth_md.XRes(); 00535 } 00536 else 00537 { 00538 cloud_msg->width = mask_indices_.size(); 00539 cloud_msg->height = 1; 00540 centerX = (depth_width_ >> 1) - 0.5f; 00541 centerY = (depth_height_ >> 1) - 0.5f; 00542 } 00543 cloud_msg->is_dense = false; 00544 00545 cloud_msg->points.resize (cloud_msg->height * cloud_msg->width); 00546 00547 float constant = 0.001 / device_->getDepthFocalLength (depth_width_); 00548 00549 if (device_->isDepthRegistered ()) 00550 cloud_msg->header.frame_id = rgb_frame_id_; 00551 else 00552 cloud_msg->header.frame_id = depth_frame_id_; 00553 00554 float bad_point = std::numeric_limits<float>::quiet_NaN (); 00555 00556 int depth_idx = 0; 00557 pcl::PointCloud<pcl::PointXYZ>::iterator pt_iter = cloud_msg->begin (); 00558 if (not do_masking) 00559 { 00560 for (int v = 0; v < (int)cloud_msg->height; ++v, depth_idx += depthSkip) 00561 { 00562 for (int u = 0; u < (int)cloud_msg->width; ++u, depth_idx += depthStep, ++pt_iter) 00563 { 00564 pcl::PointXYZ& pt = *pt_iter; 00565 00566 // Check for invalid measurements 00567 if (depth_md[depth_idx] == 0 || 00568 depth_md[depth_idx] == depth.getNoSampleValue () || 00569 depth_md[depth_idx] == depth.getShadowValue ()) 00570 { 00571 // not valid 00572 pt.x = pt.y = pt.z = bad_point; 00573 continue; 00574 } 00575 00576 // Fill in XYZ 00577 pt.x = (u - centerX) * depth_md[depth_idx] * constant; 00578 pt.y = (v - centerY) * depth_md[depth_idx] * constant; 00579 pt.z = depth_md[depth_idx] * 0.001; 00580 } 00581 } 00582 } 00583 else 00584 { 00585 int u, v; 00586 unsigned int nMask = mask_indices_.size(); 00587 int max_index = (depth_height_ * depth_width_) - 1; 00588 for (unsigned int i = 0; i < nMask; i++, ++pt_iter) 00589 { 00590 pcl::PointXYZ& pt = *pt_iter; 00591 00592 depth_idx = mask_indices_[i]; 00593 if (depth_idx > max_index) 00594 { 00595 NODELET_ERROR("Mask index %d exceeds maximum index of %d", depth_idx, max_index); 00596 continue; 00597 } 00598 v = depth_idx / depth_width_; 00599 u = depth_idx % depth_width_; 00600 00601 // Check for invalid measurements 00602 if (depth_md[depth_idx] == 0 || 00603 depth_md[depth_idx] == depth.getNoSampleValue () || 00604 depth_md[depth_idx] == depth.getShadowValue ()) 00605 { 00606 // not valid 00607 pt.x = pt.y = pt.z = bad_point; 00608 continue; 00609 } 00610 00611 // Fill in XYZ 00612 pt.x = (u - centerX) * depth_md[depth_idx] * constant; 00613 pt.y = (v - centerY) * depth_md[depth_idx] * constant; 00614 pt.z = depth_md[depth_idx] * 0.001; 00615 } 00616 } 00617 00618 pub_point_cloud_.publish (cloud_msg); 00619 } 00620 00621 void OpenNINodelet::publishXYZRGBPointCloud (const sensor_msgs::ImageConstPtr& depth_msg, const sensor_msgs::ImageConstPtr& rgb_msg) const 00622 { 00623 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_msg (new pcl::PointCloud<pcl::PointXYZRGB>() ); 00624 cloud_msg->header.stamp = depth_msg->header.stamp; 00625 cloud_msg->header.frame_id = rgb_frame_id_; 00626 cloud_msg->is_dense = false; 00627 00628 bool do_masking = (use_indices_ and (mask_indices_.size() != 0)); 00629 00630 float centerX, centerY; 00631 float constant; 00632 unsigned color_step, color_skip; 00633 00634 if (not do_masking) 00635 { 00636 cloud_msg->height = depth_msg->height; 00637 cloud_msg->width = depth_msg->width; 00638 centerX = (cloud_msg->width >> 1) - 0.5f; 00639 centerY = (cloud_msg->height >> 1) - 0.5f; 00640 constant = 1.0f / device_->getImageFocalLength(cloud_msg->width); 00641 color_step = 3 * rgb_msg->width / cloud_msg->width; 00642 color_skip = 3 * (rgb_msg->height / cloud_msg->height - 1) * rgb_msg->width; 00643 00644 } 00645 else 00646 { 00647 cloud_msg->width = mask_indices_.size(); 00648 cloud_msg->height = 1; 00649 centerX = (depth_msg->width >> 1) - 0.5f; 00650 centerY = (depth_msg->height >> 1) - 0.5f; 00651 constant = 1.0f / device_->getImageFocalLength(depth_msg->width); 00652 color_step = 3 * rgb_msg->width / depth_msg->width; 00653 color_skip = 3 * (rgb_msg->height / depth_msg->height - 1) * rgb_msg->width; 00654 } 00655 00656 static bool info_sent = false; 00657 if (not info_sent) 00658 { 00659 //NODELET_INFO("color_step = %d, color_skip = %d", color_step, color_skip); 00660 info_sent = true; 00661 } 00662 00663 // do not publish if rgb image is smaller than color image -> seg fault 00664 if (rgb_msg->height < depth_msg->height || rgb_msg->width < depth_msg->width) 00665 { 00666 // we dont want to flood the terminal with warnings 00667 static unsigned warned = 0; 00668 if (warned % 100 == 0) 00669 NODELET_WARN("rgb image smaller than depth image... skipping point cloud for this frame rgb:%dx%d vs. depth:%3dx%d" 00670 , rgb_msg->width, rgb_msg->height, depth_msg->width, depth_msg->height ); 00671 ++warned; 00672 return; 00673 } 00674 cloud_msg->points.resize (cloud_msg->height * cloud_msg->width); 00675 00676 const float* depth_buffer = reinterpret_cast<const float*>(&depth_msg->data[0]); 00677 const uint8_t* rgb_buffer = &rgb_msg->data[0]; 00678 00679 // depth_msg already has the desired dimensions, but rgb_msg may be higher res. 00680 int color_idx = 0, depth_idx = 0; 00681 pcl::PointCloud<pcl::PointXYZRGB>::iterator pt_iter = cloud_msg->begin (); 00682 if (not do_masking) 00683 { 00684 for (int v = 0; v < (int)cloud_msg->height; ++v, color_idx += color_skip) 00685 { 00686 for (int u = 0; u < (int)cloud_msg->width; ++u, color_idx += color_step, ++depth_idx, ++pt_iter) 00687 { 00688 pcl::PointXYZRGB& pt = *pt_iter; 00689 float Z = depth_buffer[depth_idx]; 00690 00691 // Check for invalid measurements 00692 if (std::isnan (Z)) 00693 { 00694 pt.x = pt.y = pt.z = Z; 00695 } 00696 else 00697 { 00698 // Fill in XYZ 00699 pt.x = (u - centerX) * Z * constant; 00700 pt.y = (v - centerY) * Z * constant; 00701 pt.z = Z; 00702 } 00703 00704 // Fill in color 00705 RGBValue color; 00706 color.Red = rgb_buffer[color_idx]; 00707 color.Green = rgb_buffer[color_idx + 1]; 00708 color.Blue = rgb_buffer[color_idx + 2]; 00709 color.Alpha = 0; 00710 pt.rgb = color.float_value; 00711 } 00712 } 00713 } 00714 else 00715 { 00716 int u, v; 00717 unsigned int nMask = mask_indices_.size(); 00718 int max_index = (depth_msg->height * depth_msg->width) - 1; 00719 for (unsigned int i = 0; i < nMask; i++, ++pt_iter) 00720 { 00721 pcl::PointXYZRGB& pt = *pt_iter; 00722 depth_idx = mask_indices_[i]; 00723 if (depth_idx > max_index) 00724 { 00725 NODELET_ERROR("Mask index %d exceeds maximum index of %d", depth_idx, max_index); 00726 continue; 00727 } 00728 float Z = depth_buffer[depth_idx]; 00729 00730 v = depth_idx / depth_msg->width; 00731 u = depth_idx % depth_msg->width; 00732 // Check for invalid measurements 00733 00734 if (std::isnan (Z)) 00735 { 00736 pt.x = pt.y = pt.z = Z; 00737 } 00738 else 00739 { 00740 // Fill in XYZ 00741 pt.x = (u - centerX) * Z * constant; 00742 pt.y = (v - centerY) * Z * constant; 00743 pt.z = Z; 00744 } 00745 00746 // Fill in color 00747 RGBValue color; 00748 color_idx = (v*depth_msg->width + u)*color_step; 00749 color.Red = rgb_buffer[color_idx]; 00750 color.Green = rgb_buffer[color_idx + 1]; 00751 color.Blue = rgb_buffer[color_idx + 2]; 00752 color.Alpha = 0; 00753 pt.rgb = color.float_value; 00754 } 00755 } 00756 00757 pub_point_cloud_rgb_.publish (cloud_msg); 00758 } 00759 00760 sensor_msgs::CameraInfoPtr OpenNINodelet::fillCameraInfo (ros::Time time, bool is_rgb) 00761 { 00762 sensor_msgs::CameraInfoPtr info_msg = boost::make_shared<sensor_msgs::CameraInfo > (); 00763 info_msg->header.stamp = time; 00764 info_msg->header.frame_id = is_rgb ? rgb_frame_id_ : depth_frame_id_; 00765 info_msg->width = is_rgb ? image_width_ : depth_width_; 00766 info_msg->height = is_rgb ? image_height_ : depth_height_; 00767 00768 #if ROS_VERSION_MINIMUM(1, 3, 0) 00769 info_msg->D = std::vector<double>(5, 0.0); 00770 info_msg->distortion_model = sensor_msgs::distortion_models::PLUMB_BOB; 00771 #else 00772 info_msg->D.assign (0.0); 00773 #endif 00774 info_msg->K.assign (0.0); 00775 info_msg->R.assign (0.0); 00776 info_msg->P.assign (0.0); 00777 // Simple camera matrix: square pixels, principal point at center 00778 double f = is_rgb ? device_->getImageFocalLength (image_width_) : device_->getDepthFocalLength (depth_width_); 00779 info_msg->K[0] = info_msg->K[4] = f; 00780 info_msg->K[2] = (info_msg->width / 2) - 0.5; 00781 info_msg->K[5] = (info_msg->width * 3./8.) - 0.5; //aspect ratio for the camera center on kinect and presumably other devices is 4/3 00782 info_msg->K[8] = 1.0; 00783 // no rotation: identity 00784 info_msg->R[0] = info_msg->R[4] = info_msg->R[8] = 1.0; 00785 // no rotation, no translation => P=K(I|0)=(K|0) 00786 info_msg->P[0] = info_msg->P[5] = info_msg->K[0]; 00787 info_msg->P[2] = info_msg->K[2]; 00788 info_msg->P[6] = info_msg->K[5]; 00789 info_msg->P[10] = 1.0; 00790 00791 return info_msg; 00792 } 00793 00794 void OpenNINodelet::configCallback (Config &config, uint32_t level) 00795 { 00796 XnMapOutputMode old_image_mode = device_->getImageOutputMode (); 00797 XnMapOutputMode old_depth_mode = device_->getDepthOutputMode (); 00798 00799 // does the device support the new image mode? 00800 XnMapOutputMode image_mode, compatible_image_mode; 00801 image_mode = mapConfigMode2XnMode (config.image_mode); 00802 00803 if (!device_->findCompatibleImageMode (image_mode, compatible_image_mode)) 00804 { 00805 NODELET_WARN ("Could not find any compatible image output mode for %d x %d @ %d.", 00806 image_mode.nXRes, image_mode.nYRes, image_mode.nFPS); 00807 00808 // dont change anything! 00809 config = config_; 00810 return; 00811 } 00812 00813 XnMapOutputMode depth_mode, compatible_depth_mode; 00814 depth_mode = mapConfigMode2XnMode (config.depth_mode); 00815 if (!device_->findCompatibleDepthMode (depth_mode, compatible_depth_mode)) 00816 { 00817 NODELET_WARN ("Could not find any compatible depth output mode for %d x %d @ %d.", 00818 depth_mode.nXRes, depth_mode.nYRes, depth_mode.nFPS); 00819 00820 // dont change anything! 00821 config = config_; 00822 return; 00823 } 00824 00825 DeviceKinect* kinect = dynamic_cast<DeviceKinect*> (device_.get ()); 00826 if (kinect) 00827 { 00828 switch (config.debayering) 00829 { 00830 case OpenNI_Bilinear: 00831 kinect->setDebayeringMethod (ImageBayerGRBG::Bilinear); 00832 break; 00833 case OpenNI_EdgeAware: 00834 kinect->setDebayeringMethod (ImageBayerGRBG::EdgeAware); 00835 break; 00836 case OpenNI_EdgeAwareWeighted: 00837 kinect->setDebayeringMethod (ImageBayerGRBG::EdgeAwareWeighted); 00838 break; 00839 default: 00840 NODELET_ERROR ("unknwon debayering method"); 00841 config.debayering = config_.debayering; 00842 break; 00843 } 00844 } 00845 else if (config.debayering != config_.debayering) // this was selected explicitely 00846 { 00847 NODELET_WARN ("%s does not output bayer images. Selection has no affect.", device_->getProductName () ); 00848 } 00849 00850 if (pub_point_cloud_rgb_.getNumSubscribers () > 0) 00851 { 00852 if ( (depth_mode.nXRes > image_mode.nXRes) || (depth_mode.nYRes > image_mode.nYRes) || 00853 (image_mode.nXRes % depth_mode.nXRes != 0) ) 00854 { 00855 // we dont care about YRes, since SXGA works fine for kinect with all depth resolutions 00856 NODELET_WARN ("depth mode not compatible to image mode, since PointCloudXYZRGB has subscribers."); 00857 config = config_; 00858 return; 00859 } 00860 if (!config.depth_registration && config_.depth_registration) 00861 { 00862 NODELET_WARN ("can not turn of registration, since PointCloudXYZRGB has subscribers."); 00863 config = config_; 00864 return; 00865 } 00866 } 00867 00868 // here everything is fine. Now make the changes 00869 if (compatible_image_mode != old_image_mode || compatible_depth_mode != old_depth_mode) 00870 { // streams need to be reset! 00871 stopSynchronization (); 00872 00873 if (compatible_image_mode != old_image_mode) 00874 { 00875 // image_mutex_.lock (); 00876 device_->setImageOutputMode (compatible_image_mode); 00877 image_width_ = image_mode.nXRes; 00878 image_height_ = image_mode.nYRes; 00879 //image_mutex_.unlock (); 00880 } 00881 00882 if (compatible_depth_mode != old_depth_mode) 00883 { 00884 //depth_mutex_.lock (); 00885 device_->setDepthOutputMode (compatible_depth_mode); 00886 depth_width_ = depth_mode.nXRes; 00887 depth_height_ = depth_mode.nYRes; 00888 //depth_mutex_.unlock (); 00889 } 00890 startSynchronization (); 00891 } 00892 else 00893 { 00894 if (config_.image_mode != config.image_mode) 00895 { 00896 image_width_ = image_mode.nXRes; 00897 image_height_ = image_mode.nYRes; 00898 } 00899 00900 if (config_.depth_mode != config.depth_mode) 00901 { 00902 depth_width_ = depth_mode.nXRes; 00903 depth_height_ = depth_mode.nYRes; 00904 } 00905 } 00906 00907 if (device_->isDepthRegistered () != config.depth_registration) 00908 { 00909 device_->setDepthRegistration (config.depth_registration); 00910 } 00911 00912 // now we can copy 00913 config_ = config; 00914 } 00915 00916 bool OpenNINodelet::isImageModeSupported (int image_mode) const 00917 { 00918 XnMapOutputMode image_md = mapConfigMode2XnMode (image_mode); 00919 XnMapOutputMode compatible_mode; 00920 if (device_->findCompatibleImageMode (image_md, compatible_mode)) 00921 return true; 00922 return false; 00923 } 00924 00925 bool OpenNINodelet::isDepthModeSupported (int depth_mode) const 00926 { 00927 XnMapOutputMode depth_md = mapConfigMode2XnMode (depth_mode); 00928 XnMapOutputMode compatible_mode; 00929 if (device_->findCompatibleDepthMode (depth_md, compatible_mode)) 00930 return true; 00931 return false; 00932 } 00933 00934 void OpenNINodelet::startSynchronization () 00935 { 00936 if (device_->isSynchronizationSupported () && !device_->isSynchronized () && 00937 device_->getImageOutputMode ().nFPS == device_->getDepthOutputMode ().nFPS && 00938 device_->isImageStreamRunning () && device_->isDepthStreamRunning () ) 00939 device_->setSynchronization (true); 00940 } 00941 00942 void OpenNINodelet::stopSynchronization () 00943 { 00944 if (device_->isSynchronizationSupported () && device_->isSynchronized ()) 00945 device_->setSynchronization (false); 00946 } 00947 00948 void OpenNINodelet::updateModeMaps () 00949 { 00950 XnMapOutputMode output_mode; 00951 00952 output_mode.nXRes = XN_SXGA_X_RES; 00953 output_mode.nYRes = XN_SXGA_Y_RES; 00954 output_mode.nFPS = 15; 00955 xn2config_map_[output_mode] = OpenNI_SXGA_15Hz; 00956 config2xn_map_[OpenNI_SXGA_15Hz] = output_mode; 00957 00958 output_mode.nXRes = XN_VGA_X_RES; 00959 output_mode.nYRes = XN_VGA_Y_RES; 00960 output_mode.nFPS = 25; 00961 xn2config_map_[output_mode] = OpenNI_VGA_25Hz; 00962 config2xn_map_[OpenNI_VGA_25Hz] = output_mode; 00963 output_mode.nFPS = 30; 00964 xn2config_map_[output_mode] = OpenNI_VGA_30Hz; 00965 config2xn_map_[OpenNI_VGA_30Hz] = output_mode; 00966 00967 output_mode.nXRes = XN_QVGA_X_RES; 00968 output_mode.nYRes = XN_QVGA_Y_RES; 00969 output_mode.nFPS = 25; 00970 xn2config_map_[output_mode] = OpenNI_QVGA_25Hz; 00971 config2xn_map_[OpenNI_QVGA_25Hz] = output_mode; 00972 output_mode.nFPS = 30; 00973 xn2config_map_[output_mode] = OpenNI_QVGA_30Hz; 00974 config2xn_map_[OpenNI_QVGA_30Hz] = output_mode; 00975 output_mode.nFPS = 60; 00976 xn2config_map_[output_mode] = OpenNI_QVGA_60Hz; 00977 config2xn_map_[OpenNI_QVGA_60Hz] = output_mode; 00978 00979 output_mode.nXRes = XN_QQVGA_X_RES; 00980 output_mode.nYRes = XN_QQVGA_Y_RES; 00981 output_mode.nFPS = 25; 00982 xn2config_map_[output_mode] = OpenNI_QQVGA_25Hz; 00983 config2xn_map_[OpenNI_QQVGA_25Hz] = output_mode; 00984 output_mode.nFPS = 30; 00985 xn2config_map_[output_mode] = OpenNI_QQVGA_30Hz; 00986 config2xn_map_[OpenNI_QQVGA_30Hz] = output_mode; 00987 output_mode.nFPS = 60; 00988 xn2config_map_[output_mode] = OpenNI_QQVGA_60Hz; 00989 config2xn_map_[OpenNI_QQVGA_60Hz] = output_mode; 00990 } 00991 00992 int OpenNINodelet::mapXnMode2ConfigMode (const XnMapOutputMode& output_mode) const 00993 { 00994 std::map<XnMapOutputMode, int, modeComp>::const_iterator it = xn2config_map_.find (output_mode); 00995 00996 if (it == xn2config_map_.end ()) 00997 { 00998 NODELET_ERROR ("mode %dx%d@%d could not be found", output_mode.nXRes, output_mode.nYRes, output_mode.nFPS); 00999 exit (-1); 01000 } 01001 else 01002 return it->second; 01003 } 01004 01005 XnMapOutputMode OpenNINodelet::mapConfigMode2XnMode (int mode) const 01006 { 01007 std::map<int, XnMapOutputMode>::const_iterator it = config2xn_map_.find (mode); 01008 if (it == config2xn_map_.end ()) 01009 { 01010 NODELET_ERROR ("mode %d could not be found", mode); 01011 exit (-1); 01012 } 01013 else 01014 return it->second; 01015 } 01016 01017 void OpenNINodelet::maskIndicesCb(const pcl::PointIndicesConstPtr& indices) 01018 { 01019 mask_indices_.resize(indices->indices.size()); 01020 // NODELET_INFO("New mask with %d indices", int(mask_indices_.size())); 01021 memcpy(mask_indices_.data(), indices->indices.data(), indices->indices.size() * sizeof(int32_t)); 01022 } 01023 } 01024 01025