pointcloud_to_depthimage.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include <ros/ros.h>
30 #include <nodelet/nodelet.h>
31 #include <ros/publisher.h>
32 #include <ros/subscriber.h>
33 
35 #include <rtabmap/core/util3d.h>
36 #include <rtabmap/core/util2d.h>
38 
39 #include <sensor_msgs/PointCloud2.h>
40 #include <sensor_msgs/Image.h>
42 #include <sensor_msgs/CameraInfo.h>
43 
45 
46 #include <pcl/point_cloud.h>
47 #include <pcl/point_types.h>
49 #include <pcl_ros/transforms.h>
50 
54 
55 namespace rtabmap_ros
56 {
57 
59 {
60 public:
62  listener_(0),
63  waitForTransform_(0.1),
64  fillHolesSize_ (0),
65  fillHolesError_(0.1),
66  fillIterations_(1),
67  decimation_(1),
68  upscale_(false),
70  approxSync_(0),
71  exactSync_(0)
72  {}
73 
75  {
76  delete listener_;
77  if(approxSync_)
78  {
79  delete approxSync_;
80  }
81  if(exactSync_)
82  {
83  delete exactSync_;
84  }
85  }
86 
87 private:
88  virtual void onInit()
89  {
91 
94 
95  int queueSize = 10;
96  bool approx = true;
97  pnh.param("queue_size", queueSize, queueSize);
98  pnh.param("fixed_frame_id", fixedFrameId_, fixedFrameId_);
99  pnh.param("wait_for_transform", waitForTransform_, waitForTransform_);
100  pnh.param("fill_holes_size", fillHolesSize_, fillHolesSize_);
101  pnh.param("fill_holes_error", fillHolesError_, fillHolesError_);
102  pnh.param("fill_iterations", fillIterations_, fillIterations_);
103  pnh.param("decimation", decimation_, decimation_);
104  pnh.param("approx", approx, approx);
105  pnh.param("upscale", upscale_, upscale_);
106  pnh.param("upscale_depth_error_ratio", upscaleDepthErrorRatio_, upscaleDepthErrorRatio_);
107 
108  if(fixedFrameId_.empty() && approx)
109  {
110  ROS_FATAL("fixed_frame_id should be set when using approximate "
111  "time synchronization (approx=true)! If the robot "
112  "is moving, it could be \"odom\". If not moving, it "
113  "could be \"base_link\".");
114  }
115 
116  ROS_INFO("Params:");
117  ROS_INFO(" approx=%s", approx?"true":"false");
118  ROS_INFO(" queue_size=%d", queueSize);
119  ROS_INFO(" fixed_frame_id=%s", fixedFrameId_.c_str());
120  ROS_INFO(" wait_for_transform=%fs", waitForTransform_);
121  ROS_INFO(" fill_holes_size=%d pixels (0=disabled)", fillHolesSize_);
122  ROS_INFO(" fill_holes_error=%f", fillHolesError_);
123  ROS_INFO(" fill_iterations=%d", fillIterations_);
124  ROS_INFO(" decimation=%d", decimation_);
125  ROS_INFO(" upscale=%s (upscale_depth_error_ratio=%f)", upscale_?"true":"false", upscaleDepthErrorRatio_);
126 
128  depthImage16Pub_ = it.advertise("image_raw", 1); // 16 bits unsigned in mm
129  depthImage32Pub_ = it.advertise("image", 1); // 32 bits float in meters
130  pointCloudTransformedPub_ = nh.advertise<sensor_msgs::PointCloud2>(nh.resolveName("cloud")+"_transformed", 1);
131  cameraInfo16Pub_ = nh.advertise<sensor_msgs::CameraInfo>(nh.resolveName("image_raw")+"/camera_info", 1);
132  cameraInfo32Pub_ = nh.advertise<sensor_msgs::CameraInfo>(nh.resolveName("image")+"/camera_info", 1);
133 
134  if(approx)
135  {
137  approxSync_->registerCallback(boost::bind(&PointCloudToDepthImage::callback, this, boost::placeholders::_1, boost::placeholders::_2));
138  }
139  else
140  {
141  fixedFrameId_.clear();
143  exactSync_->registerCallback(boost::bind(&PointCloudToDepthImage::callback, this, boost::placeholders::_1, boost::placeholders::_2));
144  }
145 
146  pointCloudSub_.subscribe(nh, "cloud", 1);
147  cameraInfoSub_.subscribe(nh, "camera_info", 1);
148  }
149 
150  void callback(
151  const sensor_msgs::PointCloud2ConstPtr & pointCloud2Msg,
152  const sensor_msgs::CameraInfoConstPtr & cameraInfoMsg)
153  {
155  {
156  double cloudStamp = pointCloud2Msg->header.stamp.toSec();
157  double infoStamp = cameraInfoMsg->header.stamp.toSec();
158 
160  if(!fixedFrameId_.empty())
161  {
162  // approx sync
163  cloudDisplacement = rtabmap_ros::getTransform(
164  pointCloud2Msg->header.frame_id,
166  cameraInfoMsg->header.stamp,
167  pointCloud2Msg->header.stamp,
168  *listener_,
170  }
171 
172  if(cloudDisplacement.isNull())
173  {
174  return;
175  }
176 
178  pointCloud2Msg->header.frame_id,
179  cameraInfoMsg->header.frame_id,
180  cameraInfoMsg->header.stamp,
181  *listener_,
183 
184  if(cloudToCamera.isNull())
185  {
186  return;
187  }
188 
189  rtabmap::Transform localTransform = cloudDisplacement*cloudToCamera;
190 
191  rtabmap::CameraModel model = rtabmap_ros::cameraModelFromROS(*cameraInfoMsg, localTransform);
192  sensor_msgs::CameraInfo cameraInfoMsgOut = *cameraInfoMsg;
193  if(decimation_ > 1)
194  {
195  if(model.imageWidth()%decimation_ == 0 && model.imageHeight()%decimation_ == 0)
196  {
197  float scale = 1.0f/float(decimation_);
198  model = model.scaled(scale);
199 
200  rtabmap_ros::cameraModelToROS(model, cameraInfoMsgOut);
201  }
202  else
203  {
204  ROS_ERROR("decimation (%d) not valid for image size %dx%d",
205  decimation_,
206  model.imageWidth(),
207  model.imageHeight());
208  }
209  }
210 
211  UASSERT_MSG(pointCloud2Msg->data.size() == pointCloud2Msg->row_step*pointCloud2Msg->height,
212  uFormat("data=%d row_step=%d height=%d", pointCloud2Msg->data.size(), pointCloud2Msg->row_step, pointCloud2Msg->height).c_str());
213 
214  pcl::PCLPointCloud2::Ptr cloud(new pcl::PCLPointCloud2);
215  pcl_conversions::toPCL(*pointCloud2Msg, *cloud);
216 
217  cv_bridge::CvImage depthImage;
218 
219  if(cloud->data.empty())
220  {
221  ROS_WARN("Received an empty cloud on topic \"%s\"! A depth image with all zeros is returned.", pointCloudSub_.getTopic().c_str());
222  depthImage.image = cv::Mat::zeros(model.imageSize(), CV_32FC1);
223  }
224  else
225  {
226  depthImage.image = rtabmap::util3d::projectCloudToCamera(model.imageSize(), model.K(), cloud, model.localTransform());
227 
228  if(fillHolesSize_ > 0 && fillIterations_ > 0)
229  {
230  for(int i=0; i<fillIterations_;++i)
231  {
233  }
234  }
235 
237  {
238  sensor_msgs::PointCloud2 pointCloud2Out;
239  pcl_ros::transformPointCloud(model.localTransform().inverse().toEigen4f(), *pointCloud2Msg, pointCloud2Out);
240  pointCloud2Out.header = cameraInfoMsg->header;
241  pointCloudTransformedPub_.publish(pointCloud2Out);
242  }
243  }
244 
245  depthImage.header = cameraInfoMsg->header;
246 
247  if(decimation_>1 && upscale_)
248  {
250  }
251 
253  {
255  depthImage32Pub_.publish(depthImage.toImageMsg());
257  {
258  cameraInfo32Pub_.publish(cameraInfoMsgOut);
259  }
260  }
261 
263  {
265  depthImage.image = rtabmap::util2d::cvtDepthFromFloat(depthImage.image);
266  depthImage16Pub_.publish(depthImage.toImageMsg());
268  {
269  cameraInfo16Pub_.publish(cameraInfoMsgOut);
270  }
271  }
272 
273  if( cloudStamp != pointCloud2Msg->header.stamp.toSec() ||
274  infoStamp != cameraInfoMsg->header.stamp.toSec())
275  {
276  NODELET_ERROR("Input stamps changed between the beginning and the end of the callback! Make "
277  "sure the node publishing the topics doesn't override the same data after publishing them. A "
278  "solution is to use this node within another nodelet manager. Stamps: "
279  "cloud=%f->%f info=%f->%f",
280  cloudStamp, pointCloud2Msg->header.stamp.toSec(),
281  infoStamp, cameraInfoMsg->header.stamp.toSec());
282  }
283  }
284  }
285 
286 private:
294  std::string fixedFrameId_;
301  bool upscale_;
303 
308 };
309 
311 }
void callback(const sensor_msgs::PointCloud2ConstPtr &pointCloud2Msg, const sensor_msgs::CameraInfoConstPtr &cameraInfoMsg)
const cv::Size & imageSize() const
std::string uFormat(const char *fmt,...)
#define ROS_FATAL(...)
int imageHeight() const
#define NODELET_ERROR(...)
CameraModel scaled(double scale) const
std::string getTopic() const
uint32_t getNumSubscribers() const
static Transform getIdentity()
ros::NodeHandle & getNodeHandle() const
std::string encoding
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
ros::NodeHandle & getPrivateNodeHandle() const
#define ROS_WARN(...)
message_filters::Subscriber< sensor_msgs::PointCloud2 > pointCloudSub_
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
cv::Mat RTABMAP_EXP interpolate(const cv::Mat &image, int factor, float depthErrorRatio=0.02f)
sensor_msgs::ImagePtr toImageMsg() const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
#define UASSERT_MSG(condition, msg_str)
#define ROS_INFO(...)
const std::string TYPE_32FC1
cv::Mat K() const
rtabmap::CameraModel cameraModelFromROS(const sensor_msgs::CameraInfo &camInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
const std::string TYPE_16UC1
const Transform & localTransform() const
std::string resolveName(const std::string &name, bool remap=true) const
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
void toPCL(const ros::Time &stamp, std::uint64_t &pcl_stamp)
void cameraModelToROS(const rtabmap::CameraModel &model, sensor_msgs::CameraInfo &camInfo)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void publish(const sensor_msgs::Image &message) const
bool isNull() const
#define false
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > MyExactSyncPolicy
cv::Mat RTABMAP_EXP fillDepthHoles(const cv::Mat &depth, int maximumHoleSize=1, float errorRatio=0.02f)
Eigen::Matrix4f toEigen4f() const
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
cv::Mat RTABMAP_EXP projectCloudToCamera(const cv::Size &imageSize, const cv::Mat &cameraMatrixK, const cv::Mat &laserScan, const rtabmap::Transform &cameraTransform)
model
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
cv::Mat RTABMAP_EXP cvtDepthFromFloat(const cv::Mat &depth32F)
int imageWidth() const
uint32_t getNumSubscribers() const
#define ROS_ERROR(...)
std_msgs::Header header
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > MyApproxSyncPolicy
Transform inverse() const


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40