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_util
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 = 1;
96  int syncQueueSize = 10;
97  bool approx = true;
98  pnh.param("topic_queue_size", queueSize, queueSize);
99  if(pnh.hasParam("queue_size") && !pnh.hasParam("sync_queue_size"))
100  {
101  pnh.param("queue_size", syncQueueSize, syncQueueSize);
102  ROS_WARN("Parameter \"queue_size\" has been renamed "
103  "to \"sync_queue_size\" and will be removed "
104  "in future versions! The value (%d) is copied to "
105  "\"sync_queue_size\".", syncQueueSize);
106  }
107  else
108  {
109  pnh.param("sync_queue_size", syncQueueSize, syncQueueSize);
110  }
111  pnh.param("fixed_frame_id", fixedFrameId_, fixedFrameId_);
112  pnh.param("wait_for_transform", waitForTransform_, waitForTransform_);
113  pnh.param("fill_holes_size", fillHolesSize_, fillHolesSize_);
114  pnh.param("fill_holes_error", fillHolesError_, fillHolesError_);
115  pnh.param("fill_iterations", fillIterations_, fillIterations_);
116  pnh.param("decimation", decimation_, decimation_);
117  pnh.param("approx", approx, approx);
118  pnh.param("upscale", upscale_, upscale_);
119  pnh.param("upscale_depth_error_ratio", upscaleDepthErrorRatio_, upscaleDepthErrorRatio_);
120 
121  if(fixedFrameId_.empty() && approx)
122  {
123  ROS_FATAL("fixed_frame_id should be set when using approximate "
124  "time synchronization (approx=true)! If the robot "
125  "is moving, it could be \"odom\". If not moving, it "
126  "could be \"base_link\".");
127  }
128 
129  ROS_INFO("Params:");
130  ROS_INFO(" approx=%s", approx?"true":"false");
131  ROS_INFO(" topic_queue_size=%d", queueSize);
132  ROS_INFO(" sync_queue_size=%d", syncQueueSize);
133  ROS_INFO(" fixed_frame_id=%s", fixedFrameId_.c_str());
134  ROS_INFO(" wait_for_transform=%fs", waitForTransform_);
135  ROS_INFO(" fill_holes_size=%d pixels (0=disabled)", fillHolesSize_);
136  ROS_INFO(" fill_holes_error=%f", fillHolesError_);
137  ROS_INFO(" fill_iterations=%d", fillIterations_);
138  ROS_INFO(" decimation=%d", decimation_);
139  ROS_INFO(" upscale=%s (upscale_depth_error_ratio=%f)", upscale_?"true":"false", upscaleDepthErrorRatio_);
140 
142  depthImage16Pub_ = it.advertise("image_raw", 1); // 16 bits unsigned in mm
143  depthImage32Pub_ = it.advertise("image", 1); // 32 bits float in meters
144  pointCloudTransformedPub_ = nh.advertise<sensor_msgs::PointCloud2>(nh.resolveName("cloud")+"_transformed", 1);
145  cameraInfo16Pub_ = nh.advertise<sensor_msgs::CameraInfo>(nh.resolveName("image_raw")+"/camera_info", 1);
146  cameraInfo32Pub_ = nh.advertise<sensor_msgs::CameraInfo>(nh.resolveName("image")+"/camera_info", 1);
147 
148  if(approx)
149  {
151  approxSync_->registerCallback(boost::bind(&PointCloudToDepthImage::callback, this, boost::placeholders::_1, boost::placeholders::_2));
152  }
153  else
154  {
155  fixedFrameId_.clear();
157  exactSync_->registerCallback(boost::bind(&PointCloudToDepthImage::callback, this, boost::placeholders::_1, boost::placeholders::_2));
158  }
159 
160  pointCloudSub_.subscribe(nh, "cloud", queueSize);
161  cameraInfoSub_.subscribe(nh, "camera_info", queueSize);
162  }
163 
164  void callback(
165  const sensor_msgs::PointCloud2ConstPtr & pointCloud2Msg,
166  const sensor_msgs::CameraInfoConstPtr & cameraInfoMsg)
167  {
169  {
170  double cloudStamp = pointCloud2Msg->header.stamp.toSec();
171  double infoStamp = cameraInfoMsg->header.stamp.toSec();
172 
174  if(!fixedFrameId_.empty())
175  {
176  // approx sync
177  cloudDisplacement = rtabmap_conversions::getMovingTransform(
178  pointCloud2Msg->header.frame_id,
180  pointCloud2Msg->header.stamp,
181  cameraInfoMsg->header.stamp,
182  *listener_,
184  }
185 
186  if(cloudDisplacement.isNull())
187  {
188  return;
189  }
190 
192  pointCloud2Msg->header.frame_id,
193  cameraInfoMsg->header.frame_id,
194  cameraInfoMsg->header.stamp,
195  *listener_,
197 
198  if(cloudToCamera.isNull())
199  {
200  return;
201  }
202 
203  rtabmap::Transform localTransform = cloudDisplacement*cloudToCamera;
204 
205  rtabmap::CameraModel model = rtabmap_conversions::cameraModelFromROS(*cameraInfoMsg, localTransform);
206  sensor_msgs::CameraInfo cameraInfoMsgOut = *cameraInfoMsg;
207  if(decimation_ > 1)
208  {
209  if(model.imageWidth()%decimation_ == 0 && model.imageHeight()%decimation_ == 0)
210  {
211  float scale = 1.0f/float(decimation_);
212  model = model.scaled(scale);
213 
214  rtabmap_conversions::cameraModelToROS(model, cameraInfoMsgOut);
215  }
216  else
217  {
218  ROS_ERROR("decimation (%d) not valid for image size %dx%d",
219  decimation_,
220  model.imageWidth(),
221  model.imageHeight());
222  }
223  }
224 
225  UASSERT_MSG(pointCloud2Msg->data.size() == pointCloud2Msg->row_step*pointCloud2Msg->height,
226  uFormat("data=%d row_step=%d height=%d", pointCloud2Msg->data.size(), pointCloud2Msg->row_step, pointCloud2Msg->height).c_str());
227 
228  pcl::PCLPointCloud2::Ptr cloud(new pcl::PCLPointCloud2);
229  pcl_conversions::toPCL(*pointCloud2Msg, *cloud);
230 
231  cv_bridge::CvImage depthImage;
232 
233  if(cloud->data.empty())
234  {
235  ROS_WARN("Received an empty cloud on topic \"%s\"! A depth image with all zeros is returned.", pointCloudSub_.getTopic().c_str());
236  depthImage.image = cv::Mat::zeros(model.imageSize(), CV_32FC1);
237  }
238  else
239  {
240  depthImage.image = rtabmap::util3d::projectCloudToCamera(model.imageSize(), model.K(), cloud, model.localTransform());
241 
242  if(fillHolesSize_ > 0 && fillIterations_ > 0)
243  {
244  for(int i=0; i<fillIterations_;++i)
245  {
247  }
248  }
249 
251  {
252  sensor_msgs::PointCloud2 pointCloud2Out;
253  pcl_ros::transformPointCloud(model.localTransform().inverse().toEigen4f(), *pointCloud2Msg, pointCloud2Out);
254  pointCloud2Out.header = cameraInfoMsg->header;
255  pointCloudTransformedPub_.publish(pointCloud2Out);
256  }
257  }
258 
259  depthImage.header = cameraInfoMsg->header;
260 
261  if(decimation_>1 && upscale_)
262  {
264  }
265 
267  {
269  depthImage32Pub_.publish(depthImage.toImageMsg());
271  {
272  cameraInfo32Pub_.publish(cameraInfoMsgOut);
273  }
274  }
275 
277  {
279  depthImage.image = rtabmap::util2d::cvtDepthFromFloat(depthImage.image);
280  depthImage16Pub_.publish(depthImage.toImageMsg());
282  {
283  cameraInfo16Pub_.publish(cameraInfoMsgOut);
284  }
285  }
286 
287  if( cloudStamp != pointCloud2Msg->header.stamp.toSec() ||
288  infoStamp != cameraInfoMsg->header.stamp.toSec())
289  {
290  NODELET_ERROR("Input stamps changed between the beginning and the end of the callback! Make "
291  "sure the node publishing the topics doesn't override the same data after publishing them. A "
292  "solution is to use this node within another nodelet manager. Stamps: "
293  "cloud=%f->%f info=%f->%f",
294  cloudStamp, pointCloud2Msg->header.stamp.toSec(),
295  infoStamp, cameraInfoMsg->header.stamp.toSec());
296  }
297  }
298  }
299 
300 private:
308  std::string fixedFrameId_;
315  bool upscale_;
317 
322 };
323 
325 }
rtabmap_util::PointCloudToDepthImage::~PointCloudToDepthImage
virtual ~PointCloudToDepthImage()
Definition: pointcloud_to_depthimage.cpp:74
NODELET_ERROR
#define NODELET_ERROR(...)
ros::Publisher
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
rtabmap_util::PointCloudToDepthImage::fillHolesSize_
int fillHolesSize_
Definition: pointcloud_to_depthimage.cpp:311
image_encodings.h
rtabmap_util::PointCloudToDepthImage::cameraInfoSub_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
Definition: pointcloud_to_depthimage.cpp:307
image_transport::ImageTransport
rtabmap::util2d::interpolate
cv::Mat RTABMAP_CORE_EXPORT interpolate(const cv::Mat &image, int factor, float depthErrorRatio=0.02f)
rtabmap_util::PointCloudToDepthImage::approxSync_
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
Definition: pointcloud_to_depthimage.cpp:319
message_filters::Synchronizer
rtabmap_conversions::getTransform
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
rtabmap_util::PointCloudToDepthImage::MyExactSyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > MyExactSyncPolicy
Definition: pointcloud_to_depthimage.cpp:320
rtabmap_util::PointCloudToDepthImage::depthImage16Pub_
image_transport::Publisher depthImage16Pub_
Definition: pointcloud_to_depthimage.cpp:301
uFormat
std::string uFormat(const char *fmt,...)
ros.h
rtabmap::Transform::getIdentity
static Transform getIdentity()
rtabmap::CameraModel
rtabmap_util::PointCloudToDepthImage::exactSync_
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
Definition: pointcloud_to_depthimage.cpp:321
image_transport::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
rtabmap_util::PointCloudToDepthImage::depthImage32Pub_
image_transport::Publisher depthImage32Pub_
Definition: pointcloud_to_depthimage.cpp:302
pcl_conversions::toPCL
void toPCL(const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
rtabmap_conversions::cameraModelToROS
void cameraModelToROS(const rtabmap::CameraModel &model, sensor_msgs::CameraInfo &camInfo)
rtabmap_conversions::cameraModelFromROS
rtabmap::CameraModel cameraModelFromROS(const sensor_msgs::CameraInfo &camInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
rtabmap_util::PointCloudToDepthImage::cameraInfo32Pub_
ros::Publisher cameraInfo32Pub_
Definition: pointcloud_to_depthimage.cpp:304
rtabmap_util::PointCloudToDepthImage::onInit
virtual void onInit()
Definition: pointcloud_to_depthimage.cpp:88
rtabmap_util
Definition: MapsManager.h:49
rtabmap_util::PointCloudToDepthImage::fixedFrameId_
std::string fixedFrameId_
Definition: pointcloud_to_depthimage.cpp:308
rtabmap::Transform::isNull
bool isNull() const
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)
rtabmap_util::PointCloudToDepthImage::fillIterations_
int fillIterations_
Definition: pointcloud_to_depthimage.cpp:313
transforms.h
image_transport::ImageTransport::advertise
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
sensor_msgs::image_encodings::TYPE_16UC1
const std::string TYPE_16UC1
message_filters::Subscriber::getTopic
std::string getTopic() const
message_filters::Subscriber< sensor_msgs::PointCloud2 >
rtabmap::util2d::fillDepthHoles
cv::Mat RTABMAP_CORE_EXPORT fillDepthHoles(const cv::Mat &depth, int maximumHoleSize=1, float errorRatio=0.02f)
rtabmap_util::PointCloudToDepthImage::callback
void callback(const sensor_msgs::PointCloud2ConstPtr &pointCloud2Msg, const sensor_msgs::CameraInfoConstPtr &cameraInfoMsg)
Definition: pointcloud_to_depthimage.cpp:164
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
message_filters::sync_policies::ApproximateTime
rtabmap_util::PointCloudToDepthImage
Definition: pointcloud_to_depthimage.cpp:58
rtabmap::util3d::projectCloudToCamera
cv::Mat RTABMAP_CORE_EXPORT projectCloudToCamera(const cv::Size &imageSize, const cv::Mat &cameraMatrixK, const cv::Mat &laserScan, const rtabmap::Transform &cameraTransform)
rtabmap_util::PointCloudToDepthImage::listener_
tf::TransformListener * listener_
Definition: pointcloud_to_depthimage.cpp:309
cv_bridge::CvImage::header
std_msgs::Header header
subscriber.h
rtabmap_util::PointCloudToDepthImage::upscale_
bool upscale_
Definition: pointcloud_to_depthimage.cpp:315
yaml_to_camera_info.scale
scale
Definition: yaml_to_camera_info.py:39
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
rtabmap_util::PointCloudToDepthImage::PointCloudToDepthImage
PointCloudToDepthImage()
Definition: pointcloud_to_depthimage.cpp:61
ROS_WARN
#define ROS_WARN(...)
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
rtabmap_util::PointCloudToDepthImage::pointCloudTransformedPub_
ros::Publisher pointCloudTransformedPub_
Definition: pointcloud_to_depthimage.cpp:305
model
noiseModel::Diagonal::shared_ptr model
ROS_FATAL
#define ROS_FATAL(...)
UASSERT_MSG
#define UASSERT_MSG(condition, msg_str)
image_transport.h
rtabmap_util::PointCloudToDepthImage::waitForTransform_
double waitForTransform_
Definition: pointcloud_to_depthimage.cpp:310
exact_time.h
message_filters::Subscriber::subscribe
void subscribe()
rtabmap_util::PointCloudToDepthImage::upscaleDepthErrorRatio_
double upscaleDepthErrorRatio_
Definition: pointcloud_to_depthimage.cpp:316
rtabmap::Transform
rtabmap_util::PointCloudToDepthImage::pointCloudSub_
message_filters::Subscriber< sensor_msgs::PointCloud2 > pointCloudSub_
Definition: pointcloud_to_depthimage.cpp:306
rtabmap::util2d::cvtDepthFromFloat
cv::Mat RTABMAP_CORE_EXPORT cvtDepthFromFloat(const cv::Mat &depth32F)
pcl_ros::transformPointCloud
void transformPointCloud(const Eigen::Matrix4f &transform, const sensor_msgs::PointCloud2 &in, sensor_msgs::PointCloud2 &out)
rtabmap_conversions::getMovingTransform
rtabmap::Transform getMovingTransform(const std::string &movingFrame, const std::string &fixedFrame, const ros::Time &stampFrom, const ros::Time &stampTo, tf::TransformListener &listener, double waitForTransform)
rtabmap_util::PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(rtabmap_util::DisparityToDepth, nodelet::Nodelet)
nodelet::Nodelet
cv_bridge::CvImage::encoding
std::string encoding
sensor_msgs::image_encodings::TYPE_32FC1
const std::string TYPE_32FC1
nodelet.h
image_transport::Publisher
rtabmap_util::PointCloudToDepthImage::decimation_
int decimation_
Definition: pointcloud_to_depthimage.cpp:314
ROS_ERROR
#define ROS_ERROR(...)
cv_bridge::CvImage
class_list_macros.hpp
tf::TransformListener
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
rtabmap_util::PointCloudToDepthImage::cameraInfo16Pub_
ros::Publisher cameraInfo16Pub_
Definition: pointcloud_to_depthimage.cpp:303
float
float
ULogger.h
approximate_time.h
rtabmap_util::PointCloudToDepthImage::MyApproxSyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > MyApproxSyncPolicy
Definition: pointcloud_to_depthimage.cpp:318
false
#define false
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
message_filters::sync_policies::ExactTime
ROS_INFO
#define ROS_INFO(...)
rtabmap_util::PointCloudToDepthImage::fillHolesError_
double fillHolesError_
Definition: pointcloud_to_depthimage.cpp:312
MsgConversion.h
cv_bridge::CvImage::image
cv::Mat image
i
int i
util3d.h
ros::NodeHandle
util2d.h
pcl_conversions.h


rtabmap_util
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:40:50