register.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/synchronizer.h>
00007 #include <message_filters/sync_policies/approximate_time.h>
00008 #include <tf/transform_listener.h>
00009 #include <sensor_msgs/image_encodings.h>
00010 #include <image_geometry/pinhole_camera_model.h>
00011 #include <Eigen/Core>
00012 #include "depth_traits.h"
00013 
00014 namespace depth_image_proc {
00015 
00016 using namespace message_filters::sync_policies;
00017 namespace enc = sensor_msgs::image_encodings;
00018 
00019 class RegisterNodelet : public nodelet::Nodelet
00020 {
00021   ros::NodeHandlePtr nh_depth_, nh_rgb_;
00022   boost::shared_ptr<image_transport::ImageTransport> it_depth_;
00023   
00024   // Subscriptions
00025   image_transport::SubscriberFilter sub_depth_image_;
00026   message_filters::Subscriber<sensor_msgs::CameraInfo> sub_depth_info_, sub_rgb_info_;
00027   boost::shared_ptr<tf::TransformListener> tf_;
00028   typedef ApproximateTime<sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> SyncPolicy;
00029   typedef message_filters::Synchronizer<SyncPolicy> Synchronizer;
00030   boost::shared_ptr<Synchronizer> sync_;
00031 
00032   // Publications
00033   boost::mutex connect_mutex_;
00034   image_transport::CameraPublisher pub_registered_;
00035 
00036   image_geometry::PinholeCameraModel depth_model_, rgb_model_;
00037 
00038   virtual void onInit();
00039 
00040   void connectCb();
00041 
00042   void imageCb(const sensor_msgs::ImageConstPtr& depth_image_msg,
00043                const sensor_msgs::CameraInfoConstPtr& depth_info_msg,
00044                const sensor_msgs::CameraInfoConstPtr& rgb_info_msg);
00045 
00046   template<typename T>
00047   void convert(const sensor_msgs::ImageConstPtr& depth_msg,
00048                const sensor_msgs::ImagePtr& registered_msg,
00049                const Eigen::Matrix4d& depth_to_rgb);
00050 };
00051 
00052 void RegisterNodelet::onInit()
00053 {
00054   ros::NodeHandle& nh         = getNodeHandle();
00055   ros::NodeHandle& private_nh = getPrivateNodeHandle();
00056   nh_depth_.reset( new ros::NodeHandle(nh, "depth") );
00057   nh_rgb_.reset( new ros::NodeHandle(nh, "rgb") );
00058   it_depth_.reset( new image_transport::ImageTransport(*nh_depth_) );
00059   tf_.reset( new tf::TransformListener );
00060 
00061   // Read parameters
00062   int queue_size;
00063   private_nh.param("queue_size", queue_size, 5);
00064 
00065   // Synchronize inputs. Topic subscriptions happen on demand in the connection callback.
00066   sync_.reset( new Synchronizer(SyncPolicy(queue_size), sub_depth_image_, sub_depth_info_, sub_rgb_info_) );
00067   sync_->registerCallback(boost::bind(&RegisterNodelet::imageCb, this, _1, _2, _3));
00068 
00069   // Monitor whether anyone is subscribed to the output
00070   image_transport::ImageTransport it_depth_reg(ros::NodeHandle(nh, "depth_registered"));
00071   image_transport::SubscriberStatusCallback image_connect_cb = boost::bind(&RegisterNodelet::connectCb, this);
00072   ros::SubscriberStatusCallback info_connect_cb = boost::bind(&RegisterNodelet::connectCb, this);
00073   // Make sure we don't enter connectCb() between advertising and assigning to pub_registered_
00074   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00075   pub_registered_ = it_depth_reg.advertiseCamera("image_rect", 1,
00076                                                  image_connect_cb, image_connect_cb,
00077                                                  info_connect_cb, info_connect_cb);
00078 }
00079 
00080 // Handles (un)subscribing when clients (un)subscribe
00081 void RegisterNodelet::connectCb()
00082 {
00083   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00084   if (pub_registered_.getNumSubscribers() == 0)
00085   {
00086     sub_depth_image_.unsubscribe();
00087     sub_depth_info_ .unsubscribe();
00088     sub_rgb_info_   .unsubscribe();
00089   }
00090   else if (!sub_depth_image_.getSubscriber())
00091   {
00092     image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00093     sub_depth_image_.subscribe(*it_depth_, "image_rect",  1, hints);
00094     sub_depth_info_ .subscribe(*nh_depth_, "camera_info", 1);
00095     sub_rgb_info_   .subscribe(*nh_rgb_,   "camera_info", 1);
00096   }
00097 }
00098 
00099 void RegisterNodelet::imageCb(const sensor_msgs::ImageConstPtr& depth_image_msg,
00100                               const sensor_msgs::CameraInfoConstPtr& depth_info_msg,
00101                               const sensor_msgs::CameraInfoConstPtr& rgb_info_msg)
00102 {
00103   // Update camera models - these take binning & ROI into account
00104   depth_model_.fromCameraInfo(depth_info_msg);
00105   rgb_model_  .fromCameraInfo(rgb_info_msg);
00106 
00107   // Query tf for transform from (X,Y,Z) in depth camera frame to RGB camera frame
00108   Eigen::Matrix4d depth_to_rgb;
00109   try
00110   {
00111     ros::Duration timeout(1.0 / 30); 
00112     tf_->waitForTransform(rgb_info_msg->header.frame_id, depth_info_msg->header.frame_id,
00113                           depth_info_msg->header.stamp, timeout);
00114     tf::StampedTransform transform;
00115     tf_->lookupTransform (rgb_info_msg->header.frame_id, depth_info_msg->header.frame_id,
00116                           depth_info_msg->header.stamp, transform);
00117 
00118     tf::Matrix3x3& R = transform.getBasis();
00119     tf::Vector3&   T = transform.getOrigin();
00120     depth_to_rgb << R[0][0], R[0][1], R[0][2], T[0],
00121                     R[1][0], R[1][1], R[1][2], T[1],
00122                     R[2][0], R[2][1], R[2][2], T[2],
00123                           0,       0,       0,    1;
00124   }
00125   catch (tf::TransformException& ex)
00126   {
00127     NODELET_WARN_THROTTLE(2, "TF exception:\n%s", ex.what());
00128     return;
00131   }
00132 
00133   // Allocate registered depth image
00134   sensor_msgs::ImagePtr registered_msg( new sensor_msgs::Image );
00135   registered_msg->header.stamp    = depth_image_msg->header.stamp;
00136   registered_msg->header.frame_id = rgb_info_msg->header.frame_id;
00137   registered_msg->encoding        = depth_image_msg->encoding;
00138   
00139   cv::Size resolution = rgb_model_.reducedResolution();
00140   registered_msg->height = resolution.height;
00141   registered_msg->width  = resolution.width;
00142   // step and data set in convert(), depend on depth data type
00143 
00144   if (depth_image_msg->encoding == enc::TYPE_16UC1)
00145   {
00146     convert<uint16_t>(depth_image_msg, registered_msg, depth_to_rgb);
00147   }
00148   else if (depth_image_msg->encoding == enc::TYPE_32FC1)
00149   {
00150     convert<float>(depth_image_msg, registered_msg, depth_to_rgb);
00151   }
00152   else
00153   {
00154     NODELET_ERROR_THROTTLE(5, "Depth image has unsupported encoding [%s]", depth_image_msg->encoding.c_str());
00155     return;
00156   }
00157 
00158   // Registered camera info is the same as the RGB info, but uses the depth timestamp
00159   sensor_msgs::CameraInfoPtr registered_info_msg( new sensor_msgs::CameraInfo(*rgb_info_msg) );
00160   registered_info_msg->header.stamp = registered_msg->header.stamp;
00161 
00162   pub_registered_.publish(registered_msg, registered_info_msg);
00163 }
00164 
00165 template<typename T>
00166 void RegisterNodelet::convert(const sensor_msgs::ImageConstPtr& depth_msg,
00167                               const sensor_msgs::ImagePtr& registered_msg,
00168                               const Eigen::Matrix4d& depth_to_rgb)
00169 {
00170   // Allocate memory for registered depth image
00171   registered_msg->step = registered_msg->width * sizeof(T);
00172   registered_msg->data.resize( registered_msg->height * registered_msg->step );
00173   // data is already zero-filled in the uint16 case, but for floats we want to initialize everything to NaN.
00174   DepthTraits<T>::initializeBuffer(registered_msg->data);
00175 
00176   // Extract all the parameters we need
00177   double inv_depth_fx = 1.0 / depth_model_.fx();
00178   double inv_depth_fy = 1.0 / depth_model_.fy();
00179   double depth_cx = depth_model_.cx(), depth_cy = depth_model_.cy();
00180   double depth_Tx = depth_model_.Tx(), depth_Ty = depth_model_.Ty();
00181   double rgb_fx = rgb_model_.fx(), rgb_fy = rgb_model_.fy();
00182   double rgb_cx = rgb_model_.cx(), rgb_cy = rgb_model_.cy();
00183   double rgb_Tx = rgb_model_.Tx(), rgb_Ty = rgb_model_.Ty();
00184   
00185   // Transform the depth values into the RGB frame
00187   const T* depth_row = reinterpret_cast<const T*>(&depth_msg->data[0]);
00188   int row_step = depth_msg->step / sizeof(T);
00189   T* registered_data = reinterpret_cast<T*>(&registered_msg->data[0]);
00190   int raw_index = 0;
00191   for (unsigned v = 0; v < depth_msg->height; ++v, depth_row += row_step)
00192   {
00193     for (unsigned u = 0; u < depth_msg->width; ++u, ++raw_index)
00194     {
00195       T raw_depth = depth_row[u];
00196       if (!DepthTraits<T>::valid(raw_depth))
00197         continue;
00198       
00199       double depth = DepthTraits<T>::toMeters(raw_depth);
00200 
00202       // Reproject (u,v,Z) to (X,Y,Z,1) in depth camera frame
00203       Eigen::Vector4d xyz_depth;
00204       xyz_depth << ((u - depth_cx)*depth - depth_Tx) * inv_depth_fx,
00205                    ((v - depth_cy)*depth - depth_Ty) * inv_depth_fy,
00206                    depth,
00207                    1;
00208 
00209       // Transform to RGB camera frame
00210       Eigen::Vector4d xyz_rgb = depth_to_rgb * xyz_depth;
00211 
00212       // Project to (u,v) in RGB image
00213       double inv_Z = 1.0 / xyz_rgb.z();
00214       int u_rgb = (rgb_fx*xyz_rgb.x() + rgb_Tx)*inv_Z + rgb_cx + 0.5;
00215       int v_rgb = (rgb_fy*xyz_rgb.y() + rgb_Ty)*inv_Z + rgb_cy + 0.5;
00216       
00217       if (u_rgb < 0 || u_rgb >= (int)registered_msg->width ||
00218           v_rgb < 0 || v_rgb >= (int)registered_msg->height)
00219         continue;
00220       
00221       T& reg_depth = registered_data[v_rgb*registered_msg->width + u_rgb];
00222       T  new_depth = DepthTraits<T>::fromMeters(xyz_rgb.z());
00223       // Validity and Z-buffer checks
00224       if (!DepthTraits<T>::valid(reg_depth) || reg_depth > new_depth)
00225         reg_depth = new_depth;
00226     }
00227   }
00228 }
00229 
00230 } // namespace depth_image_proc
00231 
00232 // Register as nodelet
00233 #include <pluginlib/class_list_macros.h>
00234 PLUGINLIB_DECLARE_CLASS (depth_image_proc, register, depth_image_proc::RegisterNodelet, nodelet::Nodelet);


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