00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 #include "depthcloud_encoder/depthcloud_encoder.h"
00038 
00039 #include <boost/bind.hpp>
00040 #include <boost/cstdint.hpp>
00041 
00042 #include <cv_bridge/cv_bridge.h>
00043 
00044 #include <pcl/common/transforms.h>
00045 #include <pcl/io/pcd_io.h>
00046 #include <pcl_conversions/pcl_conversions.h>
00047 #include <tf_conversions/tf_eigen.h>
00048 
00049 #include <iostream>
00050 
00051 #include <ros/console.h>
00052 
00053 namespace depthcloud
00054 {
00055 
00056 using namespace message_filters::sync_policies;
00057 namespace enc = sensor_msgs::image_encodings;
00058 
00059 static int target_resolution_ = 512;
00060 static float max_depth_per_tile = 1.0;
00061 
00062 DepthCloudEncoder::DepthCloudEncoder(ros::NodeHandle& nh, ros::NodeHandle& pnh) :
00063     nh_(nh),
00064     pnh_(pnh),
00065     depth_sub_(),
00066     color_sub_(),
00067     pub_it_(nh_),
00068     crop_size_(target_resolution_),
00069     connectivityExceptionFlag(false),
00070     lookupExceptionFlag(false)
00071 {
00072   
00073   ros::NodeHandle priv_nh_("~");
00074 
00075   
00076   priv_nh_.param<std::string>("depth_source", depth_source_, "depthmap");
00077 
00078   
00079   priv_nh_.param<std::string>("cloud", cloud_topic_, "");
00080 
00081   
00082   priv_nh_.param<std::string>("camera_frame_id", camera_frame_id_, "/camera_rgb_optical_frame");
00083 
00084   
00085   priv_nh_.param<double>("f", f_, 525.0);
00086 
00087   
00088   priv_nh_.param<std::string>("depth", depthmap_topic_, "/camera/depth/image");
00089 
00090   
00091   priv_nh_.param<std::string>("rgb", rgb_image_topic_, "/camera/rgb/image_color");
00092 
00093   
00094   image_transport::SubscriberStatusCallback connect_cb = boost::bind(&DepthCloudEncoder::connectCb, this);
00095   
00096   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00097 
00098   pub_ = pub_it_.advertise("depthcloud_encoded", 1, connect_cb, connect_cb);
00099 }
00100 DepthCloudEncoder::~DepthCloudEncoder()
00101 {
00102 }
00103 
00104 void DepthCloudEncoder::connectCb()
00105 {
00106   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00107 
00108   if (pub_.getNumSubscribers())
00109   {
00110     if ( depth_source_ == "depthmap" && !depthmap_topic_.empty() )
00111       subscribe(depthmap_topic_, rgb_image_topic_);
00112     else if ( depth_source_ == "cloud" && !cloud_topic_.empty() )
00113       subscribeCloud(cloud_topic_);
00114     else {
00115       if ( depth_source_ != "depthmap" && depth_source_ != "cloud" ) {
00116           ROS_ERROR("Invalid depth_source given to DepthCloudEncoder: use 'depthmap' or 'cloud'.");
00117           return;
00118       }
00119       ROS_ERROR_STREAM("Empty topic provided for DepthCloudEncoder depth_source " << depth_source_ << ". Check your arguments.");
00120     }
00121   }
00122   else
00123   {
00124     unsubscribe();
00125   }
00126 }
00127 
00128 void DepthCloudEncoder::subscribeCloud(std::string& cloud_topic)
00129 {
00130   unsubscribe();
00131 
00132   ROS_DEBUG_STREAM("Subscribing to "<< cloud_topic);
00133 
00134   
00135   cloud_sub_ = nh_.subscribe(cloud_topic, 1, &DepthCloudEncoder::cloudCB, this );
00136 }
00137 
00138 void DepthCloudEncoder::subscribe(std::string& depth_topic, std::string& color_topic)
00139 {
00140   unsubscribe();
00141 
00142   ROS_DEBUG_STREAM("Subscribing to "<< color_topic);
00143   ROS_DEBUG_STREAM("Subscribing to "<< depth_topic);
00144 
00145   if (!depth_topic.empty())
00146   {
00147     try
00148     {
00149       image_transport::ImageTransport depth_it(pnh_);
00150       image_transport::ImageTransport color_it(pnh_);
00151 
00152       
00153       depth_sub_->subscribe(depth_it, depth_topic, 1, image_transport::TransportHints("raw"));
00154 
00155       if (!color_topic.empty())
00156       {
00157         
00158         color_sub_->subscribe(color_it, color_topic, 1, image_transport::TransportHints("raw"));
00159 
00160         
00161         sync_depth_color_->connectInput(*depth_sub_, *color_sub_);
00162         sync_depth_color_->setInterMessageLowerBound(0, ros::Duration(1.5));
00163         sync_depth_color_->setInterMessageLowerBound(1, ros::Duration(1.5));
00164         sync_depth_color_->registerCallback(boost::bind(&DepthCloudEncoder::depthColorCB, this, _1, _2));
00165       }
00166       else
00167       {
00168         depth_sub_->registerCallback(boost::bind(&DepthCloudEncoder::depthCB, this, _1));
00169       }
00170     }
00171     catch (ros::Exception& e)
00172     {
00173       ROS_ERROR("Error subscribing: %s", e.what());
00174     }
00175   }
00176 }
00177 
00178 
00179 void DepthCloudEncoder::unsubscribe()
00180 {
00181   try
00182   {
00183     
00184     cloud_sub_.shutdown();
00185     sync_depth_color_.reset(new SynchronizerDepthColor(SyncPolicyDepthColor(10)));
00186     depth_sub_.reset(new image_transport::SubscriberFilter());
00187     color_sub_.reset(new image_transport::SubscriberFilter());
00188   }
00189   catch (ros::Exception& e)
00190   {
00191     ROS_ERROR("Error unsubscribing: %s", e.what());
00192   }
00193 }
00194 
00195 void DepthCloudEncoder::cloudCB(const sensor_msgs::PointCloud2& cloud_msg)
00196 {
00197   sensor_msgs::ImagePtr depth_msg( new sensor_msgs::Image() );
00198   sensor_msgs::ImagePtr color_msg( new sensor_msgs::Image() );
00199   
00200 
00201 
00202 
00203 
00204 
00205 
00206   
00207 
00208 
00209 
00210 
00211 
00212 
00213   color_msg->height = depth_msg->height = 480;
00214   color_msg->width  = depth_msg->width  = 640;
00215   depth_msg->encoding = "32FC1";
00216   color_msg->encoding = "rgb8";
00217   color_msg->is_bigendian = depth_msg->is_bigendian = 0;
00218   depth_msg->step = depth_msg->width * 4;
00219   color_msg->step = color_msg->width * 3;
00220   depth_msg->data.resize( depth_msg->height * depth_msg->step ); 
00221   color_msg->data.resize( color_msg->height * color_msg->step, 0 ); 
00222   for( int j=0; j < depth_msg->height; ++j ) {
00223     for( int i =0; i < depth_msg->width; ++i ) {
00224       *(float*)&depth_msg->data[ j*640*4 + i*4] = std::numeric_limits<float>::quiet_NaN();
00225     }
00226   }
00227 
00228   cloudToDepth(cloud_msg, depth_msg, color_msg);
00229 
00230   process(depth_msg, color_msg, crop_size_);
00231 }
00232 
00233 void DepthCloudEncoder::depthCB(const sensor_msgs::ImageConstPtr& depth_msg)
00234 {
00235   process(depth_msg, sensor_msgs::ImageConstPtr(), crop_size_);
00236 }
00237 
00238 void DepthCloudEncoder::depthColorCB(const sensor_msgs::ImageConstPtr& depth_msg,
00239                                      const sensor_msgs::ImageConstPtr& color_msg)
00240 {
00241   process(depth_msg, color_msg, crop_size_);
00242 }
00243 
00244 void DepthCloudEncoder::cloudToDepth(const sensor_msgs::PointCloud2& cloud_msg, sensor_msgs::ImagePtr depth_msg, sensor_msgs::ImagePtr color_msg)
00245 {
00246   
00247   double u, v, zd, cx, cy;
00248 
00249   cx = depth_msg->width / 2;
00250   cy = depth_msg->height / 2;
00251 
00252   
00253   pcl::PointCloud<pcl::PointXYZRGB>::Ptr scene_cloud( new pcl::PointCloud<pcl::PointXYZRGB> );
00254   pcl::fromROSMsg(cloud_msg,*scene_cloud);
00255 
00256   
00257   if ( cloud_msg.header.frame_id != this->camera_frame_id_ ) {
00258 
00259     tf::StampedTransform transform;
00260     try {
00261       ros::Duration timeout(0.05);
00262       
00263       tf_listener_.waitForTransform( this->camera_frame_id_, cloud_msg.header.frame_id,
00264                                     ros::Time(0), timeout);
00265       tf_listener_.lookupTransform(this->camera_frame_id_, cloud_msg.header.frame_id, 
00266                                    ros::Time(0), transform);
00267     }
00268     catch (tf::ExtrapolationException& ex) {
00269       ROS_WARN("[run_viewer] TF ExtrapolationException:\n%s", ex.what());
00270     }
00271     catch (tf::ConnectivityException& ex) {
00272       if (!connectivityExceptionFlag) {
00273         ROS_WARN("[run_viewer] TF ConnectivityException:\n%s", ex.what());
00274         ROS_INFO("[run_viewer] Pick-it-App might not run correctly");
00275         connectivityExceptionFlag = true;
00276       }
00277     }
00278     catch (tf::LookupException& ex) {
00279       if (!lookupExceptionFlag){
00280         ROS_WARN("[run_viewer] TF LookupException:\n%s", ex.what());
00281         ROS_INFO("[run_viewer] Pick-it-App might not be running yet");
00282         lookupExceptionFlag = true;
00283         return;
00284       }
00285     }
00286     catch (tf::TransformException& ex) {
00287       ROS_WARN("[run_viewer] TF exception:\n%s", ex.what());
00288       return;
00289     }
00290 
00291         pcl::PointCloud<pcl::PointXYZRGB>::Ptr camera_cloud( new pcl::PointCloud<pcl::PointXYZRGB> );
00292         
00293         Eigen::Affine3d eigen_transform3d;
00294         tf::transformTFToEigen(transform, eigen_transform3d );
00295         Eigen::Affine3f eigen_transform3f( eigen_transform3d );
00296         pcl::transformPointCloud(*scene_cloud,*camera_cloud,eigen_transform3f);
00297 
00298         
00299         scene_cloud = camera_cloud;
00300   }
00301 
00302   int number_of_points =  scene_cloud->size();
00303 
00304   using namespace std;
00305 
00306   for(int i = 0 ; i < number_of_points ; i++)
00307     {
00308       if(isFinite(scene_cloud->points[i]))
00309         {
00310           
00311           u = (f_ / scene_cloud->points[i].z ) * scene_cloud->points[i].x + cx;
00312           v = (f_ / scene_cloud->points[i].z ) * scene_cloud->points[i].y + cy;
00313           
00314           int dlocation = int(u)*4 + int(v)*depth_msg->step;
00315           if ( dlocation >=0 && dlocation < depth_msg->data.size() ) {
00316             *(float*)&depth_msg->data[ dlocation ] = scene_cloud->points[i].z;
00317           }
00318           int clocation = int(u)*3 + int(v)*color_msg->step;
00319           if ( clocation >=0 && clocation < color_msg->data.size() ) {
00320             color_msg->data[ clocation   ] = scene_cloud->points[i].r;
00321             color_msg->data[ clocation+1 ] = scene_cloud->points[i].g;
00322             color_msg->data[ clocation+2 ] = scene_cloud->points[i].b;
00323           }
00324         }
00325     }
00326 }
00327 
00328 void DepthCloudEncoder::process(const sensor_msgs::ImageConstPtr& depth_msg,
00329                                 const sensor_msgs::ImageConstPtr& color_msg,
00330                                 const std::size_t crop_size)
00331 {
00332   
00333   int depth_bits = enc::bitDepth(depth_msg->encoding);
00334   int depth_channels = enc::numChannels(depth_msg->encoding);
00335 
00336   int color_bits = 0;
00337   int color_channels = 0;
00338 
00339   if ((depth_bits != 32) || (depth_channels != 1))
00340   {
00341     ROS_DEBUG_STREAM( "Invalid color depth image format ("<<depth_msg->encoding <<")");
00342     return;
00343   }
00344 
00345   
00346   cv_bridge::CvImagePtr color_cv_ptr;
00347 
00348   
00349   if (color_msg)
00350   {
00351     try
00352     {
00353       color_cv_ptr = cv_bridge::toCvCopy(color_msg, "bgr8");
00354 
00355     }
00356     catch (cv_bridge::Exception& e)
00357     {
00358       ROS_ERROR_STREAM("OpenCV-ROS bridge error: " << e.what());
00359       return;
00360     }
00361 
00362     if (depth_msg->width != color_msg->width || depth_msg->height != color_msg->height)
00363     {
00364       ROS_DEBUG_STREAM( "Depth image resolution (" << (int)depth_msg->width << "x" << (int)depth_msg->height << ") "
00365       "does not match color image resolution (" << (int)color_msg->width << "x" << (int)color_msg->height << ")");
00366       return;
00367     }
00368   }
00369 
00370   
00371   sensor_msgs::ImagePtr depth_int_msg(new sensor_msgs::Image());
00372   sensor_msgs::ImagePtr valid_mask_msg(new sensor_msgs::Image());
00373 
00374   depthInterpolation(depth_msg, depth_int_msg, valid_mask_msg);
00375 
00376   unsigned int pix_size = enc::bitDepth(enc::BGR8) / 8 * 3;
00377 
00378   
00379   sensor_msgs::ImagePtr output_msg(new sensor_msgs::Image);
00380   output_msg->header = depth_int_msg->header;
00381   output_msg->encoding = enc::BGR8;
00382   output_msg->width = crop_size * 2;
00383   output_msg->height = crop_size * 2;
00384   output_msg->step = output_msg->width * pix_size;
00385   output_msg->is_bigendian = depth_int_msg->is_bigendian;
00386 
00387   
00388   output_msg->data.resize(output_msg->width * output_msg->height * pix_size, 0xFF);
00389 
00390   std::size_t input_width = depth_int_msg->width;
00391   std::size_t input_height = depth_int_msg->height;
00392 
00393   
00394   {
00395     std::size_t y, x, left_x, top_y, width_x, width_y;
00396 
00397     
00398     int top_bottom_corner = (static_cast<int>(input_height) - static_cast<int>(crop_size)) / 2;
00399     int left_right_corner = (static_cast<int>(input_width) - static_cast<int>(crop_size)) / 2;
00400 
00401     if (top_bottom_corner < 0)
00402     {
00403       top_y = 0;
00404       width_y = input_height;
00405     }
00406     else
00407     {
00408       top_y = top_bottom_corner;
00409       width_y = input_height - top_bottom_corner;
00410     }
00411 
00412     if (left_right_corner < 0)
00413     {
00414       left_x = 0;
00415       width_x = input_width;
00416     }
00417     else
00418     {
00419       left_x = left_right_corner;
00420       width_x = input_width - left_right_corner;
00421     }
00422 
00423     
00424     uint8_t* dest_ptr = &output_msg->data[((top_y - top_bottom_corner) * output_msg->width + left_x - left_right_corner)
00425         * pix_size];
00426     const std::size_t dest_y_step = output_msg->step;
00427 
00428     
00429     const float* source_depth_ptr = (const float*)&depth_int_msg->data[(top_y * input_width + left_x) * sizeof(float)];
00430 
00431     
00432     const uint8_t* source_mask_ptr = &valid_mask_msg->data[(top_y * input_width + left_x) * sizeof(uint8_t)];
00433 
00434     
00435     const uint8_t* source_color_ptr = 0;
00436     std::size_t source_color_y_step = 0;
00437     if (color_msg)
00438     {
00439       source_color_y_step = input_width * pix_size;
00440       source_color_ptr = static_cast<const uint8_t*>(&color_cv_ptr->image.data[(top_y * input_width + left_x) * pix_size]);
00441     }
00442 
00443     
00444     const std::size_t right_frame_shift = crop_size * pix_size;
00445     ;
00446     const std::size_t down_frame_shift = dest_y_step * crop_size;
00447 
00448     
00449     for (y = top_y; y < width_y;
00450         ++y, source_color_ptr += source_color_y_step, source_depth_ptr += input_width, source_mask_ptr += input_width, dest_ptr +=
00451             dest_y_step)
00452     {
00453       const float *depth_ptr = source_depth_ptr;
00454 
00455       
00456       const uint8_t *color_ptr = source_color_ptr;
00457       const uint8_t *mask_ptr = source_mask_ptr;
00458 
00459       uint8_t *out_depth_low_ptr = dest_ptr;
00460       uint8_t *out_depth_high_ptr = dest_ptr + right_frame_shift;
00461       uint8_t *out_color_ptr = dest_ptr + right_frame_shift + down_frame_shift;
00462 
00463       for (x = left_x; x < width_x; ++x)
00464       {
00465         int depth_pix_low;
00466         int depth_pix_high;
00467 
00468         if (*depth_ptr == *depth_ptr) 
00469         {
00470           depth_pix_low = std::min(std::max(0.0f, (*depth_ptr / max_depth_per_tile) * (float)(0xFF * 3)), (float)(0xFF * 3));
00471           depth_pix_high = std::min(std::max(0.0f, ((*depth_ptr - max_depth_per_tile) / max_depth_per_tile) * (float)(0xFF) * 3), (float)(0xFF * 3));
00472         }
00473         else
00474         {
00475           depth_pix_low = 0;
00476           depth_pix_high = 0;
00477 
00478         }
00479 
00480         uint8_t *mask_pix_ptr = out_depth_low_ptr + down_frame_shift;
00481         if (*mask_ptr == 0)
00482         {
00483           
00484           memset(mask_pix_ptr, 0x00, pix_size);
00485         }
00486         else
00487         {
00488           
00489           memset(mask_pix_ptr, 0xFF, pix_size);
00490         }
00491 
00492         
00493         uint8_t depth_pix_low_r = std::min(std::max(0, depth_pix_low), (0xFF));
00494         uint8_t depth_pix_low_g = std::min(std::max(0, depth_pix_low-(0xFF)), (0xFF));
00495         uint8_t depth_pix_low_b = std::min(std::max(0, depth_pix_low-(0xFF*2)), (0xFF));
00496 
00497         *out_depth_low_ptr = depth_pix_low_r;  ++out_depth_low_ptr;
00498         *out_depth_low_ptr = depth_pix_low_g;  ++out_depth_low_ptr;
00499         *out_depth_low_ptr = depth_pix_low_b;  ++out_depth_low_ptr;
00500 
00501         uint8_t depth_pix_high_r = std::min(std::max(0, depth_pix_high), (0xFF));
00502         uint8_t depth_pix_high_g = std::min(std::max(0, depth_pix_high-(0xFF)), (0xFF));
00503         uint8_t depth_pix_high_b = std::min(std::max(0, depth_pix_high-(0xFF*2)), (0xFF));
00504 
00505         *out_depth_high_ptr = depth_pix_high_r; ++out_depth_high_ptr;
00506         *out_depth_high_ptr = depth_pix_high_g; ++out_depth_high_ptr;
00507         *out_depth_high_ptr = depth_pix_high_b; ++out_depth_high_ptr;
00508 
00509         if (color_ptr)
00510         {
00511           
00512           *out_color_ptr = *color_ptr; ++out_color_ptr; ++color_ptr;
00513 
00514           *out_color_ptr = *color_ptr; ++out_color_ptr; ++color_ptr;
00515 
00516           *out_color_ptr = *color_ptr; ++out_color_ptr; ++color_ptr;
00517         }
00518 
00519         
00520         ++mask_ptr;
00521         ++depth_ptr;
00522 
00523       }
00524     }
00525   }
00526 
00527   pub_.publish(output_msg);
00528 }
00529 
00530 void DepthCloudEncoder::depthInterpolation(sensor_msgs::ImageConstPtr depth_msg, sensor_msgs::ImagePtr depth_int_msg,
00531                                            sensor_msgs::ImagePtr mask_msg)
00532 {
00533   const std::size_t input_width = depth_msg->width;
00534   const std::size_t input_height = depth_msg->height;
00535 
00536   
00537   depth_int_msg->header = depth_msg->header;
00538   depth_int_msg->encoding = depth_msg->encoding;
00539   depth_int_msg->width = input_width;
00540   depth_int_msg->height = input_height;
00541   depth_int_msg->step = depth_msg->step;
00542   depth_int_msg->is_bigendian = depth_msg->is_bigendian;
00543   depth_int_msg->data.resize(depth_int_msg->step * depth_int_msg->height, 0);
00544 
00545   
00546   mask_msg->header = depth_msg->header;
00547   mask_msg->encoding = enc::TYPE_8UC1;
00548   mask_msg->width = input_width;
00549   mask_msg->height = input_height;
00550   mask_msg->step = depth_msg->step;
00551   mask_msg->is_bigendian = depth_msg->is_bigendian;
00552   mask_msg->data.resize(mask_msg->step * mask_msg->height, 0xFF);
00553 
00554   const float* depth_ptr = (const float*)&depth_msg->data[0];
00555   float* depth_int_ptr = (float*)&depth_int_msg->data[0];
00556   uint8_t* mask_ptr = (uint8_t*)&mask_msg->data[0];
00557 
00558   float leftVal = -1.0f;
00559 
00560   unsigned int y, len;
00561   for (y = 0; y < input_height; ++y, depth_ptr += input_width, depth_int_ptr += input_width, mask_ptr += input_width)
00562   {
00563     const float* in_depth_ptr = depth_ptr;
00564     float* out_depth_int_ptr = depth_int_ptr;
00565     uint8_t* out_mask_ptr = mask_ptr;
00566 
00567     const float* in_depth_end_ptr = depth_ptr + input_width;
00568 
00569     while (in_depth_ptr < in_depth_end_ptr)
00570     {
00571       len = 0;
00572       const float* last_valid_pix_ptr = in_depth_ptr;
00573       while ((isnan(*in_depth_ptr) || (*in_depth_ptr == 0)) && (in_depth_ptr < in_depth_end_ptr))
00574       {
00575         ++in_depth_ptr;
00576         ++len;
00577       }
00578       if (len > 0)
00579       {
00580         
00581 
00582         
00583         float rightVal;
00584         if (in_depth_ptr < in_depth_end_ptr)
00585         {
00586           rightVal = *in_depth_ptr;
00587         }
00588         else
00589         {
00590           rightVal = leftVal;
00591         }
00592 
00593         
00594         if (isnan(leftVal) || (leftVal < 0.0f))
00595           leftVal = rightVal;
00596 
00597         float incVal = (rightVal - leftVal) / (float)len;
00598         float fillVal = leftVal;
00599         const float* fill_ptr;
00600 
00601         for (fill_ptr = last_valid_pix_ptr; fill_ptr < in_depth_ptr; ++fill_ptr)
00602         {
00603           
00604           *out_depth_int_ptr = fillVal;
00605           ++out_depth_int_ptr;
00606 
00607           
00608           *out_mask_ptr = 0xFF; ++out_mask_ptr;
00609 
00610           fillVal += incVal;
00611         }
00612 
00613         leftVal = rightVal;
00614       }
00615       else
00616       {
00617         
00618 
00619         leftVal = *in_depth_ptr;
00620 
00621         *out_depth_int_ptr = *in_depth_ptr;
00622 
00623         
00624         *out_mask_ptr = 0; ++out_mask_ptr;
00625 
00626         ++in_depth_ptr;
00627         ++out_depth_int_ptr;
00628       }
00629 
00630     }
00631 
00632   }
00633 
00634 }
00635 
00636 
00637 }
00638