depth_image_error_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: C++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
38 #include <cv_bridge/cv_bridge.h>
40 
41 namespace jsk_pcl_ros_utils
42 {
44  {
45  ConnectionBasedNodelet::onInit();
46  pnh_->param("approximate_sync", approximate_sync_, false);
47  depth_error_publisher_ = advertise<jsk_recognition_msgs::DepthErrorResult>(*pnh_, "output", 1);
48  }
49 
51  {
52  sub_image_.subscribe(*pnh_, "image", 1);
53  sub_point_.subscribe(*pnh_, "point", 1);
54  sub_camera_info_.subscribe(*pnh_, "camera_info", 1);
55  if (approximate_sync_) {
56  async_ = boost::make_shared<message_filters::Synchronizer<ASyncPolicy> >(1000);
58  async_->registerCallback(boost::bind(&DepthImageError::calcError,
59  this, _1, _2, _3));
60  }
61  else {
62  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(1000);
64  sync_->registerCallback(boost::bind(&DepthImageError::calcError,
65  this, _1, _2, _3));
66  }
67  }
68 
70  {
73  }
74 
75 
76  void DepthImageError::calcError(const sensor_msgs::Image::ConstPtr& depth_image,
77  const geometry_msgs::PointStamped::ConstPtr& uv_point,
78  const sensor_msgs::CameraInfo::ConstPtr& camera_info)
79  {
80  cv_bridge::CvImagePtr cv_ptr;
82  cv::Mat cv_depth_image = cv_ptr->image;
83  double depth_from_depth_sensor = cv_depth_image.at<float>((int)uv_point->point.y, (int)uv_point->point.x);
84  NODELET_INFO("timestamp diff is %f", (depth_image->header.stamp - uv_point->header.stamp).toSec());
85  NODELET_INFO("(u, v) = (%d, %d)", (int)uv_point->point.x, (int)uv_point->point.y);
86  NODELET_INFO("(z, d) = (%f, %f)", uv_point->point.z, depth_from_depth_sensor);
87  if (! isnan(depth_from_depth_sensor)) {
88  jsk_recognition_msgs::DepthErrorResult result;
89  result.header.frame_id = depth_image->header.frame_id;
90  result.header.stamp = depth_image->header.stamp;
91  result.u = (int)uv_point->point.x;
92  result.v = (int)uv_point->point.y;
93  result.center_u = camera_info->P[2];
94  result.center_v = camera_info->P[6];
95  result.true_depth = uv_point->point.z;
96  result.observed_depth = depth_from_depth_sensor;
98  }
99  }
100 }
101 
void publish(const boost::shared_ptr< M > &message) const
virtual void calcError(const sensor_msgs::Image::ConstPtr &depth_image, const geometry_msgs::PointStamped::ConstPtr &uv_point, const sensor_msgs::CameraInfo::ConstPtr &camera_info)
message_filters::Subscriber< sensor_msgs::Image > sub_image_
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > async_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
boost::shared_ptr< ros::NodeHandle > pnh_
const std::string TYPE_32FC1
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::DepthImageError, nodelet::Nodelet)
#define NODELET_INFO(...)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
message_filters::Subscriber< geometry_msgs::PointStamped > sub_point_


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:15