39 #include <boost/bind.hpp> 40 #include <boost/cstdint.hpp> 44 #include <pcl/common/transforms.h> 45 #include <pcl/io/pcd_io.h> 65 connectivityExceptionFlag(false),
66 lookupExceptionFlag(false)
84 priv_nh_.
param<
double>(
"f",
f_, 525.0);
127 ROS_ERROR(
"Invalid depth_source given to DepthCloudEncoder: use 'depthmap' or 'cloud'.");
175 if (!depth_topic.empty())
185 if (!color_topic.empty())
203 ROS_ERROR(
"Error subscribing: %s", e.what());
222 ROS_ERROR(
"Error unsubscribing: %s", e.what());
228 sensor_msgs::ImagePtr depth_msg(
new sensor_msgs::Image() );
229 sensor_msgs::ImagePtr color_msg(
new sensor_msgs::Image() );
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;
253 depth_msg->data.resize(depth_msg->height * depth_msg->step);
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();
274 const sensor_msgs::ImageConstPtr& color_msg)
282 double u, v, zd, cx, cy;
284 cx = depth_msg->width / 2;
285 cy = depth_msg->height / 2;
288 pcl::PointCloud<pcl::PointXYZRGB>::Ptr scene_cloud(
new pcl::PointCloud<pcl::PointXYZRGB> );
292 if ( cloud_msg.header.frame_id != this->camera_frame_id_ ) {
304 ROS_WARN(
"[run_viewer] TF ExtrapolationException:\n%s", ex.what());
308 ROS_WARN(
"[run_viewer] TF ConnectivityException:\n%s", ex.what());
309 ROS_INFO(
"[run_viewer] Pick-it-App might not run correctly");
315 ROS_WARN(
"[run_viewer] TF LookupException:\n%s", ex.what());
316 ROS_INFO(
"[run_viewer] Pick-it-App might not be running yet");
322 ROS_WARN(
"[run_viewer] TF exception:\n%s", ex.what());
326 pcl::PointCloud<pcl::PointXYZRGB>::Ptr camera_cloud(
new pcl::PointCloud<pcl::PointXYZRGB> );
328 Eigen::Affine3d eigen_transform3d;
330 Eigen::Affine3f eigen_transform3f( eigen_transform3d );
331 pcl::transformPointCloud(*scene_cloud,*camera_cloud,eigen_transform3f);
334 scene_cloud = camera_cloud;
337 int number_of_points = scene_cloud->size();
341 for(
int i = 0 ; i < number_of_points ; i++)
343 if(isFinite(scene_cloud->points[i]))
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;
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;
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;
364 const sensor_msgs::ImageConstPtr& color_msg,
365 const std::size_t crop_size)
368 int depth_bits = enc::bitDepth(depth_msg->encoding);
369 int depth_channels = enc::numChannels(depth_msg->encoding);
372 int color_channels = 0;
374 if ((depth_bits != 32) || (depth_channels != 1))
376 ROS_DEBUG_STREAM(
"Invalid color depth image format ("<<depth_msg->encoding <<
")");
397 if (depth_msg->width != color_msg->width || depth_msg->height != color_msg->height)
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 <<
")");
406 sensor_msgs::ImagePtr depth_int_msg(
new sensor_msgs::Image());
407 sensor_msgs::ImagePtr valid_mask_msg(
new sensor_msgs::Image());
411 unsigned int pix_size = enc::bitDepth(enc::BGR8) / 8 * 3;
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;
423 output_msg->data.resize(output_msg->width * output_msg->height * pix_size, 0xFF);
425 std::size_t input_width = depth_int_msg->width;
426 std::size_t input_height = depth_int_msg->height;
430 std::size_t
y,
x, left_x, top_y, width_x, width_y;
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;
436 if (top_bottom_corner < 0)
439 width_y = input_height;
443 top_y = top_bottom_corner;
444 width_y = input_height - top_bottom_corner;
447 if (left_right_corner < 0)
450 width_x = input_width;
454 left_x = left_right_corner;
455 width_x = input_width - left_right_corner;
459 uint8_t* dest_ptr = &output_msg->data[((top_y - top_bottom_corner) * output_msg->width + left_x - left_right_corner)
461 const std::size_t dest_y_step = output_msg->step;
464 const float* source_depth_ptr = (
const float*)&depth_int_msg->data[(top_y * input_width + left_x) *
sizeof(float)];
467 const uint8_t* source_mask_ptr = &valid_mask_msg->data[(top_y * input_width + left_x) *
sizeof(uint8_t)];
470 const uint8_t* source_color_ptr = 0;
471 std::size_t source_color_y_step = 0;
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]);
479 const std::size_t right_frame_shift = crop_size * pix_size;
481 const std::size_t down_frame_shift = dest_y_step * crop_size;
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 +=
488 const float *depth_ptr = source_depth_ptr;
491 const uint8_t *color_ptr = source_color_ptr;
492 const uint8_t *mask_ptr = source_mask_ptr;
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;
498 for (x = left_x; x < width_x; ++x)
503 if (*depth_ptr == *depth_ptr)
505 depth_pix_low = std::min(std::max(0.0
f, (*depth_ptr /
max_depth_per_tile_) * (
float)(0xFF * 3)), (
float)(0xFF * 3));
515 uint8_t *mask_pix_ptr = out_depth_low_ptr + down_frame_shift;
519 memset(mask_pix_ptr, 0x00, pix_size);
524 memset(mask_pix_ptr, 0xFF, pix_size);
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));
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;
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));
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;
547 *out_color_ptr = *color_ptr; ++out_color_ptr; ++color_ptr;
549 *out_color_ptr = *color_ptr; ++out_color_ptr; ++color_ptr;
551 *out_color_ptr = *color_ptr; ++out_color_ptr; ++color_ptr;
566 sensor_msgs::ImagePtr mask_msg)
568 const std::size_t input_width = depth_msg->width;
569 const std::size_t input_height = depth_msg->height;
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);
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);
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];
593 float leftVal = -1.0f;
596 for (y = 0; y < input_height; ++y, depth_ptr += input_width, depth_int_ptr += input_width, mask_ptr += input_width)
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;
602 const float* in_depth_end_ptr = depth_ptr + input_width;
604 while (in_depth_ptr < in_depth_end_ptr)
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))
619 if (in_depth_ptr < in_depth_end_ptr)
621 rightVal = *in_depth_ptr;
629 if (isnan(leftVal) || (leftVal < 0.0f))
632 float incVal = (rightVal - leftVal) / (
float)len;
633 float fillVal = leftVal;
634 const float* fill_ptr;
636 for (fill_ptr = last_valid_pix_ptr; fill_ptr < in_depth_ptr; ++fill_ptr)
639 *out_depth_int_ptr = fillVal;
643 *out_mask_ptr = 0xFF; ++out_mask_ptr;
654 leftVal = *in_depth_ptr;
656 *out_depth_int_ptr = *in_depth_ptr;
659 *out_mask_ptr = 0; ++out_mask_ptr;
ros::Subscriber camera_info_sub_
void subscribe(std::string &depth_topic, std::string &color_topic)
ros::Subscriber cloud_sub_
void subscribeCloud(std::string &cloud_topic)
void cloudToDepth(const sensor_msgs::PointCloud2 &cloud_msg, sensor_msgs::ImagePtr depth_msg, sensor_msgs::ImagePtr color_msg)
float max_depth_per_tile_
std::string camera_frame_id_
tf::TransformListener tf_listener_
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual ~DepthCloudEncoder()
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)
std::string camera_info_topic_
std::string depthmap_topic_
TFSIMD_FORCE_INLINE const tfScalar & y() const
void cloudCB(const sensor_msgs::PointCloud2 &cloud_msg)
uint32_t getNumSubscribers() const
void publish(const sensor_msgs::Image &message) const
bool connectivityExceptionFlag
message_filters::Synchronizer< SyncPolicyDepthColor > SynchronizerDepthColor
bool param(const std::string ¶m_name, T ¶m_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)
boost::mutex connect_mutex_
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)
std::string rgb_image_topic_
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)
std::string depth_source_