depthcloud_encoder.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Copyright (c) 2014, Willow Garage, Inc.
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions
8  * are met:
9  *
10  * * Redistributions of source code must retain the above copyright
11  * notice, this list of conditions and the following disclaimer.
12  * * Redistributions in binary form must reproduce the above
13  * copyright notice, this list of conditions and the following
14  * disclaimer in the documentation and/or other materials provided
15  * with the distribution.
16  * * Neither the name of the Willow Garage nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32 
33  * Author: Julius Kammerl (jkammerl@willowgarage.com)
34  *
35  */
36 
38 
39 #include <boost/bind.hpp>
40 #include <boost/cstdint.hpp>
41 
42 #include <cv_bridge/cv_bridge.h>
43 
44 #include <pcl/common/transforms.h>
45 #include <pcl/io/pcd_io.h>
48 
49 #include <iostream>
50 
51 #include <ros/console.h>
52 
53 namespace depthcloud
54 {
55 
56 using namespace message_filters::sync_policies;
58 
60  nh_(nh),
61  pnh_(pnh),
62  depth_sub_(),
63  color_sub_(),
64  pub_it_(nh_),
65  connectivityExceptionFlag(false),
66  lookupExceptionFlag(false)
67 {
68  // ROS parameters
69  ros::NodeHandle priv_nh_("~");
70 
71  // read source from param server
72  priv_nh_.param<std::string>("depth_source", depth_source_, "depthmap");
73 
74  // read point cloud topic from param server
75  priv_nh_.param<std::string>("cloud", cloud_topic_, "");
76 
77  // read camera info topic from param server.
78  priv_nh_.param<std::string>("camera_info_topic", camera_info_topic_, "");
79 
80  // The original frame id of the camera that captured this cloud
81  priv_nh_.param<std::string>("camera_frame_id", camera_frame_id_, "/camera_rgb_optical_frame");
82 
83  // read focal length value from param server in case a cloud topic is used.
84  priv_nh_.param<double>("f", f_, 525.0);
85 
86  // read focal length multiplication factor value from param server in case a cloud topic is used.
87  priv_nh_.param<double>("f_mult_factor", f_mult_factor_, 1.0);
88 
89  // read max depth per tile from param server
90  priv_nh_.param<float>("max_depth_per_tile", max_depth_per_tile_, 1.0);
91 
92  // read target resolution from param server.
93  priv_nh_.param<int>("target_resolution", crop_size_, 512);
94 
95  // read depth map topic from param server
96  priv_nh_.param<std::string>("depth", depthmap_topic_, "/camera/depth/image");
97 
98  // read rgb topic from param server
99  priv_nh_.param<std::string>("rgb", rgb_image_topic_, "/camera/rgb/image_color");
100 
101  // Whether the encoded topic should be latched.
102  priv_nh_.param<bool>("latch", latch_, false);
103 
104  // Monitor whether anyone is subscribed to the output
106  // Make sure we don't enter connectCb() between advertising and assigning to pub_point_cloud_
107  boost::lock_guard<boost::mutex> lock(connect_mutex_);
108 
109  pub_ = pub_it_.advertise("depthcloud_encoded", 1, connect_cb, connect_cb, ros::VoidPtr(), latch_);
110 }
112 {
113 }
114 
116 {
117  boost::lock_guard<boost::mutex> lock(connect_mutex_);
118 
119  if (pub_.getNumSubscribers())
120  {
121  if ( depth_source_ == "depthmap" && !depthmap_topic_.empty() )
123  else if ( depth_source_ == "cloud" && !cloud_topic_.empty() )
125  else {
126  if ( depth_source_ != "depthmap" && depth_source_ != "cloud" ) {
127  ROS_ERROR("Invalid depth_source given to DepthCloudEncoder: use 'depthmap' or 'cloud'.");
128  return;
129  }
130  ROS_ERROR_STREAM("Empty topic provided for DepthCloudEncoder depth_source " << depth_source_ << ". Check your arguments.");
131  }
132  }
133  else
134  {
135  unsubscribe();
136  }
137 }
138 
139 void DepthCloudEncoder::cameraInfoCb(const sensor_msgs::CameraInfoConstPtr& cam_info_msg)
140 {
141  if (cam_info_msg) {
142  // Update focal length value.
143  const double fx = f_mult_factor_ * cam_info_msg->K[0];
144  const double fy = f_mult_factor_ * cam_info_msg->K[4];
145  f_ = (fx + fy) / 2;
146  }
147 }
148 
149 void DepthCloudEncoder::dynReconfCb(depthcloud_encoder::paramsConfig& config, uint32_t level)
150 {
151  max_depth_per_tile_ = config.max_depth_per_tile;
152  f_mult_factor_ = config.f_mult_factor;
153 }
154 
155 void DepthCloudEncoder::subscribeCloud(std::string& cloud_topic)
156 {
157  unsubscribe();
158 
159  ROS_DEBUG_STREAM("Subscribing to "<< cloud_topic);
160 
161  // subscribe to depth cloud topic
162  cloud_sub_ = nh_.subscribe(cloud_topic, 1, &DepthCloudEncoder::cloudCB, this );
163  if (!camera_info_topic_.empty()) {
165  }
166 }
167 
168 void DepthCloudEncoder::subscribe(std::string& depth_topic, std::string& color_topic)
169 {
170  unsubscribe();
171 
172  ROS_DEBUG_STREAM("Subscribing to "<< color_topic);
173  ROS_DEBUG_STREAM("Subscribing to "<< depth_topic);
174 
175  if (!depth_topic.empty())
176  {
177  try
178  {
181 
182  // subscribe to depth map topic
183  depth_sub_->subscribe(depth_it, depth_topic, 1, image_transport::TransportHints("raw"));
184 
185  if (!color_topic.empty())
186  {
187  // subscribe to color image topic
188  color_sub_->subscribe(color_it, color_topic, 1, image_transport::TransportHints("raw"));
189 
190  // connect message filters to synchronizer
191  sync_depth_color_->connectInput(*depth_sub_, *color_sub_);
192  sync_depth_color_->setInterMessageLowerBound(0, ros::Duration(1.5));
193  sync_depth_color_->setInterMessageLowerBound(1, ros::Duration(1.5));
194  sync_depth_color_->registerCallback(boost::bind(&DepthCloudEncoder::depthColorCB, this, _1, _2));
195  }
196  else
197  {
198  depth_sub_->registerCallback(boost::bind(&DepthCloudEncoder::depthCB, this, _1));
199  }
200  }
201  catch (ros::Exception& e)
202  {
203  ROS_ERROR("Error subscribing: %s", e.what());
204  }
205  }
206 }
207 
208 
210 {
211  try
212  {
213  // reset all message filters
219  }
220  catch (ros::Exception& e)
221  {
222  ROS_ERROR("Error unsubscribing: %s", e.what());
223  }
224 }
225 
226 void DepthCloudEncoder::cloudCB(const sensor_msgs::PointCloud2& cloud_msg)
227 {
228  sensor_msgs::ImagePtr depth_msg( new sensor_msgs::Image() );
229  sensor_msgs::ImagePtr color_msg( new sensor_msgs::Image() );
230  /* For depth:
231  height: 480
232  width: 640
233  encoding: 32FC1
234  is_bigendian: 0
235  step: 2560
236  */
237  /* For color:
238  height: 480
239  width: 640
240  encoding: rgb8
241  is_bigendian: 0
242  step: 1920
243  */
244 
245  color_msg->height = depth_msg->height = cloud_msg.height;
246  color_msg->width = depth_msg->width = cloud_msg.width;
247  depth_msg->encoding = "32FC1";
248  color_msg->encoding = "rgb8";
249  color_msg->is_bigendian = depth_msg->is_bigendian = 0;
250  depth_msg->step = depth_msg->width * 4;
251  color_msg->step = color_msg->width * 3;
252  // 480 (default) rows of 2560 bytes.
253  depth_msg->data.resize(depth_msg->height * depth_msg->step);
254  // 480 (default) rows of 1920 bytes.
255  color_msg->data.resize(color_msg->height * color_msg->step, 0);
256  for (int j=0; j < depth_msg->height; ++j) {
257  for (int i =0; i < depth_msg->width; ++i) {
258  *(float*)&depth_msg->data[ j * cloud_msg.width * 4 + i * 4 ] =
259  std::numeric_limits<float>::quiet_NaN();
260  }
261  }
262 
263  cloudToDepth(cloud_msg, depth_msg, color_msg);
264 
265  process(depth_msg, color_msg, crop_size_);
266 }
267 
268 void DepthCloudEncoder::depthCB(const sensor_msgs::ImageConstPtr& depth_msg)
269 {
270  process(depth_msg, sensor_msgs::ImageConstPtr(), crop_size_);
271 }
272 
273 void DepthCloudEncoder::depthColorCB(const sensor_msgs::ImageConstPtr& depth_msg,
274  const sensor_msgs::ImageConstPtr& color_msg)
275 {
276  process(depth_msg, color_msg, crop_size_);
277 }
278 
279 void DepthCloudEncoder::cloudToDepth(const sensor_msgs::PointCloud2& cloud_msg, sensor_msgs::ImagePtr depth_msg, sensor_msgs::ImagePtr color_msg)
280 {
281  // projected coordinates + z depth value + Cx,y offset of image plane to origin :
282  double u, v, zd, cx, cy;
283 
284  cx = depth_msg->width / 2;
285  cy = depth_msg->height / 2;
286 
287  // we assume that all the coordinates are in meters...
288  pcl::PointCloud<pcl::PointXYZRGB>::Ptr scene_cloud( new pcl::PointCloud<pcl::PointXYZRGB> );
289  pcl::fromROSMsg(cloud_msg,*scene_cloud);
290 
291  // first convert to camera frame.
292  if ( cloud_msg.header.frame_id != this->camera_frame_id_ ) {
293 
294  tf::StampedTransform transform;
295  try {
296  ros::Duration timeout(0.05);
297  // ros::Time(0) can cause unexpected frames?
298  tf_listener_.waitForTransform( this->camera_frame_id_, cloud_msg.header.frame_id,
299  ros::Time(0), timeout);
300  tf_listener_.lookupTransform(this->camera_frame_id_, cloud_msg.header.frame_id,
301  ros::Time(0), transform);
302  }
303  catch (tf::ExtrapolationException& ex) {
304  ROS_WARN("[run_viewer] TF ExtrapolationException:\n%s", ex.what());
305  }
306  catch (tf::ConnectivityException& ex) {
308  ROS_WARN("[run_viewer] TF ConnectivityException:\n%s", ex.what());
309  ROS_INFO("[run_viewer] Pick-it-App might not run correctly");
311  }
312  }
313  catch (tf::LookupException& ex) {
314  if (!lookupExceptionFlag){
315  ROS_WARN("[run_viewer] TF LookupException:\n%s", ex.what());
316  ROS_INFO("[run_viewer] Pick-it-App might not be running yet");
317  lookupExceptionFlag = true;
318  return;
319  }
320  }
321  catch (tf::TransformException& ex) {
322  ROS_WARN("[run_viewer] TF exception:\n%s", ex.what());
323  return;
324  }
325 
326  pcl::PointCloud<pcl::PointXYZRGB>::Ptr camera_cloud( new pcl::PointCloud<pcl::PointXYZRGB> );
327  // Transform to the Camera reference frame
328  Eigen::Affine3d eigen_transform3d;
329  tf::transformTFToEigen(transform, eigen_transform3d );
330  Eigen::Affine3f eigen_transform3f( eigen_transform3d );
331  pcl::transformPointCloud(*scene_cloud,*camera_cloud,eigen_transform3f);
332 
333  // pass on new point cloud expressed in camera frame:
334  scene_cloud = camera_cloud;
335  }
336 
337  int number_of_points = scene_cloud->size();
338 
339  using namespace std;
340 
341  for(int i = 0 ; i < number_of_points ; i++)
342  {
343  if(isFinite(scene_cloud->points[i]))
344  {
345  // calculate in 'image plane' :
346  u = (f_ / scene_cloud->points[i].z ) * scene_cloud->points[i].x + cx;
347  v = (f_ / scene_cloud->points[i].z ) * scene_cloud->points[i].y + cy;
348  // only write out pixels that fit into our depth image
349  int dlocation = int(u)*4 + int(v)*depth_msg->step;
350  if ( dlocation >=0 && dlocation < depth_msg->data.size() ) {
351  *(float*)&depth_msg->data[ dlocation ] = scene_cloud->points[i].z;
352  }
353  int clocation = int(u)*3 + int(v)*color_msg->step;
354  if ( clocation >=0 && clocation < color_msg->data.size() ) {
355  color_msg->data[ clocation ] = scene_cloud->points[i].r;
356  color_msg->data[ clocation+1 ] = scene_cloud->points[i].g;
357  color_msg->data[ clocation+2 ] = scene_cloud->points[i].b;
358  }
359  }
360  }
361 }
362 
363 void DepthCloudEncoder::process(const sensor_msgs::ImageConstPtr& depth_msg,
364  const sensor_msgs::ImageConstPtr& color_msg,
365  const std::size_t crop_size)
366 {
367  // Bit depth of image encoding
368  int depth_bits = enc::bitDepth(depth_msg->encoding);
369  int depth_channels = enc::numChannels(depth_msg->encoding);
370 
371  int color_bits = 0;
372  int color_channels = 0;
373 
374  if ((depth_bits != 32) || (depth_channels != 1))
375  {
376  ROS_DEBUG_STREAM( "Invalid color depth image format ("<<depth_msg->encoding <<")");
377  return;
378  }
379 
380  // OpenCV-ros bridge
381  cv_bridge::CvImagePtr color_cv_ptr;
382 
383  // check for color message
384  if (color_msg)
385  {
386  try
387  {
388  color_cv_ptr = cv_bridge::toCvCopy(color_msg, "bgr8");
389 
390  }
391  catch (cv_bridge::Exception& e)
392  {
393  ROS_ERROR_STREAM("OpenCV-ROS bridge error: " << e.what());
394  return;
395  }
396 
397  if (depth_msg->width != color_msg->width || depth_msg->height != color_msg->height)
398  {
399  ROS_DEBUG_STREAM( "Depth image resolution (" << (int)depth_msg->width << "x" << (int)depth_msg->height << ") "
400  "does not match color image resolution (" << (int)color_msg->width << "x" << (int)color_msg->height << ")");
401  return;
402  }
403  }
404 
405  // preprocessing => close NaN hole via interpolation and generate valid_point_mask
406  sensor_msgs::ImagePtr depth_int_msg(new sensor_msgs::Image());
407  sensor_msgs::ImagePtr valid_mask_msg(new sensor_msgs::Image());
408 
409  depthInterpolation(depth_msg, depth_int_msg, valid_mask_msg);
410 
411  unsigned int pix_size = enc::bitDepth(enc::BGR8) / 8 * 3;
412 
413  // generate output image message
414  sensor_msgs::ImagePtr output_msg(new sensor_msgs::Image);
415  output_msg->header = depth_int_msg->header;
416  output_msg->encoding = enc::BGR8;
417  output_msg->width = crop_size * 2;
418  output_msg->height = crop_size * 2;
419  output_msg->step = output_msg->width * pix_size;
420  output_msg->is_bigendian = depth_int_msg->is_bigendian;
421 
422  // allocate memory
423  output_msg->data.resize(output_msg->width * output_msg->height * pix_size, 0xFF);
424 
425  std::size_t input_width = depth_int_msg->width;
426  std::size_t input_height = depth_int_msg->height;
427 
428  // copy depth & color data to output image
429  {
430  std::size_t y, x, left_x, top_y, width_x, width_y;
431 
432  // calculate borders to crop input image to crop_size X crop_size
433  int top_bottom_corner = (static_cast<int>(input_height) - static_cast<int>(crop_size)) / 2;
434  int left_right_corner = (static_cast<int>(input_width) - static_cast<int>(crop_size)) / 2;
435 
436  if (top_bottom_corner < 0)
437  {
438  top_y = 0;
439  width_y = input_height;
440  }
441  else
442  {
443  top_y = top_bottom_corner;
444  width_y = input_height - top_bottom_corner;
445  }
446 
447  if (left_right_corner < 0)
448  {
449  left_x = 0;
450  width_x = input_width;
451  }
452  else
453  {
454  left_x = left_right_corner;
455  width_x = input_width - left_right_corner;
456  }
457 
458  // pointer to output image
459  uint8_t* dest_ptr = &output_msg->data[((top_y - top_bottom_corner) * output_msg->width + left_x - left_right_corner)
460  * pix_size];
461  const std::size_t dest_y_step = output_msg->step;
462 
463  // pointer to interpolated depth data
464  const float* source_depth_ptr = (const float*)&depth_int_msg->data[(top_y * input_width + left_x) * sizeof(float)];
465 
466  // pointer to valid-pixel-mask
467  const uint8_t* source_mask_ptr = &valid_mask_msg->data[(top_y * input_width + left_x) * sizeof(uint8_t)];
468 
469  // pointer to color data
470  const uint8_t* source_color_ptr = 0;
471  std::size_t source_color_y_step = 0;
472  if (color_msg)
473  {
474  source_color_y_step = input_width * pix_size;
475  source_color_ptr = static_cast<const uint8_t*>(&color_cv_ptr->image.data[(top_y * input_width + left_x) * pix_size]);
476  }
477 
478  // helpers
479  const std::size_t right_frame_shift = crop_size * pix_size;
480  ;
481  const std::size_t down_frame_shift = dest_y_step * crop_size;
482 
483  // generate output image
484  for (y = top_y; y < width_y;
485  ++y, source_color_ptr += source_color_y_step, source_depth_ptr += input_width, source_mask_ptr += input_width, dest_ptr +=
486  dest_y_step)
487  {
488  const float *depth_ptr = source_depth_ptr;
489 
490  // reset iterator pointers for each column
491  const uint8_t *color_ptr = source_color_ptr;
492  const uint8_t *mask_ptr = source_mask_ptr;
493 
494  uint8_t *out_depth_low_ptr = dest_ptr;
495  uint8_t *out_depth_high_ptr = dest_ptr + right_frame_shift;
496  uint8_t *out_color_ptr = dest_ptr + right_frame_shift + down_frame_shift;
497 
498  for (x = left_x; x < width_x; ++x)
499  {
500  int depth_pix_low;
501  int depth_pix_high;
502 
503  if (*depth_ptr == *depth_ptr) // valid point
504  {
505  depth_pix_low = std::min(std::max(0.0f, (*depth_ptr / max_depth_per_tile_) * (float)(0xFF * 3)), (float)(0xFF * 3));
506  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));
507  }
508  else
509  {
510  depth_pix_low = 0;
511  depth_pix_high = 0;
512 
513  }
514 
515  uint8_t *mask_pix_ptr = out_depth_low_ptr + down_frame_shift;
516  if (*mask_ptr == 0)
517  {
518  // black pixel for valid point
519  memset(mask_pix_ptr, 0x00, pix_size);
520  }
521  else
522  {
523  // white pixel for invalid point
524  memset(mask_pix_ptr, 0xFF, pix_size);
525  }
526 
527  // divide into color channels + saturate for each channel:
528  uint8_t depth_pix_low_r = std::min(std::max(0, depth_pix_low), (0xFF));
529  uint8_t depth_pix_low_g = std::min(std::max(0, depth_pix_low-(0xFF)), (0xFF));
530  uint8_t depth_pix_low_b = std::min(std::max(0, depth_pix_low-(0xFF*2)), (0xFF));
531 
532  *out_depth_low_ptr = depth_pix_low_r; ++out_depth_low_ptr;
533  *out_depth_low_ptr = depth_pix_low_g; ++out_depth_low_ptr;
534  *out_depth_low_ptr = depth_pix_low_b; ++out_depth_low_ptr;
535 
536  uint8_t depth_pix_high_r = std::min(std::max(0, depth_pix_high), (0xFF));
537  uint8_t depth_pix_high_g = std::min(std::max(0, depth_pix_high-(0xFF)), (0xFF));
538  uint8_t depth_pix_high_b = std::min(std::max(0, depth_pix_high-(0xFF*2)), (0xFF));
539 
540  *out_depth_high_ptr = depth_pix_high_r; ++out_depth_high_ptr;
541  *out_depth_high_ptr = depth_pix_high_g; ++out_depth_high_ptr;
542  *out_depth_high_ptr = depth_pix_high_b; ++out_depth_high_ptr;
543 
544  if (color_ptr)
545  {
546  // copy three color channels
547  *out_color_ptr = *color_ptr; ++out_color_ptr; ++color_ptr;
548 
549  *out_color_ptr = *color_ptr; ++out_color_ptr; ++color_ptr;
550 
551  *out_color_ptr = *color_ptr; ++out_color_ptr; ++color_ptr;
552  }
553 
554  // increase input iterator pointers
555  ++mask_ptr;
556  ++depth_ptr;
557 
558  }
559  }
560  }
561 
562  pub_.publish(output_msg);
563 }
564 
565 void DepthCloudEncoder::depthInterpolation(sensor_msgs::ImageConstPtr depth_msg, sensor_msgs::ImagePtr depth_int_msg,
566  sensor_msgs::ImagePtr mask_msg)
567 {
568  const std::size_t input_width = depth_msg->width;
569  const std::size_t input_height = depth_msg->height;
570 
571  // prepare output image - depth image with interpolated NaN holes
572  depth_int_msg->header = depth_msg->header;
573  depth_int_msg->encoding = depth_msg->encoding;
574  depth_int_msg->width = input_width;
575  depth_int_msg->height = input_height;
576  depth_int_msg->step = depth_msg->step;
577  depth_int_msg->is_bigendian = depth_msg->is_bigendian;
578  depth_int_msg->data.resize(depth_int_msg->step * depth_int_msg->height, 0);
579 
580  // prepare output image - valid sample mask
581  mask_msg->header = depth_msg->header;
582  mask_msg->encoding = enc::TYPE_8UC1;
583  mask_msg->width = input_width;
584  mask_msg->height = input_height;
585  mask_msg->step = depth_msg->step;
586  mask_msg->is_bigendian = depth_msg->is_bigendian;
587  mask_msg->data.resize(mask_msg->step * mask_msg->height, 0xFF);
588 
589  const float* depth_ptr = (const float*)&depth_msg->data[0];
590  float* depth_int_ptr = (float*)&depth_int_msg->data[0];
591  uint8_t* mask_ptr = (uint8_t*)&mask_msg->data[0];
592 
593  float leftVal = -1.0f;
594 
595  unsigned int y, len;
596  for (y = 0; y < input_height; ++y, depth_ptr += input_width, depth_int_ptr += input_width, mask_ptr += input_width)
597  {
598  const float* in_depth_ptr = depth_ptr;
599  float* out_depth_int_ptr = depth_int_ptr;
600  uint8_t* out_mask_ptr = mask_ptr;
601 
602  const float* in_depth_end_ptr = depth_ptr + input_width;
603 
604  while (in_depth_ptr < in_depth_end_ptr)
605  {
606  len = 0;
607  const float* last_valid_pix_ptr = in_depth_ptr;
608  while ((isnan(*in_depth_ptr) || (*in_depth_ptr == 0)) && (in_depth_ptr < in_depth_end_ptr))
609  {
610  ++in_depth_ptr;
611  ++len;
612  }
613  if (len > 0)
614  {
615  // we found a NaN hole
616 
617  // find valid pixel on right side of hole
618  float rightVal;
619  if (in_depth_ptr < in_depth_end_ptr)
620  {
621  rightVal = *in_depth_ptr;
622  }
623  else
624  {
625  rightVal = leftVal;
626  }
627 
628  // find valid pixel on left side of hole
629  if (isnan(leftVal) || (leftVal < 0.0f))
630  leftVal = rightVal;
631 
632  float incVal = (rightVal - leftVal) / (float)len;
633  float fillVal = leftVal;
634  const float* fill_ptr;
635 
636  for (fill_ptr = last_valid_pix_ptr; fill_ptr < in_depth_ptr; ++fill_ptr)
637  {
638  // fill hole with interpolated pixel data
639  *out_depth_int_ptr = fillVal;
640  ++out_depth_int_ptr;
641 
642  // write unknown sample to valid-pixel-mask
643  *out_mask_ptr = 0xFF; ++out_mask_ptr;
644 
645  fillVal += incVal;
646  }
647 
648  leftVal = rightVal;
649  }
650  else
651  {
652  // valid sample found - no hole to patch
653 
654  leftVal = *in_depth_ptr;
655 
656  *out_depth_int_ptr = *in_depth_ptr;
657 
658  // write known sample to valid-pixel-mask
659  *out_mask_ptr = 0; ++out_mask_ptr;
660 
661  ++in_depth_ptr;
662  ++out_depth_int_ptr;
663  }
664 
665  }
666 
667  }
668 
669 }
670 
671 
672 }
void subscribe(std::string &depth_topic, std::string &color_topic)
void subscribeCloud(std::string &cloud_topic)
void cloudToDepth(const sensor_msgs::PointCloud2 &cloud_msg, sensor_msgs::ImagePtr depth_msg, sensor_msgs::ImagePtr color_msg)
tf::TransformListener tf_listener_
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
f
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void cameraInfoCb(const sensor_msgs::CameraInfoConstPtr &cam_info_msg)
boost::shared_ptr< SynchronizerDepthColor > sync_depth_color_
void depthCB(const sensor_msgs::ImageConstPtr &depth_msg)
image_transport::ImageTransport pub_it_
void depthInterpolation(sensor_msgs::ImageConstPtr depth_msg, sensor_msgs::ImagePtr depth_int_msg, sensor_msgs::ImagePtr mask_msg)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
DepthCloudEncoder(ros::NodeHandle &nh, ros::NodeHandle &pnh)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
void cloudCB(const sensor_msgs::PointCloud2 &cloud_msg)
uint32_t getNumSubscribers() const
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
void publish(const sensor_msgs::Image &message) const
#define ROS_INFO(...)
message_filters::Synchronizer< SyncPolicyDepthColor > SynchronizerDepthColor
bool param(const std::string &param_name, T &param_val, const T &default_val) const
boost::shared_ptr< image_transport::SubscriberFilter > depth_sub_
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
TFSIMD_FORCE_INLINE const tfScalar & x() const
image_transport::Publisher pub_
#define ROS_DEBUG_STREAM(args)
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
boost::shared_ptr< image_transport::SubscriberFilter > color_sub_
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > SyncPolicyDepthColor
void dynReconfCb(depthcloud_encoder::paramsConfig &config, uint32_t level)
#define ROS_ERROR_STREAM(args)
#define ROS_ERROR(...)
void process(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &color_msg, const std::size_t crop_size)
void depthColorCB(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &color_msg)


depthcloud_encoder
Author(s): Julius Kammer
autogenerated on Mon Jun 10 2019 13:06:12