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 #include <pluginlib/class_list_macros.h>
00040 #include "openni_camera/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
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 ros::NodeHandle comm_nh(getNodeHandle ().resolveName ("camera"));
00091 ros::NodeHandle param_nh = getPrivateNodeHandle ();
00092
00093 updateModeMaps ();
00094 device_ = boost::shared_ptr<openni_wrapper::OpenNIDevice > ((openni_wrapper::OpenNIDevice*)NULL);
00095 setupDevice (param_nh);
00096
00097 param_nh.param ("rgb_frame_id", rgb_frame_id_, string (""));
00098 if (rgb_frame_id_.empty ())
00099 {
00100 rgb_frame_id_ = "/openni_rgb_optical_frame";
00101 NODELET_INFO ("'rgb_frame_id' not set. using default: '%s'", rgb_frame_id_.c_str());
00102 }
00103 else
00104 NODELET_INFO ("rgb_frame_id = '%s' ", rgb_frame_id_.c_str());
00105
00106 param_nh.param ("depth_frame_id", depth_frame_id_, string (""));
00107 if (depth_frame_id_.empty ())
00108 {
00109 depth_frame_id_ = "/openni_depth_optical_frame";
00110 NODELET_INFO ("'depth_frame_id' not set. using default: '%s'", depth_frame_id_.c_str());
00111 }
00112 else
00113 NODELET_INFO ("depth_frame_id = '%s' ", depth_frame_id_.c_str());
00114
00115 param_nh.param ("use_indices", use_indices_, false);
00116
00117 image_transport::ImageTransport imageTransport (comm_nh);
00118 image_transport::SubscriberStatusCallback subscriberChanged = boost::bind(&OpenNINodelet::subscriberChangedEvent, this);
00119 pub_rgb_image_ = imageTransport.advertise ("rgb/image_color", 5, subscriberChanged, subscriberChanged );
00120 pub_image_raw_ = imageTransport.advertise ("rgb/image_raw", 5, subscriberChanged, subscriberChanged );
00121 pub_gray_image_ = imageTransport.advertise ("rgb/image_mono" , 5, subscriberChanged, subscriberChanged );
00122 pub_depth_image_ = imageTransport.advertise ("depth/image" , 5, subscriberChanged, subscriberChanged );
00123 pub_depth_raw_ = imageTransport.advertise ("depth/image_raw", 5, subscriberChanged, subscriberChanged );
00124
00125 ros::SubscriberStatusCallback subscriberChanged2 = boost::bind(&OpenNINodelet::subscriberChangedEvent, this);
00126 pub_disparity_ = comm_nh.advertise<stereo_msgs::DisparityImage > ("depth/disparity", 5, subscriberChanged2, subscriberChanged2);
00127 pub_rgb_info_ = comm_nh.advertise<sensor_msgs::CameraInfo > ("rgb/camera_info", 5, subscriberChanged2, subscriberChanged2);
00128 pub_depth_info_ = comm_nh.advertise<sensor_msgs::CameraInfo > ("depth/camera_info", 5, subscriberChanged2, subscriberChanged2);
00129 pub_point_cloud_ = comm_nh.advertise<pcl::PointCloud<pcl::PointXYZ> > ("depth/points", 5, subscriberChanged2, subscriberChanged2);
00130 pub_point_cloud_rgb_ = comm_nh.advertise<pcl::PointCloud<pcl::PointXYZRGB> > ("rgb/points", 5, subscriberChanged2, subscriberChanged2);
00131
00132 if (use_indices_)
00133 sub_mask_indices_ = comm_nh.subscribe("depth/indices", 5, &OpenNINodelet::maskIndicesCb, this);
00134
00135 SyncPolicy sync_policy (4);
00136 depth_rgb_sync_.reset (new Synchronizer (sync_policy));
00137 depth_rgb_sync_->registerCallback (boost::bind (&OpenNINodelet::publishXYZRGBPointCloud, this, _1, _2));
00138
00139
00140 reconfigure_server_.reset (new ReconfigureServer (reconfigure_mutex_, param_nh));
00141 reconfigure_mutex_.lock ();
00142 reconfigure_server_->updateConfig (config_);
00143 reconfigure_server_->setCallback (boost::bind (&OpenNINodelet::configCallback, this, _1, _2));
00144 reconfigure_mutex_.unlock ();
00145 }
00146
00147 void OpenNINodelet::setupDevice (ros::NodeHandle& param_nh)
00148 {
00149
00150 OpenNIDriver& driver = OpenNIDriver::getInstance ();
00151
00152 do {
00153
00154 if (!ros::ok())
00155 exit(-1);
00156
00157 driver.updateDeviceList ();
00158
00159 if (driver.getNumberDevices () == 0)
00160 {
00161 NODELET_INFO ("[%s] No devices connected.... waiting for devices to be connected", getName ().c_str ());
00162 sleep(1);
00163 continue;
00164 }
00165
00166 NODELET_INFO ("[%s] Number devices connected: %d", getName ().c_str (), driver.getNumberDevices ());
00167 for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00168 {
00169 NODELET_INFO ("[%s] %u. device on bus %03u:%02u is a %s (%03x) from %s (%03x) with serial id \'%s\'"
00170 , getName ().c_str (), deviceIdx + 1, driver.getBus (deviceIdx), driver.getAddress (deviceIdx)
00171 , driver.getProductName (deviceIdx), driver.getProductID (deviceIdx), driver.getVendorName (deviceIdx)
00172 , driver.getVendorID (deviceIdx), driver.getSerialNumber (deviceIdx));
00173 }
00174
00175 string device_id;
00176 param_nh.param ("device_id", device_id, std::string ());
00177
00178 try {
00179 if (device_id.empty ())
00180 {
00181 NODELET_WARN ("[%s] device_id is not set! Using first device.", getName ().c_str ());
00182 device_ = driver.getDeviceByIndex (0);
00183 }
00184 else if (device_id.find ('@') != string::npos)
00185 {
00186 size_t pos = device_id.find ('@');
00187 unsigned bus = atoi (device_id.substr (0, pos).c_str ());
00188 unsigned address = atoi (device_id.substr (pos + 1, device_id.length () - pos - 1).c_str ());
00189 NODELET_INFO ("[%s] searching for device with bus@address = %d@%d", getName ().c_str (), bus, address);
00190 device_ = driver.getDeviceByAddress (bus, address);
00191 }
00192 else if (device_id[0] == '#')
00193 {
00194 unsigned index = atoi (device_id.c_str () + 1);
00195 NODELET_INFO ("[%s] searching for device with index = %d", getName ().c_str (), index);
00196 device_ = driver.getDeviceByIndex (index - 1);
00197 }
00198 else
00199 {
00200 NODELET_INFO ("[%s] searching for device with serial number = %s", getName ().c_str (), device_id.c_str ());
00201 device_ = driver.getDeviceBySerialNumber (device_id);
00202 }
00203 }
00204 catch (const OpenNIException& exception)
00205 {
00206 if (!device_)
00207 {
00208 NODELET_INFO ("[%s] No matching device found.... waiting for devices. Reason: %s", getName ().c_str (), exception.what ());
00209 sleep (1);
00210 continue;
00211 }
00212 else
00213 {
00214 NODELET_ERROR ("[%s] could not retrieve device. Reason %s", getName ().c_str (), exception.what ());
00215 exit (-1);
00216 }
00217 }
00218 } while (!device_);
00219
00220 NODELET_INFO ("[%s] Opened '%s' on bus %d:%d with serial number '%s'", getName ().c_str (),
00221 device_->getProductName (), device_->getBus (), device_->getAddress (), device_->getSerialNumber ());
00222
00223 device_->registerImageCallback (&OpenNINodelet::imageCallback, *this);
00224 device_->registerDepthCallback (&OpenNINodelet::depthCallback, *this);
00225
00226 bool registration = false;
00227 param_nh.param ("depth_registration", registration, false );
00228 config_.depth_registration = registration;
00229
00230 int debayering_method = 0;
00231 param_nh.param ("debayering", debayering_method, 0 );
00232 if(debayering_method > 2 || debayering_method < 0)
00233 {
00234 NODELET_ERROR ("Unknown debayering method %d. Only Folowing values are available: Bilinear (0), EdgeAware (1), EdgeAwareWeighted (2). Falling back to Bilinear (0).", debayering_method);
00235 debayering_method = 0;
00236 }
00237 config_.debayering = debayering_method;
00238
00239 param_nh.param ("depth_time_offset", config_.depth_time_offset, 0.0 );
00240 if(config_.depth_time_offset > 1.0 || config_.depth_time_offset < -1.0)
00241 {
00242 NODELET_ERROR ("depth time offset is % 2.5f seconds. Thats unlikely... setting back to 0.0 seconds", config_.depth_time_offset);
00243 config_.depth_time_offset = 0.0;
00244 }
00245
00246 param_nh.param ("image_time_offset", config_.image_time_offset, 0.0 );
00247 if(config_.image_time_offset > 1.0 || config_.image_time_offset < -1.0)
00248 {
00249 NODELET_ERROR ("image time offset is % 2.5f seconds. Thats unlikely... setting back to 0.0 seconds", config_.image_time_offset);
00250 config_.image_time_offset = 0.0;
00251 }
00252
00253 int image_mode = mapXnMode2ConfigMode (device_->getDefaultImageMode ());
00254 param_nh.param ("image_mode", image_mode, image_mode );
00255 if (image_mode < config_.__getMin__().image_mode || image_mode > config_.__getMax__ ().image_mode ||
00256 !isImageModeSupported (image_mode))
00257 {
00258 XnMapOutputMode image_md = device_->getDefaultImageMode ();
00259 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);
00260 image_mode = mapXnMode2ConfigMode (image_md);
00261 }
00262 config_.image_mode = image_mode;
00263
00264 int depth_mode = mapXnMode2ConfigMode (device_->getDefaultDepthMode ());
00265 param_nh.param ("depth_mode", depth_mode, depth_mode );
00266 if (depth_mode < OpenNI_VGA_30Hz || depth_mode > config_.__getMax__ ().image_mode ||
00267 !isDepthModeSupported (depth_mode))
00268 {
00269 XnMapOutputMode depth_md = device_->getDefaultImageMode ();
00270 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);
00271 depth_mode = mapXnMode2ConfigMode (depth_md);
00272 }
00273 config_.depth_mode = depth_mode;
00274
00275 XnMapOutputMode image_md = mapConfigMode2XnMode ( config_.image_mode);
00276 image_width_ = image_md.nXRes;
00277 image_height_ = image_md.nYRes;
00278
00279 XnMapOutputMode depth_md = mapConfigMode2XnMode ( config_.depth_mode);
00280 depth_width_ = depth_md.nXRes;
00281 depth_height_ = depth_md.nYRes;
00282 }
00283
00284 void OpenNINodelet::imageCallback (boost::shared_ptr<openni_wrapper::Image> image, void* cookie)
00285 {
00286 ros::Time time = ros::Time::now () + ros::Duration(config_.image_time_offset);
00287
00288
00289
00290
00291
00292 if (pub_rgb_info_.getNumSubscribers () > 0)
00293 pub_rgb_info_.publish (fillCameraInfo (time, true));
00294
00295 if (pub_image_raw_.getNumSubscribers () > 0)
00296 publishRgbImageRaw (*image, time);
00297
00298 if (pub_rgb_image_.getNumSubscribers () > 0 || pub_point_cloud_rgb_.getNumSubscribers () > 0 )
00299 publishRgbImage (*image, time);
00300
00301 if (pub_gray_image_.getNumSubscribers () > 0)
00302 publishGrayImage (*image, time);
00303
00304
00305 }
00306
00307 void OpenNINodelet::depthCallback (boost::shared_ptr<openni_wrapper::DepthImage> depth_image, void* cookie)
00308 {
00309 ros::Time time = ros::Time::now () + ros::Duration(config_.depth_time_offset);
00310
00311
00312
00313
00314 if (pub_depth_info_.getNumSubscribers () > 0)
00315 pub_depth_info_.publish (fillCameraInfo (time, false));
00316
00317
00318 if (pub_depth_raw_.getNumSubscribers () > 0)
00319 publishDepthImageRaw (*depth_image, time);
00320
00321
00322 if (pub_depth_image_.getNumSubscribers () > 0 || (pub_point_cloud_rgb_.getNumSubscribers () > 0 ))
00323 publishDepthImage (*depth_image, time);
00324
00325
00326 if (pub_disparity_.getNumSubscribers () > 0)
00327 publishDisparity (*depth_image, time);
00328
00329
00330 if (pub_point_cloud_.getNumSubscribers () > 0 )
00331 publishXYZPointCloud (*depth_image, time);
00332
00333
00334 }
00335
00336 void OpenNINodelet::subscriberChangedEvent ()
00337 {
00338
00339 if (isImageStreamRequired () && !device_->isImageStreamRunning ())
00340 {
00341 device_->startImageStream ();
00342 startSynchronization ();
00343 }
00344 else if (!isImageStreamRequired () && device_->isImageStreamRunning ())
00345 {
00346 stopSynchronization ();
00347 device_->stopImageStream ();
00348 if (pub_rgb_info_.getNumSubscribers() > 0)
00349 NODELET_WARN("Camera Info for rgb stream has subscribers, but stream has stopped.");
00350 }
00351
00352 if (isDepthStreamRequired () && !device_->isDepthStreamRunning ())
00353 {
00354 device_->startDepthStream ();
00355 startSynchronization ();
00356 }
00357 else if ( !isDepthStreamRequired () && device_->isDepthStreamRunning ())
00358 {
00359 stopSynchronization ();
00360 device_->stopDepthStream ();
00361 if (pub_depth_info_.getNumSubscribers() > 0)
00362 NODELET_WARN("Camera Info for depth stream has subscribers, but stream has stopped.");
00363 }
00364
00365
00366
00367 if (pub_point_cloud_rgb_.getNumSubscribers() > 0)
00368 {
00369 Config config = config_;
00370
00371 reconfigure_mutex_.lock ();
00372 if (!device_->isDepthRegistered ())
00373 {
00374 NODELET_WARN ("turning on depth registration, since PointCloudXYZRGB has subscribers.");
00375 device_->setDepthRegistration (true);
00376 config.depth_registration = true;
00377 }
00378
00379 XnMapOutputMode depth_mode = mapConfigMode2XnMode (config_.depth_mode);
00380 XnMapOutputMode image_mode = mapConfigMode2XnMode (config_.image_mode);
00381 if (depth_mode.nXRes > image_mode.nXRes || depth_mode.nYRes > image_mode.nYRes)
00382 {
00383 NODELET_WARN ("PointCloudXYZRGB need at least the same image size for mapping rgb values to the points");
00384 config.image_mode = config_.depth_mode;
00385 }
00386
00387 reconfigure_server_->updateConfig (config);
00388 configCallback (config, 0);
00389 reconfigure_mutex_.unlock ();
00390 }
00391 }
00392
00393 void OpenNINodelet::publishRgbImage (const Image& image, ros::Time time) const
00394 {
00395 sensor_msgs::ImagePtr rgb_msg = boost::make_shared<sensor_msgs::Image > ();
00396 rgb_msg->header.stamp = time;
00397 rgb_msg->header.frame_id = rgb_frame_id_;
00398 rgb_msg->encoding = sensor_msgs::image_encodings::RGB8;
00399 rgb_msg->height = image_height_;
00400 rgb_msg->width = image_width_;
00401 rgb_msg->step = image_width_ * 3;
00402 rgb_msg->data.resize (rgb_msg->height * rgb_msg->step);
00403 image.fillRGB (rgb_msg->width, rgb_msg->height, &rgb_msg->data[0], rgb_msg->step);
00404
00405 if (pub_rgb_image_.getNumSubscribers () > 0)
00406 pub_rgb_image_.publish (rgb_msg);
00407
00408 if (pub_point_cloud_rgb_.getNumSubscribers () > 0)
00409 depth_rgb_sync_->add < 1 > (rgb_msg);
00410 }
00411
00412 void OpenNINodelet::publishRgbImageRaw (const Image& image, ros::Time time) const
00413 {
00414 sensor_msgs::ImagePtr rgb_msg = boost::make_shared<sensor_msgs::Image > ();
00415 rgb_msg->header.stamp = time;
00416 rgb_msg->header.frame_id = rgb_frame_id_;
00417 if (image.getEncoding () == openni_wrapper::Image::BAYER_GRBG)
00418 {
00419 rgb_msg->encoding = sensor_msgs::image_encodings::BAYER_GRBG8;
00420 rgb_msg->step = image_width_ * 1;
00421 }
00422 else if (image.getEncoding () == openni_wrapper::Image::YUV422)
00423 {
00424 rgb_msg->encoding = sensor_msgs::image_encodings::RGB8;
00425
00426 rgb_msg->step = image_width_ * 3;
00427 }
00428 rgb_msg->height = image_height_;
00429 rgb_msg->width = image_width_;
00430 rgb_msg->data.resize (rgb_msg->height * rgb_msg->step);
00431 image.fillRaw (&rgb_msg->data[0]);
00432
00433 if (pub_image_raw_.getNumSubscribers () > 0)
00434 pub_image_raw_.publish (rgb_msg);
00435 }
00436
00437 void OpenNINodelet::publishGrayImage (const Image& image, ros::Time time) const
00438 {
00439 sensor_msgs::ImagePtr gray_msg = boost::make_shared<sensor_msgs::Image > ();
00440 gray_msg->header.stamp = time;
00441 gray_msg->header.frame_id = rgb_frame_id_;
00442 gray_msg->encoding = sensor_msgs::image_encodings::MONO8;
00443 gray_msg->height = image_height_;
00444 gray_msg->width = image_width_;
00445 gray_msg->step = image_width_;
00446 gray_msg->data.resize (gray_msg->height * gray_msg->step);
00447 image.fillGrayscale (gray_msg->width, gray_msg->height, &gray_msg->data[0], gray_msg->step);
00448
00449 pub_gray_image_.publish (gray_msg);
00450 }
00451
00452 void OpenNINodelet::publishDepthImage (const DepthImage& depth, ros::Time time) const
00453 {
00454 sensor_msgs::ImagePtr depth_msg = boost::make_shared<sensor_msgs::Image > ();
00455 depth_msg->header.stamp = time;
00456 depth_msg->header.frame_id = device_->isDepthRegistered () ? rgb_frame_id_ : depth_frame_id_;
00457 depth_msg->encoding = sensor_msgs::image_encodings::TYPE_32FC1;
00458 depth_msg->height = depth_height_;
00459 depth_msg->width = depth_width_;
00460 depth_msg->step = depth_msg->width * sizeof (float);
00461 depth_msg->data.resize (depth_msg->height * depth_msg->step);
00462
00463 depth.fillDepthImage (depth_width_, depth_height_, reinterpret_cast<float*>(&depth_msg->data[0]), depth_msg->step);
00464
00465 if (pub_depth_image_.getNumSubscribers () > 0)
00466 pub_depth_image_.publish (depth_msg);
00467
00468 if (pub_point_cloud_rgb_.getNumSubscribers () > 0)
00469 depth_rgb_sync_->add < 0 > (depth_msg);
00470 }
00471
00472 void OpenNINodelet::publishDepthImageRaw (const DepthImage& depth, ros::Time time) const
00473 {
00474 sensor_msgs::ImagePtr depth_msg = boost::make_shared<sensor_msgs::Image > ();
00475 depth_msg->header.stamp = time;
00476 depth_msg->header.frame_id = device_->isDepthRegistered () ? rgb_frame_id_ : depth_frame_id_;
00477 depth_msg->encoding = sensor_msgs::image_encodings::TYPE_16SC1;
00478 depth_msg->height = depth_height_;
00479 depth_msg->width = depth_width_;
00480 depth_msg->step = depth_msg->width * sizeof (short);
00481 depth_msg->data.resize (depth_msg->height * depth_msg->step);
00482
00483 depth.fillDepthImageRaw (depth_width_, depth_height_, reinterpret_cast<short*>(&depth_msg->data[0]), depth_msg->step);
00484
00485 if (pub_depth_raw_.getNumSubscribers () > 0)
00486 pub_depth_raw_.publish (depth_msg);
00487 }
00488
00489 void OpenNINodelet::publishDisparity (const DepthImage& depth, ros::Time time) const
00490 {
00491 stereo_msgs::DisparityImagePtr disp_msg = boost::make_shared<stereo_msgs::DisparityImage > ();
00492 disp_msg->header.stamp = time;
00493 disp_msg->header.frame_id = device_->isDepthRegistered () ? rgb_frame_id_ : depth_frame_id_;
00494 disp_msg->image.header = disp_msg->header;
00495 disp_msg->image.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
00496 disp_msg->image.height = depth_height_;
00497 disp_msg->image.width = depth_width_;
00498 disp_msg->image.step = disp_msg->image.width * sizeof (float);
00499 disp_msg->image.data.resize (disp_msg->image.height * disp_msg->image.step);
00500 disp_msg->T = depth.getBaseline ();
00501 disp_msg->f = depth.getFocalLength () * depth_width_ / depth.getWidth ();
00502
00504 disp_msg->min_disparity = 0.0;
00505 disp_msg->max_disparity = disp_msg->T * disp_msg->f / 0.3;
00506 disp_msg->delta_d = 0.125;
00507
00508 depth.fillDisparityImage (depth_width_, depth_height_, reinterpret_cast<float*>(&disp_msg->image.data[0]), disp_msg->image.step);
00509
00510 pub_disparity_.publish (disp_msg);
00511 }
00512
00513 void OpenNINodelet::publishXYZPointCloud (const DepthImage& depth, ros::Time time) const
00514 {
00515 const xn::DepthMetaData& depth_md = depth.getDepthMetaData ();
00516
00517 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_msg (new pcl::PointCloud<pcl::PointXYZ>() );
00518 cloud_msg->header.stamp = time;
00519
00520 bool do_masking = (use_indices_ and (mask_indices_.size() != 0));
00521
00522 float centerX, centerY;
00523 unsigned depthStep = 1, depthSkip = 0;
00524 if (not do_masking)
00525 {
00526 cloud_msg->height = depth_height_;
00527 cloud_msg->width = depth_width_;
00528 centerX = (cloud_msg->width >> 1) - 0.5f;
00529 centerY = (cloud_msg->height >> 1) - 0.5f;
00530 depthStep = depth_md.XRes() / cloud_msg->width;
00531 depthSkip = (depth_md.YRes() / cloud_msg->height - 1) * depth_md.XRes();
00532 }
00533 else
00534 {
00535 cloud_msg->width = mask_indices_.size();
00536 cloud_msg->height = 1;
00537 centerX = (depth_width_ >> 1) - 0.5f;
00538 centerY = (depth_height_ >> 1) - 0.5f;
00539 }
00540 cloud_msg->is_dense = false;
00541
00542 cloud_msg->points.resize (cloud_msg->height * cloud_msg->width);
00543
00544 float constant = 0.001 / device_->getDepthFocalLength (depth_width_);
00545
00546 if (device_->isDepthRegistered ())
00547 cloud_msg->header.frame_id = rgb_frame_id_;
00548 else
00549 cloud_msg->header.frame_id = depth_frame_id_;
00550
00551 float bad_point = std::numeric_limits<float>::quiet_NaN ();
00552
00553 int depth_idx = 0;
00554 pcl::PointCloud<pcl::PointXYZ>::iterator pt_iter = cloud_msg->begin ();
00555 if (not do_masking)
00556 {
00557 for (int v = 0; v < (int)cloud_msg->height; ++v, depth_idx += depthSkip)
00558 {
00559 for (int u = 0; u < (int)cloud_msg->width; ++u, depth_idx += depthStep, ++pt_iter)
00560 {
00561 pcl::PointXYZ& pt = *pt_iter;
00562
00563
00564 if (depth_md[depth_idx] == 0 ||
00565 depth_md[depth_idx] == depth.getNoSampleValue () ||
00566 depth_md[depth_idx] == depth.getShadowValue ())
00567 {
00568
00569 pt.x = pt.y = pt.z = bad_point;
00570 continue;
00571 }
00572
00573
00574 pt.x = (u - centerX) * depth_md[depth_idx] * constant;
00575 pt.y = (v - centerY) * depth_md[depth_idx] * constant;
00576 pt.z = depth_md[depth_idx] * 0.001;
00577 }
00578 }
00579 }
00580 else
00581 {
00582 int u, v;
00583 unsigned int nMask = mask_indices_.size();
00584 int max_index = (depth_height_ * depth_width_) - 1;
00585 for (unsigned int i = 0; i < nMask; i++, ++pt_iter)
00586 {
00587 pcl::PointXYZ& pt = *pt_iter;
00588
00589 depth_idx = mask_indices_[i];
00590 if (depth_idx > max_index)
00591 {
00592 NODELET_ERROR("Mask index %d exceeds maximum index of %d", depth_idx, max_index);
00593 continue;
00594 }
00595 v = depth_idx / depth_width_;
00596 u = depth_idx % depth_width_;
00597
00598
00599 if (depth_md[depth_idx] == 0 ||
00600 depth_md[depth_idx] == depth.getNoSampleValue () ||
00601 depth_md[depth_idx] == depth.getShadowValue ())
00602 {
00603
00604 pt.x = pt.y = pt.z = bad_point;
00605 continue;
00606 }
00607
00608
00609 pt.x = (u - centerX) * depth_md[depth_idx] * constant;
00610 pt.y = (v - centerY) * depth_md[depth_idx] * constant;
00611 pt.z = depth_md[depth_idx] * 0.001;
00612 }
00613 }
00614
00615 pub_point_cloud_.publish (cloud_msg);
00616 }
00617
00618 void OpenNINodelet::publishXYZRGBPointCloud (const sensor_msgs::ImageConstPtr& depth_msg, const sensor_msgs::ImageConstPtr& rgb_msg) const
00619 {
00620 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_msg (new pcl::PointCloud<pcl::PointXYZRGB>() );
00621 cloud_msg->header.stamp = depth_msg->header.stamp;
00622 cloud_msg->header.frame_id = rgb_frame_id_;
00623 cloud_msg->is_dense = false;
00624
00625 bool do_masking = (use_indices_ and (mask_indices_.size() != 0));
00626
00627 float centerX, centerY;
00628 float constant;
00629 unsigned color_step, color_skip;
00630
00631 if (not do_masking)
00632 {
00633 cloud_msg->height = depth_msg->height;
00634 cloud_msg->width = depth_msg->width;
00635 centerX = (cloud_msg->width >> 1) - 0.5f;
00636 centerY = (cloud_msg->height >> 1) - 0.5f;
00637 constant = 1.0f / device_->getImageFocalLength(cloud_msg->width);
00638 color_step = 3 * rgb_msg->width / cloud_msg->width;
00639 color_skip = 3 * (rgb_msg->height / cloud_msg->height - 1) * rgb_msg->width;
00640
00641 }
00642 else
00643 {
00644 cloud_msg->width = mask_indices_.size();
00645 cloud_msg->height = 1;
00646 centerX = (depth_msg->width >> 1) - 0.5f;
00647 centerY = (depth_msg->height >> 1) - 0.5f;
00648 constant = 1.0f / device_->getImageFocalLength(depth_msg->width);
00649 color_step = 3 * rgb_msg->width / depth_msg->width;
00650 color_skip = 3 * (rgb_msg->height / depth_msg->height - 1) * rgb_msg->width;
00651 }
00652
00653 static bool info_sent = false;
00654 if (not info_sent)
00655 {
00656
00657 info_sent = true;
00658 }
00659
00660
00661 if (rgb_msg->height < depth_msg->height || rgb_msg->width < depth_msg->width)
00662 {
00663
00664 static unsigned warned = 0;
00665 if (warned % 100 == 0)
00666 NODELET_WARN("rgb image smaller than depth image... skipping point cloud for this frame rgb:%dx%d vs. depth:%3dx%d"
00667 , rgb_msg->width, rgb_msg->height, depth_msg->width, depth_msg->height );
00668 ++warned;
00669 return;
00670 }
00671 cloud_msg->points.resize (cloud_msg->height * cloud_msg->width);
00672
00673 const float* depth_buffer = reinterpret_cast<const float*>(&depth_msg->data[0]);
00674 const uint8_t* rgb_buffer = &rgb_msg->data[0];
00675
00676
00677 int color_idx = 0, depth_idx = 0;
00678 pcl::PointCloud<pcl::PointXYZRGB>::iterator pt_iter = cloud_msg->begin ();
00679 if (not do_masking)
00680 {
00681 for (int v = 0; v < (int)cloud_msg->height; ++v, color_idx += color_skip)
00682 {
00683 for (int u = 0; u < (int)cloud_msg->width; ++u, color_idx += color_step, ++depth_idx, ++pt_iter)
00684 {
00685 pcl::PointXYZRGB& pt = *pt_iter;
00686 float Z = depth_buffer[depth_idx];
00687
00688
00689 if (std::isnan (Z))
00690 {
00691 pt.x = pt.y = pt.z = Z;
00692 }
00693 else
00694 {
00695
00696 pt.x = (u - centerX) * Z * constant;
00697 pt.y = (v - centerY) * Z * constant;
00698 pt.z = Z;
00699 }
00700
00701
00702 RGBValue color;
00703 color.Red = rgb_buffer[color_idx];
00704 color.Green = rgb_buffer[color_idx + 1];
00705 color.Blue = rgb_buffer[color_idx + 2];
00706 color.Alpha = 0;
00707 pt.rgb = color.float_value;
00708 }
00709 }
00710 }
00711 else
00712 {
00713 int u, v;
00714 unsigned int nMask = mask_indices_.size();
00715 int max_index = (depth_msg->height * depth_msg->width) - 1;
00716 for (unsigned int i = 0; i < nMask; i++, ++pt_iter)
00717 {
00718 pcl::PointXYZRGB& pt = *pt_iter;
00719 depth_idx = mask_indices_[i];
00720 if (depth_idx > max_index)
00721 {
00722 NODELET_ERROR("Mask index %d exceeds maximum index of %d", depth_idx, max_index);
00723 continue;
00724 }
00725 float Z = depth_buffer[depth_idx];
00726
00727 v = depth_idx / depth_msg->width;
00728 u = depth_idx % depth_msg->width;
00729
00730
00731 if (std::isnan (Z))
00732 {
00733 pt.x = pt.y = pt.z = Z;
00734 }
00735 else
00736 {
00737
00738 pt.x = (u - centerX) * Z * constant;
00739 pt.y = (v - centerY) * Z * constant;
00740 pt.z = Z;
00741 }
00742
00743
00744 RGBValue color;
00745 color_idx = (v*depth_msg->width + u)*color_step;
00746 color.Red = rgb_buffer[color_idx];
00747 color.Green = rgb_buffer[color_idx + 1];
00748 color.Blue = rgb_buffer[color_idx + 2];
00749 color.Alpha = 0;
00750 pt.rgb = color.float_value;
00751 }
00752 }
00753
00754 pub_point_cloud_rgb_.publish (cloud_msg);
00755 }
00756
00757 sensor_msgs::CameraInfoPtr OpenNINodelet::fillCameraInfo (ros::Time time, bool is_rgb)
00758 {
00759 sensor_msgs::CameraInfoPtr info_msg = boost::make_shared<sensor_msgs::CameraInfo > ();
00760 info_msg->header.stamp = time;
00761 info_msg->header.frame_id = is_rgb ? rgb_frame_id_ : depth_frame_id_;
00762 info_msg->width = is_rgb ? image_width_ : depth_width_;
00763 info_msg->height = is_rgb ? image_height_ : depth_height_;
00764
00765 #if ROS_VERSION_MINIMUM(1, 3, 0)
00766 info_msg->D = std::vector<double>(5, 0.0);
00767 info_msg->distortion_model = sensor_msgs::distortion_models::PLUMB_BOB;
00768 #else
00769 info_msg->D.assign (0.0);
00770 #endif
00771 info_msg->K.assign (0.0);
00772 info_msg->R.assign (0.0);
00773 info_msg->P.assign (0.0);
00774
00775 double f = is_rgb ? device_->getImageFocalLength (image_width_) : device_->getDepthFocalLength (depth_width_);
00776 info_msg->K[0] = info_msg->K[4] = f;
00777 info_msg->K[2] = (info_msg->width / 2) - 0.5;
00778 info_msg->K[5] = (info_msg->width * 3./8.) - 0.5;
00779 info_msg->K[8] = 1.0;
00780
00781 info_msg->R[0] = info_msg->R[4] = info_msg->R[8] = 1.0;
00782
00783 info_msg->P[0] = info_msg->P[5] = info_msg->K[0];
00784 info_msg->P[2] = info_msg->K[2];
00785 info_msg->P[6] = info_msg->K[5];
00786 info_msg->P[10] = 1.0;
00787
00788 return info_msg;
00789 }
00790
00791 void OpenNINodelet::configCallback (Config &config, uint32_t level)
00792 {
00793 XnMapOutputMode old_image_mode = device_->getImageOutputMode ();
00794 XnMapOutputMode old_depth_mode = device_->getDepthOutputMode ();
00795
00796
00797 XnMapOutputMode image_mode, compatible_image_mode;
00798 image_mode = mapConfigMode2XnMode (config.image_mode);
00799
00800 if (!device_->findCompatibleImageMode (image_mode, compatible_image_mode))
00801 {
00802 NODELET_WARN ("Could not find any compatible image output mode for %d x %d @ %d.",
00803 image_mode.nXRes, image_mode.nYRes, image_mode.nFPS);
00804
00805
00806 config = config_;
00807 return;
00808 }
00809
00810 XnMapOutputMode depth_mode, compatible_depth_mode;
00811 depth_mode = mapConfigMode2XnMode (config.depth_mode);
00812 if (!device_->findCompatibleDepthMode (depth_mode, compatible_depth_mode))
00813 {
00814 NODELET_WARN ("Could not find any compatible depth output mode for %d x %d @ %d.",
00815 depth_mode.nXRes, depth_mode.nYRes, depth_mode.nFPS);
00816
00817
00818 config = config_;
00819 return;
00820 }
00821
00822 DeviceKinect* kinect = dynamic_cast<DeviceKinect*> (device_.get ());
00823 if (kinect)
00824 {
00825 switch (config.debayering)
00826 {
00827 case OpenNI_Bilinear:
00828 kinect->setDebayeringMethod (ImageBayerGRBG::Bilinear);
00829 break;
00830 case OpenNI_EdgeAware:
00831 kinect->setDebayeringMethod (ImageBayerGRBG::EdgeAware);
00832 break;
00833 case OpenNI_EdgeAwareWeighted:
00834 kinect->setDebayeringMethod (ImageBayerGRBG::EdgeAwareWeighted);
00835 break;
00836 default:
00837 NODELET_ERROR ("unknwon debayering method");
00838 config.debayering = config_.debayering;
00839 break;
00840 }
00841 }
00842 else if (config.debayering != config_.debayering)
00843 {
00844 NODELET_WARN ("%s does not output bayer images. Selection has no affect.", device_->getProductName () );
00845 }
00846
00847 if (pub_point_cloud_rgb_.getNumSubscribers () > 0)
00848 {
00849 if ( (depth_mode.nXRes > image_mode.nXRes) || (depth_mode.nYRes > image_mode.nYRes) ||
00850 (image_mode.nXRes % depth_mode.nXRes != 0) )
00851 {
00852
00853 NODELET_WARN ("depth mode not compatible to image mode, since PointCloudXYZRGB has subscribers.");
00854 config = config_;
00855 return;
00856 }
00857 if (!config.depth_registration && config_.depth_registration)
00858 {
00859 NODELET_WARN ("can not turn of registration, since PointCloudXYZRGB has subscribers.");
00860 config = config_;
00861 return;
00862 }
00863 }
00864
00865
00866 if (compatible_image_mode != old_image_mode || compatible_depth_mode != old_depth_mode)
00867 {
00868 stopSynchronization ();
00869
00870 if (compatible_image_mode != old_image_mode)
00871 {
00872
00873 device_->setImageOutputMode (compatible_image_mode);
00874 image_width_ = image_mode.nXRes;
00875 image_height_ = image_mode.nYRes;
00876
00877 }
00878
00879 if (compatible_depth_mode != old_depth_mode)
00880 {
00881
00882 device_->setDepthOutputMode (compatible_depth_mode);
00883 depth_width_ = depth_mode.nXRes;
00884 depth_height_ = depth_mode.nYRes;
00885
00886 }
00887 startSynchronization ();
00888 }
00889 else
00890 {
00891 if (config_.image_mode != config.image_mode)
00892 {
00893 image_width_ = image_mode.nXRes;
00894 image_height_ = image_mode.nYRes;
00895 }
00896
00897 if (config_.depth_mode != config.depth_mode)
00898 {
00899 depth_width_ = depth_mode.nXRes;
00900 depth_height_ = depth_mode.nYRes;
00901 }
00902 }
00903
00904 if (device_->isDepthRegistered () != config.depth_registration)
00905 {
00906 device_->setDepthRegistration (config.depth_registration);
00907 }
00908
00909
00910 config_ = config;
00911 }
00912
00913 bool OpenNINodelet::isImageModeSupported (int image_mode) const
00914 {
00915 XnMapOutputMode image_md = mapConfigMode2XnMode (image_mode);
00916 XnMapOutputMode compatible_mode;
00917 if (device_->findCompatibleImageMode (image_md, compatible_mode))
00918 return true;
00919 return false;
00920 }
00921
00922 bool OpenNINodelet::isDepthModeSupported (int depth_mode) const
00923 {
00924 XnMapOutputMode depth_md = mapConfigMode2XnMode (depth_mode);
00925 XnMapOutputMode compatible_mode;
00926 if (device_->findCompatibleDepthMode (depth_md, compatible_mode))
00927 return true;
00928 return false;
00929 }
00930
00931 void OpenNINodelet::startSynchronization ()
00932 {
00933 if (device_->isSynchronizationSupported () && !device_->isSynchronized () &&
00934 device_->getImageOutputMode ().nFPS == device_->getDepthOutputMode ().nFPS &&
00935 device_->isImageStreamRunning () && device_->isDepthStreamRunning () )
00936 device_->setSynchronization (true);
00937 }
00938
00939 void OpenNINodelet::stopSynchronization ()
00940 {
00941 if (device_->isSynchronizationSupported () && device_->isSynchronized ())
00942 device_->setSynchronization (false);
00943 }
00944
00945 void OpenNINodelet::updateModeMaps ()
00946 {
00947 XnMapOutputMode output_mode;
00948
00949 output_mode.nXRes = XN_SXGA_X_RES;
00950 output_mode.nYRes = XN_SXGA_Y_RES;
00951 output_mode.nFPS = 15;
00952 xn2config_map_[output_mode] = OpenNI_SXGA_15Hz;
00953 config2xn_map_[OpenNI_SXGA_15Hz] = output_mode;
00954
00955 output_mode.nXRes = XN_VGA_X_RES;
00956 output_mode.nYRes = XN_VGA_Y_RES;
00957 output_mode.nFPS = 25;
00958 xn2config_map_[output_mode] = OpenNI_VGA_25Hz;
00959 config2xn_map_[OpenNI_VGA_25Hz] = output_mode;
00960 output_mode.nFPS = 30;
00961 xn2config_map_[output_mode] = OpenNI_VGA_30Hz;
00962 config2xn_map_[OpenNI_VGA_30Hz] = output_mode;
00963
00964 output_mode.nXRes = XN_QVGA_X_RES;
00965 output_mode.nYRes = XN_QVGA_Y_RES;
00966 output_mode.nFPS = 25;
00967 xn2config_map_[output_mode] = OpenNI_QVGA_25Hz;
00968 config2xn_map_[OpenNI_QVGA_25Hz] = output_mode;
00969 output_mode.nFPS = 30;
00970 xn2config_map_[output_mode] = OpenNI_QVGA_30Hz;
00971 config2xn_map_[OpenNI_QVGA_30Hz] = output_mode;
00972 output_mode.nFPS = 60;
00973 xn2config_map_[output_mode] = OpenNI_QVGA_60Hz;
00974 config2xn_map_[OpenNI_QVGA_60Hz] = output_mode;
00975
00976 output_mode.nXRes = XN_QQVGA_X_RES;
00977 output_mode.nYRes = XN_QQVGA_Y_RES;
00978 output_mode.nFPS = 25;
00979 xn2config_map_[output_mode] = OpenNI_QQVGA_25Hz;
00980 config2xn_map_[OpenNI_QQVGA_25Hz] = output_mode;
00981 output_mode.nFPS = 30;
00982 xn2config_map_[output_mode] = OpenNI_QQVGA_30Hz;
00983 config2xn_map_[OpenNI_QQVGA_30Hz] = output_mode;
00984 output_mode.nFPS = 60;
00985 xn2config_map_[output_mode] = OpenNI_QQVGA_60Hz;
00986 config2xn_map_[OpenNI_QQVGA_60Hz] = output_mode;
00987 }
00988
00989 int OpenNINodelet::mapXnMode2ConfigMode (const XnMapOutputMode& output_mode) const
00990 {
00991 std::map<XnMapOutputMode, int, modeComp>::const_iterator it = xn2config_map_.find (output_mode);
00992
00993 if (it == xn2config_map_.end ())
00994 {
00995 NODELET_ERROR ("mode %dx%d@%d could not be found", output_mode.nXRes, output_mode.nYRes, output_mode.nFPS);
00996 exit (-1);
00997 }
00998 else
00999 return it->second;
01000 }
01001
01002 XnMapOutputMode OpenNINodelet::mapConfigMode2XnMode (int mode) const
01003 {
01004 std::map<int, XnMapOutputMode>::const_iterator it = config2xn_map_.find (mode);
01005 if (it == config2xn_map_.end ())
01006 {
01007 NODELET_ERROR ("mode %d could not be found", mode);
01008 exit (-1);
01009 }
01010 else
01011 return it->second;
01012 }
01013
01014 void OpenNINodelet::maskIndicesCb(const pcl::PointIndicesConstPtr& indices)
01015 {
01016 mask_indices_.resize(indices->indices.size());
01017
01018 memcpy(mask_indices_.data(), indices->indices.data(), indices->indices.size() * sizeof(int32_t));
01019 }
01020 }
01021
01022