point_cloud_xyzi_radial.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>
43 #include <opencv2/calib3d/calib3d.hpp>
44 #include <boost/thread.hpp>
46 
48 
49 namespace depth_image_proc {
50 
51  using namespace message_filters::sync_policies;
54 
55  class PointCloudXyziRadialNodelet : public nodelet::Nodelet
56  {
57  ros::NodeHandlePtr intensity_nh_;
58 
59  // Subscriptions
61  image_transport::SubscriberFilter sub_depth_, sub_intensity_;
63 
64  int queue_size_;
65 
66  // Publications
67  boost::mutex connect_mutex_;
68  typedef sensor_msgs::PointCloud2 PointCloud;
69  ros::Publisher pub_point_cloud_;
70 
71 
72  typedef message_filters::Synchronizer<SyncPolicy> Synchronizer;
74 
75  std::vector<double> D_;
76  boost::array<double, 9> K_;
77 
78  int width_;
79  int height_;
80 
81  cv::Mat transform_;
82 
83  virtual void onInit();
84 
85  void connectCb();
86 
87  void imageCb(const sensor_msgs::ImageConstPtr& depth_msg,
88  const sensor_msgs::ImageConstPtr& intensity_msg_in,
89  const sensor_msgs::CameraInfoConstPtr& info_msg);
90 
91  // Handles float or uint16 depths
92  template<typename T>
93  void convert_depth(const sensor_msgs::ImageConstPtr& depth_msg, PointCloud::Ptr& cloud_msg);
94 
95  template<typename T>
96  void convert_intensity(const sensor_msgs::ImageConstPtr &inten_msg, PointCloud::Ptr& cloud_msg);
97 
98  cv::Mat initMatrix(cv::Mat cameraMatrix, cv::Mat distCoeffs, int width, int height, bool radial);
99 
100  };
101 
102  cv::Mat PointCloudXyziRadialNodelet::initMatrix(cv::Mat cameraMatrix, cv::Mat distCoeffs, int width, int height, bool radial)
103  {
104  int i,j;
105  int totalsize = width*height;
106  cv::Mat pixelVectors(1,totalsize,CV_32FC3);
107  cv::Mat dst(1,totalsize,CV_32FC3);
108 
109  cv::Mat sensorPoints(cv::Size(height,width), CV_32FC2);
110  cv::Mat undistortedSensorPoints(1,totalsize, CV_32FC2);
111 
112  std::vector<cv::Mat> ch;
113  for(j = 0; j < height; j++)
114  {
115  for(i = 0; i < width; i++)
116  {
117  cv::Vec2f &p = sensorPoints.at<cv::Vec2f>(i,j);
118  p[0] = i;
119  p[1] = j;
120  }
121  }
122 
123  sensorPoints = sensorPoints.reshape(2,1);
124 
125  cv::undistortPoints(sensorPoints, undistortedSensorPoints, cameraMatrix, distCoeffs);
126 
127  ch.push_back(undistortedSensorPoints);
128  ch.push_back(cv::Mat::ones(1,totalsize,CV_32FC1));
129  cv::merge(ch,pixelVectors);
130 
131  if(radial)
132  {
133  for(i = 0; i < totalsize; i++)
134  {
135  normalize(pixelVectors.at<cv::Vec3f>(i),
136  dst.at<cv::Vec3f>(i));
137  }
138  pixelVectors = dst;
139  }
140  return pixelVectors.reshape(3,width);
141  }
142 
143 
145  {
146  ros::NodeHandle& nh = getNodeHandle();
147  ros::NodeHandle& private_nh = getPrivateNodeHandle();
148 
149  intensity_nh_.reset( new ros::NodeHandle(nh, "intensity") );
150  ros::NodeHandle depth_nh(nh, "depth");
151  intensity_it_ .reset( new image_transport::ImageTransport(*intensity_nh_) );
152  depth_it_.reset( new image_transport::ImageTransport(depth_nh) );
153 
154  // Read parameters
155  private_nh.param("queue_size", queue_size_, 5);
156 
157  // Synchronize inputs. Topic subscriptions happen on demand in the connection callback.
158  sync_.reset( new Synchronizer(SyncPolicy(queue_size_), sub_depth_, sub_intensity_, sub_info_) );
159  sync_->registerCallback(boost::bind(&PointCloudXyziRadialNodelet::imageCb, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
160 
161  // Monitor whether anyone is subscribed to the output
162  ros::SubscriberStatusCallback connect_cb =
163  boost::bind(&PointCloudXyziRadialNodelet::connectCb, this);
164  // Make sure we don't enter connectCb() between advertising and assigning to pub_point_cloud_
165  boost::lock_guard<boost::mutex> lock(connect_mutex_);
166  pub_point_cloud_ = nh.advertise<PointCloud>("points", 20, connect_cb, connect_cb);
167  }
168 
169  // Handles (un)subscribing when clients (un)subscribe
171  {
172  boost::lock_guard<boost::mutex> lock(connect_mutex_);
173 
174  if (pub_point_cloud_.getNumSubscribers() == 0)
175  {
176  sub_depth_.unsubscribe();
177  sub_intensity_.unsubscribe();
178  sub_info_.unsubscribe();
179  }
180  else if (!sub_depth_.getSubscriber())
181  {
182  ros::NodeHandle& private_nh = getPrivateNodeHandle();
183  // parameter for depth_image_transport hint
184  std::string depth_image_transport_param = "depth_image_transport";
185 
186  // depth image can use different transport.(e.g. compressedDepth)
187  image_transport::TransportHints depth_hints("raw",ros::TransportHints(), private_nh, depth_image_transport_param);
188  sub_depth_.subscribe(*depth_it_, "image_raw", 5, depth_hints);
189 
190  // intensity uses normal ros transport hints.
191  image_transport::TransportHints hints("raw", ros::TransportHints(), private_nh);
192  sub_intensity_.subscribe(*intensity_it_, "image_raw", 5, hints);
193  sub_info_.subscribe(*intensity_nh_, "camera_info", 5);
194  }
195  }
196 
197  void PointCloudXyziRadialNodelet::imageCb(const sensor_msgs::ImageConstPtr& depth_msg,
198  const sensor_msgs::ImageConstPtr& intensity_msg,
199  const sensor_msgs::CameraInfoConstPtr& info_msg)
200  {
201  PointCloud::Ptr cloud_msg(new PointCloud);
202  cloud_msg->header = depth_msg->header;
203  cloud_msg->height = depth_msg->height;
204  cloud_msg->width = depth_msg->width;
205  cloud_msg->is_dense = false;
206  cloud_msg->is_bigendian = false;
207 
208  sensor_msgs::PointCloud2Modifier pcd_modifier(*cloud_msg);
209  pcd_modifier.setPointCloud2Fields(4,
210  "x", 1, sensor_msgs::PointField::FLOAT32,
211  "y", 1, sensor_msgs::PointField::FLOAT32,
212  "z", 1, sensor_msgs::PointField::FLOAT32,
213  "intensity", 1, sensor_msgs::PointField::FLOAT32);
214 
215 
216  if(info_msg->D != D_ || info_msg->K != K_ || width_ != info_msg->width ||
217  height_ != info_msg->height)
218  {
219  D_ = info_msg->D;
220  K_ = info_msg->K;
221  width_ = info_msg->width;
222  height_ = info_msg->height;
223  transform_ = initMatrix(cv::Mat_<double>(3, 3, &K_[0]),cv::Mat(D_),width_,height_,true);
224  }
225 
226  if (depth_msg->encoding == enc::TYPE_16UC1)
227  {
228  convert_depth<uint16_t>(depth_msg, cloud_msg);
229  }
230  else if (depth_msg->encoding == enc::TYPE_32FC1)
231  {
232  convert_depth<float>(depth_msg, cloud_msg);
233  }
234  else
235  {
236  NODELET_ERROR_THROTTLE(5, "Depth image has unsupported encoding [%s]", depth_msg->encoding.c_str());
237  return;
238  }
239 
240  if(intensity_msg->encoding == enc::TYPE_16UC1)
241  {
242  convert_intensity<uint16_t>(intensity_msg, cloud_msg);
243 
244  }
245  else if(intensity_msg->encoding == enc::MONO8)
246  {
247  convert_intensity<uint8_t>(intensity_msg, cloud_msg);
248  }
249  else if(intensity_msg->encoding == enc::TYPE_32FC1)
250  {
251  convert_intensity<float>(intensity_msg, cloud_msg);
252  }
253  else
254  {
255  NODELET_ERROR_THROTTLE(5, "Intensity image has unsupported encoding [%s]", intensity_msg->encoding.c_str());
256  return;
257  }
258 
259  pub_point_cloud_.publish (cloud_msg);
260  }
261 
262  template<typename T>
263  void PointCloudXyziRadialNodelet::convert_depth(const sensor_msgs::ImageConstPtr& depth_msg,
264  PointCloud::Ptr& cloud_msg)
265  {
266  // Combine unit conversion (if necessary) with scaling by focal length for computing (X,Y)
267  double unit_scaling = DepthTraits<T>::toMeters( T(1) );
268  float bad_point = std::numeric_limits<float>::quiet_NaN();
269 
270  sensor_msgs::PointCloud2Iterator<float> iter_x(*cloud_msg, "x");
271  sensor_msgs::PointCloud2Iterator<float> iter_y(*cloud_msg, "y");
272  sensor_msgs::PointCloud2Iterator<float> iter_z(*cloud_msg, "z");
273  const T* depth_row = reinterpret_cast<const T*>(&depth_msg->data[0]);
274 
275  int row_step = depth_msg->step / sizeof(T);
276  for (int v = 0; v < (int)cloud_msg->height; ++v, depth_row += row_step)
277  {
278  for (int u = 0; u < (int)cloud_msg->width; ++u, ++iter_x, ++iter_y, ++iter_z)
279  {
280  T depth = depth_row[u];
281 
282  // Missing points denoted by NaNs
283  if (!DepthTraits<T>::valid(depth))
284  {
285  *iter_x = *iter_y = *iter_z = bad_point;
286  continue;
287  }
288  const cv::Vec3f &cvPoint = transform_.at<cv::Vec3f>(u,v) * DepthTraits<T>::toMeters(depth);
289  // Fill in XYZ
290  *iter_x = cvPoint(0);
291  *iter_y = cvPoint(1);
292  *iter_z = cvPoint(2);
293  }
294  }
295  }
296 
297  template<typename T>
298  void PointCloudXyziRadialNodelet::convert_intensity(const sensor_msgs::ImageConstPtr& intensity_msg,
299  PointCloud::Ptr& cloud_msg)
300  {
301  sensor_msgs::PointCloud2Iterator<float> iter_i(*cloud_msg, "intensity");
302  const T* inten_row = reinterpret_cast<const T*>(&intensity_msg->data[0]);
303 
304  const int i_row_step = intensity_msg->step/sizeof(T);
305  for (int v = 0; v < (int)cloud_msg->height; ++v, inten_row += i_row_step)
306  {
307  for (int u = 0; u < (int)cloud_msg->width; ++u, ++iter_i)
308  {
309  *iter_i = inten_row[u];
310  }
311  }
312  }
313 
314 } // namespace depth_image_proc
315 
316 // Register as nodelet
image_transport::SubscriberFilter
sensor_msgs::image_encodings
point_cloud2_iterator.h
depth_traits.h
depth_image_proc::PointCloudXyziRadialNodelet
Definition: point_cloud_xyzi_radial.cpp:87
ros::Publisher
image_encodings.h
image_transport::ImageTransport
message_filters::Synchronizer
depth_image_proc::PointCloudXyziRadialNodelet::imageCb
void imageCb(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &intensity_msg_in, const sensor_msgs::CameraInfoConstPtr &info_msg)
Definition: point_cloud_xyzi_radial.cpp:229
boost::shared_ptr< NodeHandle >
depth_image_proc::PointCloudXyziRadialNodelet::onInit
virtual void onInit()
Definition: point_cloud_xyzi_radial.cpp:176
pinhole_camera_model.h
NODELET_ERROR_THROTTLE
#define NODELET_ERROR_THROTTLE(rate,...)
ros.h
ros::TransportHints
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(depth_image_proc::PointCloudXyziRadialNodelet, nodelet::Nodelet)
depth_image_proc::PointCloudXyziRadialNodelet::convert_intensity
void convert_intensity(const sensor_msgs::ImageConstPtr &inten_msg, PointCloud::Ptr &cloud_msg)
Definition: point_cloud_xyzi_radial.cpp:330
ros::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
message_filters::Subscriber< sensor_msgs::CameraInfo >
sensor_msgs::PointCloud2Iterator
subscriber_filter.h
subscriber.h
depth_image_proc::PointCloudXyziRadialNodelet::convert_depth
void convert_depth(const sensor_msgs::ImageConstPtr &depth_msg, PointCloud::Ptr &cloud_msg)
Definition: point_cloud_xyzi_radial.cpp:295
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
exact_time.h
depth_image_proc::PointCloud
sensor_msgs::PointCloud2 PointCloud
Definition: depth_conversions.h:78
message_filters::sync_policies
nodelet::Nodelet
nodelet.h
sensor_msgs::PointCloud2Modifier
class_list_macros.hpp
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
synchronizer.h
image_transport::TransportHints
depth_image_proc::initMatrix
cv::Mat initMatrix(cv::Mat cameraMatrix, cv::Mat distCoeffs, int width, int height, bool radial)
Definition: point_cloud_xyz_radial.cpp:114
message_filters::sync_policies::ExactTime
depth_image_proc::PointCloudXyziRadialNodelet::initMatrix
cv::Mat initMatrix(cv::Mat cameraMatrix, cv::Mat distCoeffs, int width, int height, bool radial)
Definition: point_cloud_xyzi_radial.cpp:134
ros::NodeHandle
depth_image_proc::PointCloudXyziRadialNodelet::connectCb
void connectCb()
Definition: point_cloud_xyzi_radial.cpp:202


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