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 
55 {
58 
59  // Subscriptions
67 
68  // Publications
69  boost::mutex connect_mutex_;
71 
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 
77  virtual void onInit();
78 
79  void connectCb();
80 
81  void imageCb(const sensor_msgs::ImageConstPtr& depth_image_msg,
82  const sensor_msgs::CameraInfoConstPtr& depth_info_msg,
83  const sensor_msgs::CameraInfoConstPtr& rgb_info_msg);
84 
85  template<typename T>
86  void convert(const sensor_msgs::ImageConstPtr& depth_msg,
87  const sensor_msgs::ImagePtr& registered_msg,
88  const Eigen::Affine3d& depth_to_rgb);
89 };
90 
92 {
93  ros::NodeHandle& nh = getNodeHandle();
94  ros::NodeHandle& private_nh = getPrivateNodeHandle();
95  nh_depth_.reset( new ros::NodeHandle(nh, "depth") );
96  nh_rgb_.reset( new ros::NodeHandle(nh, "rgb") );
97  it_depth_.reset( new image_transport::ImageTransport(*nh_depth_) );
98  tf_buffer_.reset( new tf2_ros::Buffer );
99  tf_.reset( new tf2_ros::TransformListener(*tf_buffer_) );
100 
101  // Read parameters
102  int queue_size;
103  private_nh.param("queue_size", queue_size, 5);
104  private_nh.param("fill_upsampling_holes", fill_upsampling_holes_, false);
105 
106  // Synchronize inputs. Topic subscriptions happen on demand in the connection callback.
107  sync_.reset( new Synchronizer(SyncPolicy(queue_size), sub_depth_image_, sub_depth_info_, sub_rgb_info_) );
108  sync_->registerCallback(boost::bind(&RegisterNodelet::imageCb, this, _1, _2, _3));
109 
110  // Monitor whether anyone is subscribed to the output
111  image_transport::ImageTransport it_depth_reg(ros::NodeHandle(nh, "depth_registered"));
112  image_transport::SubscriberStatusCallback image_connect_cb = boost::bind(&RegisterNodelet::connectCb, this);
113  ros::SubscriberStatusCallback info_connect_cb = boost::bind(&RegisterNodelet::connectCb, this);
114  // Make sure we don't enter connectCb() between advertising and assigning to pub_registered_
115  boost::lock_guard<boost::mutex> lock(connect_mutex_);
116  pub_registered_ = it_depth_reg.advertiseCamera("image_rect", 1,
117  image_connect_cb, image_connect_cb,
118  info_connect_cb, info_connect_cb);
119 }
120 
121 // Handles (un)subscribing when clients (un)subscribe
123 {
124  boost::lock_guard<boost::mutex> lock(connect_mutex_);
125  if (pub_registered_.getNumSubscribers() == 0)
126  {
127  sub_depth_image_.unsubscribe();
128  sub_depth_info_ .unsubscribe();
129  sub_rgb_info_ .unsubscribe();
130  }
131  else if (!sub_depth_image_.getSubscriber())
132  {
133  image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
134  sub_depth_image_.subscribe(*it_depth_, "image_rect", 1, hints);
135  sub_depth_info_ .subscribe(*nh_depth_, "camera_info", 1);
136  sub_rgb_info_ .subscribe(*nh_rgb_, "camera_info", 1);
137  }
138 }
139 
140 void RegisterNodelet::imageCb(const sensor_msgs::ImageConstPtr& depth_image_msg,
141  const sensor_msgs::CameraInfoConstPtr& depth_info_msg,
142  const sensor_msgs::CameraInfoConstPtr& rgb_info_msg)
143 {
144  // Update camera models - these take binning & ROI into account
145  depth_model_.fromCameraInfo(depth_info_msg);
146  rgb_model_ .fromCameraInfo(rgb_info_msg);
147 
148  // Query tf2 for transform from (X,Y,Z) in depth camera frame to RGB camera frame
149  Eigen::Affine3d depth_to_rgb;
150  try
151  {
152  geometry_msgs::TransformStamped transform = tf_buffer_->lookupTransform (
153  rgb_info_msg->header.frame_id, depth_info_msg->header.frame_id,
154  depth_info_msg->header.stamp);
155 
156  tf::transformMsgToEigen(transform.transform, depth_to_rgb);
157  }
158  catch (tf2::TransformException& ex)
159  {
160  NODELET_WARN_THROTTLE(2, "TF2 exception:\n%s", ex.what());
161  return;
164  }
165 
166  // Allocate registered depth image
167  sensor_msgs::ImagePtr registered_msg( new sensor_msgs::Image );
168  registered_msg->header.stamp = depth_image_msg->header.stamp;
169  registered_msg->header.frame_id = rgb_info_msg->header.frame_id;
170  registered_msg->encoding = depth_image_msg->encoding;
171 
172  cv::Size resolution = rgb_model_.reducedResolution();
173  registered_msg->height = resolution.height;
174  registered_msg->width = resolution.width;
175  // step and data set in convert(), depend on depth data type
176 
177  if (depth_image_msg->encoding == enc::TYPE_16UC1)
178  {
179  convert<uint16_t>(depth_image_msg, registered_msg, depth_to_rgb);
180  }
181  else if (depth_image_msg->encoding == enc::TYPE_32FC1)
182  {
183  convert<float>(depth_image_msg, registered_msg, depth_to_rgb);
184  }
185  else
186  {
187  NODELET_ERROR_THROTTLE(5, "Depth image has unsupported encoding [%s]", depth_image_msg->encoding.c_str());
188  return;
189  }
190 
191  // Registered camera info is the same as the RGB info, but uses the depth timestamp
192  sensor_msgs::CameraInfoPtr registered_info_msg( new sensor_msgs::CameraInfo(*rgb_info_msg) );
193  registered_info_msg->header.stamp = registered_msg->header.stamp;
194 
195  pub_registered_.publish(registered_msg, registered_info_msg);
196 }
197 
198 template<typename T>
199 void RegisterNodelet::convert(const sensor_msgs::ImageConstPtr& depth_msg,
200  const sensor_msgs::ImagePtr& registered_msg,
201  const Eigen::Affine3d& depth_to_rgb)
202 {
203  // Allocate memory for registered depth image
204  registered_msg->step = registered_msg->width * sizeof(T);
205  registered_msg->data.resize( registered_msg->height * registered_msg->step );
206  // data is already zero-filled in the uint16 case, but for floats we want to initialize everything to NaN.
207  DepthTraits<T>::initializeBuffer(registered_msg->data);
208 
209  // Extract all the parameters we need
210  double inv_depth_fx = 1.0 / depth_model_.fx();
211  double inv_depth_fy = 1.0 / depth_model_.fy();
212  double depth_cx = depth_model_.cx(), depth_cy = depth_model_.cy();
213  double depth_Tx = depth_model_.Tx(), depth_Ty = depth_model_.Ty();
214  double rgb_fx = rgb_model_.fx(), rgb_fy = rgb_model_.fy();
215  double rgb_cx = rgb_model_.cx(), rgb_cy = rgb_model_.cy();
216  double rgb_Tx = rgb_model_.Tx(), rgb_Ty = rgb_model_.Ty();
217 
218  // Transform the depth values into the RGB frame
220  const T* depth_row = reinterpret_cast<const T*>(&depth_msg->data[0]);
221  int row_step = depth_msg->step / sizeof(T);
222  T* registered_data = reinterpret_cast<T*>(&registered_msg->data[0]);
223  int raw_index = 0;
224  for (unsigned v = 0; v < depth_msg->height; ++v, depth_row += row_step)
225  {
226  for (unsigned u = 0; u < depth_msg->width; ++u, ++raw_index)
227  {
228  T raw_depth = depth_row[u];
229  if (!DepthTraits<T>::valid(raw_depth))
230  continue;
231 
232  double depth = DepthTraits<T>::toMeters(raw_depth);
233 
234  if (fill_upsampling_holes_ == false)
235  {
237  // Reproject (u,v,Z) to (X,Y,Z,1) in depth camera frame
238  Eigen::Vector4d xyz_depth;
239  xyz_depth << ((u - depth_cx)*depth - depth_Tx) * inv_depth_fx,
240  ((v - depth_cy)*depth - depth_Ty) * inv_depth_fy,
241  depth,
242  1;
243 
244  // Transform to RGB camera frame
245  Eigen::Vector4d xyz_rgb = depth_to_rgb * xyz_depth;
246 
247  // Project to (u,v) in RGB image
248  double inv_Z = 1.0 / xyz_rgb.z();
249  int u_rgb = (rgb_fx*xyz_rgb.x() + rgb_Tx)*inv_Z + rgb_cx + 0.5;
250  int v_rgb = (rgb_fy*xyz_rgb.y() + rgb_Ty)*inv_Z + rgb_cy + 0.5;
251 
252  if (u_rgb < 0 || u_rgb >= (int)registered_msg->width ||
253  v_rgb < 0 || v_rgb >= (int)registered_msg->height)
254  continue;
255 
256  T& reg_depth = registered_data[v_rgb*registered_msg->width + u_rgb];
257  T new_depth = DepthTraits<T>::fromMeters(xyz_rgb.z());
258  // Validity and Z-buffer checks
259  if (!DepthTraits<T>::valid(reg_depth) || reg_depth > new_depth)
260  reg_depth = new_depth;
261  }
262  else
263  {
264  // Reproject (u,v,Z) to (X,Y,Z,1) in depth camera frame
265  Eigen::Vector4d xyz_depth_1, xyz_depth_2;
266  xyz_depth_1 << ((u-0.5f - depth_cx)*depth - depth_Tx) * inv_depth_fx,
267  ((v-0.5f - depth_cy)*depth - depth_Ty) * inv_depth_fy,
268  depth,
269  1;
270  xyz_depth_2 << ((u+0.5f - depth_cx)*depth - depth_Tx) * inv_depth_fx,
271  ((v+0.5f - depth_cy)*depth - depth_Ty) * inv_depth_fy,
272  depth,
273  1;
274 
275  // Transform to RGB camera frame
276  Eigen::Vector4d xyz_rgb_1 = depth_to_rgb * xyz_depth_1;
277  Eigen::Vector4d xyz_rgb_2 = depth_to_rgb * xyz_depth_2;
278 
279  // Project to (u,v) in RGB image
280  double inv_Z = 1.0 / xyz_rgb_1.z();
281  int u_rgb_1 = (rgb_fx*xyz_rgb_1.x() + rgb_Tx)*inv_Z + rgb_cx + 0.5;
282  int v_rgb_1 = (rgb_fy*xyz_rgb_1.y() + rgb_Ty)*inv_Z + rgb_cy + 0.5;
283  inv_Z = 1.0 / xyz_rgb_2.z();
284  int u_rgb_2 = (rgb_fx*xyz_rgb_2.x() + rgb_Tx)*inv_Z + rgb_cx + 0.5;
285  int v_rgb_2 = (rgb_fy*xyz_rgb_2.y() + rgb_Ty)*inv_Z + rgb_cy + 0.5;
286 
287  if (u_rgb_1 < 0 || u_rgb_2 >= (int)registered_msg->width ||
288  v_rgb_1 < 0 || v_rgb_2 >= (int)registered_msg->height)
289  continue;
290 
291  for (int nv=v_rgb_1; nv<=v_rgb_2; ++nv)
292  {
293  for (int nu=u_rgb_1; nu<=u_rgb_2; ++nu)
294  {
295  T& reg_depth = registered_data[nv*registered_msg->width + nu];
296  T new_depth = DepthTraits<T>::fromMeters(0.5*(xyz_rgb_1.z()+xyz_rgb_2.z()));
297  // Validity and Z-buffer checks
298  if (!DepthTraits<T>::valid(reg_depth) || reg_depth > new_depth)
299  reg_depth = new_depth;
300  }
301  }
302  }
303  }
304  }
305 }
306 
307 } // namespace depth_image_proc
308 
309 // Register as nodelet
void convert(const sensor_msgs::ImageConstPtr &depth_msg, PointCloud::Ptr &cloud_msg, const image_geometry::PinholeCameraModel &model, double range_max=0.0)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
boost::shared_ptr< Synchronizer > sync_
Definition: register.cpp:66
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_rgb_info_
Definition: register.cpp:61
ros::NodeHandlePtr nh_rgb_
Definition: register.cpp:56
#define NODELET_ERROR_THROTTLE(rate,...)
ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
boost::shared_ptr< image_transport::ImageTransport > it_depth_
Definition: register.cpp:57
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
boost::shared_ptr< tf2_ros::TransformListener > tf_
Definition: register.cpp:63
image_geometry::PinholeCameraModel rgb_model_
Definition: register.cpp:72
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define NODELET_WARN_THROTTLE(rate,...)
image_transport::SubscriberFilter sub_depth_image_
Definition: register.cpp:60
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:140
void transformMsgToEigen(const geometry_msgs::Transform &m, Eigen::Affine3d &e)
PLUGINLIB_EXPORT_CLASS(depth_image_proc::RegisterNodelet, nodelet::Nodelet)
void convert(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImagePtr &registered_msg, const Eigen::Affine3d &depth_to_rgb)
Definition: register.cpp:199
image_transport::CameraPublisher pub_registered_
Definition: register.cpp:70
boost::shared_ptr< tf2_ros::Buffer > tf_buffer_
Definition: register.cpp:62
ApproximateTime< sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > SyncPolicy
Definition: register.cpp:64
message_filters::Synchronizer< SyncPolicy > Synchronizer
Definition: register.cpp:65


depth_image_proc
Author(s): Patrick Mihelich
autogenerated on Wed Dec 7 2022 03:25:21