register.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 #include <ros/ros.h>
35 #include <nodelet/nodelet.h>
41 #include <tf2_ros/buffer.h>
45 #include <Eigen/Geometry>
48 
49 namespace depth_image_proc {
50 
51 using namespace message_filters::sync_policies;
53 
54 class RegisterNodelet : public nodelet::Nodelet
55 {
56  ros::NodeHandlePtr nh_depth_, nh_rgb_;
58 
59  // Subscriptions
60  image_transport::SubscriberFilter sub_depth_image_;
61  message_filters::Subscriber<sensor_msgs::CameraInfo> sub_depth_info_, sub_rgb_info_;
65  typedef message_filters::Synchronizer<SyncPolicy> Synchronizer;
67 
68  // Publications
69  boost::mutex connect_mutex_;
70  image_transport::CameraPublisher pub_registered_;
71 
72  image_geometry::PinholeCameraModel depth_model_, rgb_model_;
73 
74  // Parameters
75  bool fill_upsampling_holes_; // fills holes which occur due to upsampling by scaling each pixel to the target image scale (only takes effect on upsampling)
76  bool use_rgb_timestamp_; // use source time stamp from RGB camera
77 
78  virtual void onInit();
79 
80  void connectCb();
81 
82  void imageCb(const sensor_msgs::ImageConstPtr& depth_image_msg,
83  const sensor_msgs::CameraInfoConstPtr& depth_info_msg,
84  const sensor_msgs::CameraInfoConstPtr& rgb_info_msg);
85 
86  template<typename T>
87  void convert(const sensor_msgs::ImageConstPtr& depth_msg,
88  const sensor_msgs::ImagePtr& registered_msg,
89  const Eigen::Affine3d& depth_to_rgb);
90 };
91 
93 {
94  ros::NodeHandle& nh = getNodeHandle();
95  ros::NodeHandle& private_nh = getPrivateNodeHandle();
96  nh_depth_.reset( new ros::NodeHandle(nh, "depth") );
97  nh_rgb_.reset( new ros::NodeHandle(nh, "rgb") );
98  it_depth_.reset( new image_transport::ImageTransport(*nh_depth_) );
99  tf_buffer_.reset( new tf2_ros::Buffer );
100  tf_.reset( new tf2_ros::TransformListener(*tf_buffer_) );
101 
102  // Read parameters
103  int queue_size;
104  private_nh.param("queue_size", queue_size, 5);
105  private_nh.param("fill_upsampling_holes", fill_upsampling_holes_, false);
106  private_nh.param("use_rgb_timestamp", use_rgb_timestamp_, false);
107 
108  // Synchronize inputs. Topic subscriptions happen on demand in the connection callback.
109  sync_.reset( new Synchronizer(SyncPolicy(queue_size), sub_depth_image_, sub_depth_info_, sub_rgb_info_) );
110  sync_->registerCallback(boost::bind(&RegisterNodelet::imageCb, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
111 
112  // Monitor whether anyone is subscribed to the output
113  image_transport::ImageTransport it_depth_reg(ros::NodeHandle(nh, "depth_registered"));
114  image_transport::SubscriberStatusCallback image_connect_cb = boost::bind(&RegisterNodelet::connectCb, this);
115  ros::SubscriberStatusCallback info_connect_cb = boost::bind(&RegisterNodelet::connectCb, this);
116  // Make sure we don't enter connectCb() between advertising and assigning to pub_registered_
117  boost::lock_guard<boost::mutex> lock(connect_mutex_);
118  pub_registered_ = it_depth_reg.advertiseCamera("image_rect", 1,
119  image_connect_cb, image_connect_cb,
120  info_connect_cb, info_connect_cb);
121 }
122 
123 // Handles (un)subscribing when clients (un)subscribe
125 {
126  boost::lock_guard<boost::mutex> lock(connect_mutex_);
127  if (pub_registered_.getNumSubscribers() == 0)
128  {
129  sub_depth_image_.unsubscribe();
130  sub_depth_info_ .unsubscribe();
131  sub_rgb_info_ .unsubscribe();
132  }
133  else if (!sub_depth_image_.getSubscriber())
134  {
135  image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
136  sub_depth_image_.subscribe(*it_depth_, "image_rect", 1, hints);
137  sub_depth_info_ .subscribe(*nh_depth_, "camera_info", 1);
138  sub_rgb_info_ .subscribe(*nh_rgb_, "camera_info", 1);
139  }
140 }
141 
142 void RegisterNodelet::imageCb(const sensor_msgs::ImageConstPtr& depth_image_msg,
143  const sensor_msgs::CameraInfoConstPtr& depth_info_msg,
144  const sensor_msgs::CameraInfoConstPtr& rgb_info_msg)
145 {
146  // Update camera models - these take binning & ROI into account
147  depth_model_.fromCameraInfo(depth_info_msg);
148  rgb_model_ .fromCameraInfo(rgb_info_msg);
149 
150  // Query tf2 for transform from (X,Y,Z) in depth camera frame to RGB camera frame
151  Eigen::Affine3d depth_to_rgb;
152  try
153  {
154  geometry_msgs::TransformStamped transform = tf_buffer_->lookupTransform (
155  rgb_info_msg->header.frame_id, depth_info_msg->header.frame_id,
156  depth_info_msg->header.stamp);
157 
158  tf::transformMsgToEigen(transform.transform, depth_to_rgb);
159  }
160  catch (tf2::TransformException& ex)
161  {
162  NODELET_WARN_THROTTLE(2, "TF2 exception:\n%s", ex.what());
163  return;
166  }
167 
168  // Allocate registered depth image
169  sensor_msgs::ImagePtr registered_msg( new sensor_msgs::Image );
170  registered_msg->header.stamp = use_rgb_timestamp_ ? rgb_info_msg->header.stamp : depth_image_msg->header.stamp;
171  registered_msg->header.frame_id = rgb_info_msg->header.frame_id;
172  registered_msg->encoding = depth_image_msg->encoding;
173 
174  cv::Size resolution = rgb_model_.reducedResolution();
175  registered_msg->height = resolution.height;
176  registered_msg->width = resolution.width;
177  // step and data set in convert(), depend on depth data type
178 
179  if (depth_image_msg->encoding == enc::TYPE_16UC1)
180  {
181  convert<uint16_t>(depth_image_msg, registered_msg, depth_to_rgb);
182  }
183  else if (depth_image_msg->encoding == enc::TYPE_32FC1)
184  {
185  convert<float>(depth_image_msg, registered_msg, depth_to_rgb);
186  }
187  else
188  {
189  NODELET_ERROR_THROTTLE(5, "Depth image has unsupported encoding [%s]", depth_image_msg->encoding.c_str());
190  return;
191  }
192 
193  // Registered camera info is the same as the RGB info, but uses the depth timestamp
194  sensor_msgs::CameraInfoPtr registered_info_msg( new sensor_msgs::CameraInfo(*rgb_info_msg) );
195  registered_info_msg->header.stamp = registered_msg->header.stamp;
196 
197  pub_registered_.publish(registered_msg, registered_info_msg);
198 }
199 
200 template<typename T>
201 void RegisterNodelet::convert(const sensor_msgs::ImageConstPtr& depth_msg,
202  const sensor_msgs::ImagePtr& registered_msg,
203  const Eigen::Affine3d& depth_to_rgb)
204 {
205  // Allocate memory for registered depth image
206  registered_msg->step = registered_msg->width * sizeof(T);
207  registered_msg->data.resize( registered_msg->height * registered_msg->step );
208  // data is already zero-filled in the uint16 case, but for floats we want to initialize everything to NaN.
209  DepthTraits<T>::initializeBuffer(registered_msg->data);
210 
211  // Extract all the parameters we need
212  double inv_depth_fx = 1.0 / depth_model_.fx();
213  double inv_depth_fy = 1.0 / depth_model_.fy();
214  double depth_cx = depth_model_.cx(), depth_cy = depth_model_.cy();
215  double depth_Tx = depth_model_.Tx(), depth_Ty = depth_model_.Ty();
216  double rgb_fx = rgb_model_.fx(), rgb_fy = rgb_model_.fy();
217  double rgb_cx = rgb_model_.cx(), rgb_cy = rgb_model_.cy();
218  double rgb_Tx = rgb_model_.Tx(), rgb_Ty = rgb_model_.Ty();
219 
220  // Transform the depth values into the RGB frame
222  const T* depth_row = reinterpret_cast<const T*>(&depth_msg->data[0]);
223  int row_step = depth_msg->step / sizeof(T);
224  T* registered_data = reinterpret_cast<T*>(&registered_msg->data[0]);
225  int raw_index = 0;
226  for (unsigned v = 0; v < depth_msg->height; ++v, depth_row += row_step)
227  {
228  for (unsigned u = 0; u < depth_msg->width; ++u, ++raw_index)
229  {
230  T raw_depth = depth_row[u];
231  if (!DepthTraits<T>::valid(raw_depth))
232  continue;
233 
234  double depth = DepthTraits<T>::toMeters(raw_depth);
235 
236  if (fill_upsampling_holes_ == false)
237  {
239  // Reproject (u,v,Z) to (X,Y,Z,1) in depth camera frame
240  Eigen::Vector4d xyz_depth;
241  xyz_depth << ((u - depth_cx)*depth - depth_Tx) * inv_depth_fx,
242  ((v - depth_cy)*depth - depth_Ty) * inv_depth_fy,
243  depth,
244  1;
245 
246  // Transform to RGB camera frame
247  Eigen::Vector4d xyz_rgb = depth_to_rgb * xyz_depth;
248 
249  // Project to (u,v) in RGB image
250  double inv_Z = 1.0 / xyz_rgb.z();
251  int u_rgb = (rgb_fx*xyz_rgb.x() + rgb_Tx)*inv_Z + rgb_cx + 0.5;
252  int v_rgb = (rgb_fy*xyz_rgb.y() + rgb_Ty)*inv_Z + rgb_cy + 0.5;
253 
254  if (u_rgb < 0 || u_rgb >= (int)registered_msg->width ||
255  v_rgb < 0 || v_rgb >= (int)registered_msg->height)
256  continue;
257 
258  T& reg_depth = registered_data[v_rgb*registered_msg->width + u_rgb];
259  T new_depth = DepthTraits<T>::fromMeters(xyz_rgb.z());
260  // Validity and Z-buffer checks
261  if (!DepthTraits<T>::valid(reg_depth) || reg_depth > new_depth)
262  reg_depth = new_depth;
263  }
264  else
265  {
266  // Reproject (u,v,Z) to (X,Y,Z,1) in depth camera frame
267  Eigen::Vector4d xyz_depth_1, xyz_depth_2;
268  xyz_depth_1 << ((u-0.5f - depth_cx)*depth - depth_Tx) * inv_depth_fx,
269  ((v-0.5f - depth_cy)*depth - depth_Ty) * inv_depth_fy,
270  depth,
271  1;
272  xyz_depth_2 << ((u+0.5f - depth_cx)*depth - depth_Tx) * inv_depth_fx,
273  ((v+0.5f - depth_cy)*depth - depth_Ty) * inv_depth_fy,
274  depth,
275  1;
276 
277  // Transform to RGB camera frame
278  Eigen::Vector4d xyz_rgb_1 = depth_to_rgb * xyz_depth_1;
279  Eigen::Vector4d xyz_rgb_2 = depth_to_rgb * xyz_depth_2;
280 
281  // Project to (u,v) in RGB image
282  double inv_Z = 1.0 / xyz_rgb_1.z();
283  int u_rgb_1 = (rgb_fx*xyz_rgb_1.x() + rgb_Tx)*inv_Z + rgb_cx + 0.5;
284  int v_rgb_1 = (rgb_fy*xyz_rgb_1.y() + rgb_Ty)*inv_Z + rgb_cy + 0.5;
285  inv_Z = 1.0 / xyz_rgb_2.z();
286  int u_rgb_2 = (rgb_fx*xyz_rgb_2.x() + rgb_Tx)*inv_Z + rgb_cx + 0.5;
287  int v_rgb_2 = (rgb_fy*xyz_rgb_2.y() + rgb_Ty)*inv_Z + rgb_cy + 0.5;
288 
289  if (u_rgb_1 < 0 || u_rgb_2 >= (int)registered_msg->width ||
290  v_rgb_1 < 0 || v_rgb_2 >= (int)registered_msg->height)
291  continue;
292 
293  for (int nv=v_rgb_1; nv<=v_rgb_2; ++nv)
294  {
295  for (int nu=u_rgb_1; nu<=u_rgb_2; ++nu)
296  {
297  T& reg_depth = registered_data[nv*registered_msg->width + nu];
298  T new_depth = DepthTraits<T>::fromMeters(0.5*(xyz_rgb_1.z()+xyz_rgb_2.z()));
299  // Validity and Z-buffer checks
300  if (!DepthTraits<T>::valid(reg_depth) || reg_depth > new_depth)
301  reg_depth = new_depth;
302  }
303  }
304  }
305  }
306  }
307 }
308 
309 } // namespace depth_image_proc
310 
311 // Register as nodelet
image_transport::SubscriberFilter
sensor_msgs::image_encodings
depth_traits.h
image_encodings.h
image_transport::ImageTransport
message_filters::Synchronizer
boost::shared_ptr< NodeHandle >
pinhole_camera_model.h
NODELET_ERROR_THROTTLE
#define NODELET_ERROR_THROTTLE(rate,...)
ros.h
ros::TransportHints
buffer.h
depth_image_proc::DepthTraits
Definition: depth_traits.h:78
ros::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
NODELET_WARN_THROTTLE
#define NODELET_WARN_THROTTLE(rate,...)
message_filters::Subscriber< sensor_msgs::CameraInfo >
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(depth_image_proc::RegisterNodelet, nodelet::Nodelet)
depth_image_proc::RegisterNodelet::imageCb
void imageCb(const sensor_msgs::ImageConstPtr &depth_image_msg, const sensor_msgs::CameraInfoConstPtr &depth_info_msg, const sensor_msgs::CameraInfoConstPtr &rgb_info_msg)
Definition: register.cpp:174
depth_image_proc::RegisterNodelet::convert
void convert(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImagePtr &registered_msg, const Eigen::Affine3d &depth_to_rgb)
Definition: register.cpp:233
tf2_ros::TransformListener
depth_image_proc::convert
void convert(const sensor_msgs::ImageConstPtr &depth_msg, PointCloud::Ptr &cloud_msg, const image_geometry::PinholeCameraModel &model, double range_max=0.0)
Definition: depth_conversions.h:82
message_filters::sync_policies::ApproximateTime
depth_image_proc::RegisterNodelet::onInit
virtual void onInit()
Definition: register.cpp:124
subscriber_filter.h
subscriber.h
eigen_msg.h
image_transport::CameraPublisher
tf2_ros::Buffer
tf::transformMsgToEigen
void transformMsgToEigen(const geometry_msgs::Transform &m, Eigen::Affine3d &e)
depth_image_proc::SyncPolicy
ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
Definition: point_cloud_xyzi_radial.cpp:85
depth_image_proc
Definition: depth_conversions.h:44
image_transport.h
depth_image_proc::RegisterNodelet
Definition: register.cpp:86
transform_listener.h
message_filters::sync_policies
nodelet::Nodelet
image_geometry::PinholeCameraModel
depth_image_proc::RegisterNodelet::connectCb
void connectCb()
Definition: register.cpp:156
nodelet.h
class_list_macros.hpp
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
synchronizer.h
image_transport::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
approximate_time.h
image_transport::TransportHints
tf2::TransformException
ros::NodeHandle


depth_image_proc
Author(s): Patrick Mihelich
autogenerated on Wed Jan 24 2024 03:57:15