disparity.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <nodelet/nodelet.h>
00003 #include <image_transport/image_transport.h>
00004 #include <image_transport/subscriber_filter.h>
00005 #include <message_filters/subscriber.h>
00006 #include <message_filters/time_synchronizer.h>
00007 #include <sensor_msgs/image_encodings.h>
00008 #include <stereo_msgs/DisparityImage.h>
00009 #include "depth_traits.h"
00010 
00011 namespace depth_image_proc {
00012 
00013 namespace enc = sensor_msgs::image_encodings;
00014 
00015 class DisparityNodelet : public nodelet::Nodelet
00016 {
00017   boost::shared_ptr<image_transport::ImageTransport> left_it_;
00018   ros::NodeHandlePtr right_nh_;
00019   image_transport::SubscriberFilter sub_depth_image_;
00020   message_filters::Subscriber<sensor_msgs::CameraInfo> sub_info_;
00021   typedef message_filters::TimeSynchronizer<sensor_msgs::Image, sensor_msgs::CameraInfo> Sync;
00022   boost::shared_ptr<Sync> sync_;
00023   
00024   boost::mutex connect_mutex_;
00025   ros::Publisher pub_disparity_;
00026   double min_range_;
00027   double max_range_;
00028   double delta_d_;
00029 
00030   virtual void onInit();
00031 
00032   void connectCb();
00033 
00034   void depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
00035                const sensor_msgs::CameraInfoConstPtr& info_msg);
00036 
00037   template<typename T>
00038   void convert(const sensor_msgs::ImageConstPtr& depth_msg,
00039                stereo_msgs::DisparityImagePtr& disp_msg);
00040 };
00041 
00042 void DisparityNodelet::onInit()
00043 {
00044   ros::NodeHandle &nh         = getNodeHandle();
00045   ros::NodeHandle &private_nh = getPrivateNodeHandle();
00046   ros::NodeHandle left_nh(nh, "left");
00047   left_it_.reset(new image_transport::ImageTransport(left_nh));
00048   right_nh_.reset( new ros::NodeHandle(nh, "right") );
00049 
00050   // Read parameters
00051   int queue_size;
00052   private_nh.param("queue_size", queue_size, 5);
00053   private_nh.param("min_range", min_range_, 0.0);
00054   private_nh.param("max_range", max_range_, std::numeric_limits<double>::infinity());
00055   private_nh.param("delta_d", delta_d_, 0.125);
00056 
00057   // Synchronize inputs. Topic subscriptions happen on demand in the connection callback.
00058   sync_.reset( new Sync(sub_depth_image_, sub_info_, queue_size) );
00059   sync_->registerCallback(boost::bind(&DisparityNodelet::depthCb, this, _1, _2));
00060 
00061   // Monitor whether anyone is subscribed to the output
00062   ros::SubscriberStatusCallback connect_cb = boost::bind(&DisparityNodelet::connectCb, this);
00063   // Make sure we don't enter connectCb() between advertising and assigning to pub_disparity_
00064   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00065   pub_disparity_ = left_nh.advertise<stereo_msgs::DisparityImage>("disparity", 1, connect_cb, connect_cb);
00066 }
00067 
00068 // Handles (un)subscribing when clients (un)subscribe
00069 void DisparityNodelet::connectCb()
00070 {
00071   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00072   if (pub_disparity_.getNumSubscribers() == 0)
00073   {
00074     sub_depth_image_.unsubscribe();
00075     sub_info_ .unsubscribe();
00076   }
00077   else if (!sub_depth_image_.getSubscriber())
00078   {
00079     image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00080     sub_depth_image_.subscribe(*left_it_, "image_rect", 1, hints);
00081     sub_info_.subscribe(*right_nh_, "camera_info", 1);
00082   }
00083 }
00084 
00085 void DisparityNodelet::depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
00086                                const sensor_msgs::CameraInfoConstPtr& info_msg)
00087 {
00088   // Allocate new DisparityImage message
00089   stereo_msgs::DisparityImagePtr disp_msg( new stereo_msgs::DisparityImage );
00090   disp_msg->header         = depth_msg->header;
00091   disp_msg->image.header   = disp_msg->header;
00092   disp_msg->image.encoding = enc::TYPE_32FC1;
00093   disp_msg->image.height   = depth_msg->height;
00094   disp_msg->image.width    = depth_msg->width;
00095   disp_msg->image.step     = disp_msg->image.width * sizeof (float);
00096   disp_msg->image.data.resize( disp_msg->image.height * disp_msg->image.step, 0.0f );
00097   double fx = info_msg->P[0];
00098   disp_msg->T = -info_msg->P[3] / fx;
00099   disp_msg->f = fx;
00100   // Remaining fields depend on device characteristics, so rely on user input
00101   disp_msg->min_disparity = disp_msg->f * disp_msg->T / max_range_;
00102   disp_msg->max_disparity = disp_msg->f * disp_msg->T / min_range_;
00103   disp_msg->delta_d = delta_d_;
00104 
00105   if (depth_msg->encoding == enc::TYPE_16UC1)
00106   {
00107     convert<uint16_t>(depth_msg, disp_msg);
00108   }
00109   else if (depth_msg->encoding == enc::TYPE_32FC1)
00110   {
00111     convert<float>(depth_msg, disp_msg);
00112   }
00113   else
00114   {
00115     NODELET_ERROR_THROTTLE(5, "Depth image has unsupported encoding [%s]", depth_msg->encoding.c_str());
00116     return;
00117   }
00118 
00119   pub_disparity_.publish(disp_msg);
00120 }
00121 
00122 template<typename T>
00123 void DisparityNodelet::convert(const sensor_msgs::ImageConstPtr& depth_msg,
00124                                stereo_msgs::DisparityImagePtr& disp_msg)
00125 {
00126   // For each depth Z, disparity d = fT / Z
00127   float unit_scaling = DepthTraits<T>::toMeters( T(1) );
00128   float constant = disp_msg->f * disp_msg->T / unit_scaling;
00129 
00130   const T* depth_row = reinterpret_cast<const T*>(&depth_msg->data[0]);
00131   int row_step = depth_msg->step / sizeof(T);
00132   float* disp_data = reinterpret_cast<float*>(&disp_msg->image.data[0]);
00133   for (int v = 0; v < (int)depth_msg->height; ++v)
00134   {
00135     for (int u = 0; u < (int)depth_msg->width; ++u)
00136     {
00137       T depth = depth_row[u];
00138       if (DepthTraits<T>::valid(depth))
00139         *disp_data = constant / depth;
00140       ++disp_data;
00141     }
00142 
00143     depth_row += row_step;
00144   }
00145 }
00146 
00147 } // namespace depth_image_proc
00148 
00149 // Register as nodelet
00150 #include <pluginlib/class_list_macros.h>
00151 PLUGINLIB_DECLARE_CLASS (depth_image_proc, disparity, depth_image_proc::DisparityNodelet, nodelet::Nodelet);


depth_image_proc
Author(s): Patrick Mihelich
autogenerated on Fri Jan 3 2014 11:24:53