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/or 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  onInitPostProcess();
49  }
50 
52  // message_filters::Synchronizer needs to be called reset
53  // before message_filters::Subscriber is freed.
54  // Calling reset fixes the following error on shutdown of the nodelet:
55  // terminate called after throwing an instance of
56  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
57  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
58  // Also see https://github.com/ros/ros_comm/issues/720 .
59  sync_.reset();
60  async_.reset();
61  }
62 
64  {
65  sub_image_.subscribe(*pnh_, "image", 1);
66  sub_point_.subscribe(*pnh_, "point", 1);
67  sub_camera_info_.subscribe(*pnh_, "camera_info", 1);
68  if (approximate_sync_) {
69  async_ = boost::make_shared<message_filters::Synchronizer<ASyncPolicy> >(1000);
71  async_->registerCallback(boost::bind(&DepthImageError::calcError,
72  this, _1, _2, _3));
73  }
74  else {
75  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(1000);
77  sync_->registerCallback(boost::bind(&DepthImageError::calcError,
78  this, _1, _2, _3));
79  }
80  }
81 
83  {
86  }
87 
88 
89  void DepthImageError::calcError(const sensor_msgs::Image::ConstPtr& depth_image,
90  const geometry_msgs::PointStamped::ConstPtr& uv_point,
91  const sensor_msgs::CameraInfo::ConstPtr& camera_info)
92  {
93  cv_bridge::CvImagePtr cv_ptr;
95  cv::Mat cv_depth_image = cv_ptr->image;
96  double depth_from_depth_sensor = cv_depth_image.at<float>((int)uv_point->point.y, (int)uv_point->point.x);
97  NODELET_INFO("timestamp diff is %f", (depth_image->header.stamp - uv_point->header.stamp).toSec());
98  NODELET_INFO("(u, v) = (%d, %d)", (int)uv_point->point.x, (int)uv_point->point.y);
99  NODELET_INFO("(z, d) = (%f, %f)", uv_point->point.z, depth_from_depth_sensor);
100  if (! isnan(depth_from_depth_sensor)) {
101  jsk_recognition_msgs::DepthErrorResult result;
102  result.header.frame_id = depth_image->header.frame_id;
103  result.header.stamp = depth_image->header.stamp;
104  result.u = (int)uv_point->point.x;
105  result.v = (int)uv_point->point.y;
106  result.center_u = camera_info->P[2];
107  result.center_v = camera_info->P[6];
108  result.true_depth = uv_point->point.z;
109  result.observed_depth = depth_from_depth_sensor;
111  }
112  }
113 }
114 
depth_image_error.h
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
jsk_pcl_ros_utils::DepthImageError::async_
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > async_
Definition: depth_image_error.h:145
image_encodings.h
boost::shared_ptr
jsk_pcl_ros_utils::DepthImageError::approximate_sync_
bool approximate_sync_
Definition: depth_image_error.h:147
jsk_pcl_ros_utils::DepthImageError::~DepthImageError
virtual ~DepthImageError()
Definition: depth_image_error_nodelet.cpp:83
jsk_pcl_ros_utils::DepthImageError::sub_point_
message_filters::Subscriber< geometry_msgs::PointStamped > sub_point_
Definition: depth_image_error.h:143
jsk_pcl_ros_utils::DepthImageError::subscribe
virtual void subscribe()
Definition: depth_image_error_nodelet.cpp:95
jsk_pcl_ros_utils::DepthImageError::depth_error_publisher_
ros::Publisher depth_error_publisher_
Definition: depth_image_error.h:133
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_pcl_ros_utils::DepthImageError::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: depth_image_error.h:146
class_list_macros.h
jsk_pcl_ros_utils::DepthImageError::onInit
virtual void onInit()
Definition: depth_image_error_nodelet.cpp:75
jsk_pcl_ros_utils::DepthImageError::unsubscribe
virtual void unsubscribe()
Definition: depth_image_error_nodelet.cpp:114
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
jsk_pcl_ros_utils::DepthImageError::sub_image_
message_filters::Subscriber< sensor_msgs::Image > sub_image_
Definition: depth_image_error.h:142
message_filters::Subscriber::subscribe
void subscribe()
NODELET_INFO
#define NODELET_INFO(...)
nodelet::Nodelet
sensor_msgs::image_encodings::TYPE_32FC1
const std::string TYPE_32FC1
cv_bridge.h
jsk_pcl_ros_utils::DepthImageError::calcError
virtual void calcError(const sensor_msgs::Image::ConstPtr &depth_image, const geometry_msgs::PointStamped::ConstPtr &uv_point, const sensor_msgs::CameraInfo::ConstPtr &camera_info)
Definition: depth_image_error_nodelet.cpp:121
jsk_pcl_ros_utils::DepthImageError::sub_camera_info_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
Definition: depth_image_error.h:144
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::DepthImageError, nodelet::Nodelet)
jsk_pcl_ros_utils::DepthImageError
Definition: depth_image_error.h:88


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43