point_cloud_xyz_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>
39 #include <opencv2/calib3d/calib3d.hpp>
40 #include <boost/thread.hpp>
42 
44 
45 namespace depth_image_proc {
46 
48 
49  class PointCloudXyzRadialNodelet : public nodelet::Nodelet
50  {
51  // Subscriptions
54  int queue_size_;
55 
56  // Publications
57  boost::mutex connect_mutex_;
58  typedef sensor_msgs::PointCloud2 PointCloud;
60 
61 
62  std::vector<double> D_;
63  boost::array<double, 9> K_;
64 
65  int width_;
66  int height_;
67 
68  cv::Mat binned;
69 
70  virtual void onInit();
71 
72  void connectCb();
73 
74  void depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
75  const sensor_msgs::CameraInfoConstPtr& info_msg);
76 
77  // Handles float or uint16 depths
78  template<typename T>
79  void convert(const sensor_msgs::ImageConstPtr& depth_msg, PointCloud::Ptr& cloud_msg);
80  };
81 
82  cv::Mat initMatrix(cv::Mat cameraMatrix, cv::Mat distCoeffs, int width, int height, bool radial)
83  {
84  int i,j;
85  int totalsize = width*height;
86  cv::Mat pixelVectors(1,totalsize,CV_32FC3);
87  cv::Mat dst(1,totalsize,CV_32FC3);
88 
89  cv::Mat sensorPoints(cv::Size(height,width), CV_32FC2);
90  cv::Mat undistortedSensorPoints(1,totalsize, CV_32FC2);
91 
92  std::vector<cv::Mat> ch;
93  for(j = 0; j < height; j++)
94  {
95  for(i = 0; i < width; i++)
96  {
97  cv::Vec2f &p = sensorPoints.at<cv::Vec2f>(i,j);
98  p[0] = i;
99  p[1] = j;
100  }
101  }
102 
103  sensorPoints = sensorPoints.reshape(2,1);
104 
105  cv::undistortPoints(sensorPoints, undistortedSensorPoints, cameraMatrix, distCoeffs);
106 
107  ch.push_back(undistortedSensorPoints);
108  ch.push_back(cv::Mat::ones(1,totalsize,CV_32FC1));
109  cv::merge(ch,pixelVectors);
110 
111  if(radial)
112  {
113  for(i = 0; i < totalsize; i++)
114  {
115  normalize(pixelVectors.at<cv::Vec3f>(i),
116  dst.at<cv::Vec3f>(i));
117  }
118  pixelVectors = dst;
119  }
120  return pixelVectors.reshape(3,width);
121  }
122 
123 
125  {
128  it_.reset(new image_transport::ImageTransport(nh));
129 
130  // Read parameters
131  private_nh.param("queue_size", queue_size_, 5);
132 
133  // Monitor whether anyone is subscribed to the output
134  ros::SubscriberStatusCallback connect_cb =
135  boost::bind(&PointCloudXyzRadialNodelet::connectCb, this);
136  // Make sure we don't enter connectCb() between advertising and assigning to pub_point_cloud_
137  boost::lock_guard<boost::mutex> lock(connect_mutex_);
138  pub_point_cloud_ = nh.advertise<PointCloud>("points", 1, connect_cb, connect_cb);
139  }
140 
141  // Handles (un)subscribing when clients (un)subscribe
143  {
144  boost::lock_guard<boost::mutex> lock(connect_mutex_);
146  {
148  }
149  else if (!sub_depth_)
150  {
152  sub_depth_ = it_->subscribeCamera("image_raw",
153  queue_size_,
155  this, hints);
156  }
157  }
158 
159  void PointCloudXyzRadialNodelet::depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
160  const sensor_msgs::CameraInfoConstPtr& info_msg)
161  {
162  PointCloud::Ptr cloud_msg(new PointCloud);
163  cloud_msg->header = depth_msg->header;
164  cloud_msg->height = depth_msg->height;
165  cloud_msg->width = depth_msg->width;
166  cloud_msg->is_dense = false;
167  cloud_msg->is_bigendian = false;
168 
169  sensor_msgs::PointCloud2Modifier pcd_modifier(*cloud_msg);
170  pcd_modifier.setPointCloud2FieldsByString(1, "xyz");
171 
172  if(info_msg->D != D_ || info_msg->K != K_ || width_ != info_msg->width ||
173  height_ != info_msg->height)
174  {
175  D_ = info_msg->D;
176  K_ = info_msg->K;
177  width_ = info_msg->width;
178  height_ = info_msg->height;
179  binned = initMatrix(cv::Mat_<double>(3, 3, &K_[0]),cv::Mat(D_),width_,height_,true);
180  }
181 
182  if (depth_msg->encoding == enc::TYPE_16UC1)
183  {
184  convert<uint16_t>(depth_msg, cloud_msg);
185  }
186  else if (depth_msg->encoding == enc::TYPE_32FC1)
187  {
188  convert<float>(depth_msg, cloud_msg);
189  }
190  else
191  {
192  NODELET_ERROR_THROTTLE(5, "Depth image has unsupported encoding [%s]", depth_msg->encoding.c_str());
193  return;
194  }
195 
196  pub_point_cloud_.publish (cloud_msg);
197  }
198 
199  template<typename T>
200  void PointCloudXyzRadialNodelet::convert(const sensor_msgs::ImageConstPtr& depth_msg, PointCloud::Ptr& cloud_msg)
201  {
202  // Combine unit conversion (if necessary) with scaling by focal length for computing (X,Y)
203  double unit_scaling = DepthTraits<T>::toMeters( T(1) );
204  float bad_point = std::numeric_limits<float>::quiet_NaN();
205 
206  sensor_msgs::PointCloud2Iterator<float> iter_x(*cloud_msg, "x");
207  sensor_msgs::PointCloud2Iterator<float> iter_y(*cloud_msg, "y");
208  sensor_msgs::PointCloud2Iterator<float> iter_z(*cloud_msg, "z");
209  const T* depth_row = reinterpret_cast<const T*>(&depth_msg->data[0]);
210  int row_step = depth_msg->step / sizeof(T);
211  for (int v = 0; v < (int)cloud_msg->height; ++v, depth_row += row_step)
212  {
213  for (int u = 0; u < (int)cloud_msg->width; ++u, ++iter_x, ++iter_y, ++iter_z)
214  {
215  T depth = depth_row[u];
216 
217  // Missing points denoted by NaNs
218  if (!DepthTraits<T>::valid(depth))
219  {
220  *iter_x = *iter_y = *iter_z = bad_point;
221  continue;
222  }
223  const cv::Vec3f &cvPoint = binned.at<cv::Vec3f>(u,v) * DepthTraits<T>::toMeters(depth);
224  // Fill in XYZ
225  *iter_x = cvPoint(0);
226  *iter_y = cvPoint(1);
227  *iter_z = cvPoint(2);
228  }
229  }
230  }
231 
232 } // namespace depth_image_proc
233 
234 // Register as nodelet
sensor_msgs::image_encodings
depth_image_proc::PointCloudXyzRadialNodelet::pub_point_cloud_
ros::Publisher pub_point_cloud_
Definition: point_cloud_xyz_radial.cpp:123
depth_image_proc::PointCloudXyzRadialNodelet::connect_mutex_
boost::mutex connect_mutex_
Definition: point_cloud_xyz_radial.cpp:121
depth_image_proc::PointCloudXyzRadialNodelet::convert
void convert(const sensor_msgs::ImageConstPtr &depth_msg, PointCloud::Ptr &cloud_msg)
Definition: point_cloud_xyz_radial.cpp:232
point_cloud2_iterator.h
depth_traits.h
ros::Publisher
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
image_encodings.h
image_transport::ImageTransport
boost::shared_ptr< image_transport::ImageTransport >
pinhole_camera_model.h
NODELET_ERROR_THROTTLE
#define NODELET_ERROR_THROTTLE(rate,...)
ros.h
depth_image_proc::PointCloudXyzRadialNodelet::it_
boost::shared_ptr< image_transport::ImageTransport > it_
Definition: point_cloud_xyz_radial.cpp:116
depth_image_proc::PointCloudXyzRadialNodelet::binned
cv::Mat binned
Definition: point_cloud_xyz_radial.cpp:132
ros::TransportHints
depth_image_proc::PointCloudXyzRadialNodelet::onInit
virtual void onInit()
Definition: point_cloud_xyz_radial.cpp:156
ros::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
depth_image_proc::PointCloudXyzRadialNodelet::K_
boost::array< double, 9 > K_
Definition: point_cloud_xyz_radial.cpp:127
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
depth_image_proc::PointCloudXyzRadialNodelet::queue_size_
int queue_size_
Definition: point_cloud_xyz_radial.cpp:118
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(depth_image_proc::PointCloudXyzRadialNodelet, nodelet::Nodelet)
sensor_msgs::PointCloud2Iterator
image_transport::CameraSubscriber
image_transport::CameraSubscriber::shutdown
void shutdown()
depth_image_proc::PointCloudXyzRadialNodelet::PointCloud
sensor_msgs::PointCloud2 PointCloud
Definition: point_cloud_xyz_radial.cpp:122
depth_image_proc
Definition: depth_conversions.h:44
image_transport.h
depth_image_proc::PointCloudXyzRadialNodelet::depthCb
void depthCb(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
Definition: point_cloud_xyz_radial.cpp:191
depth_image_proc::PointCloudXyzRadialNodelet::D_
std::vector< double > D_
Definition: point_cloud_xyz_radial.cpp:126
depth_image_proc::PointCloudXyzRadialNodelet::sub_depth_
image_transport::CameraSubscriber sub_depth_
Definition: point_cloud_xyz_radial.cpp:117
nodelet::Nodelet
depth_image_proc::PointCloudXyzRadialNodelet::connectCb
void connectCb()
Definition: point_cloud_xyz_radial.cpp:174
nodelet.h
sensor_msgs::PointCloud2Modifier
class_list_macros.hpp
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
depth_image_proc::PointCloudXyzRadialNodelet::width_
int width_
Definition: point_cloud_xyz_radial.cpp:129
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
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
sensor_msgs::PointCloud2Modifier::setPointCloud2FieldsByString
void setPointCloud2FieldsByString(int n_fields,...)
depth_image_proc::PointCloudXyzRadialNodelet::height_
int height_
Definition: point_cloud_xyz_radial.cpp:130
ros::NodeHandle
depth_image_proc::PointCloudXyzRadialNodelet
Definition: point_cloud_xyz_radial.cpp:81


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