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 
53 
54 namespace rtabmap_ros
55 {
56 
58 {
59 public:
61  listener_(0),
62  waitForTransform_(0.1),
63  fillHolesSize_ (0),
64  fillHolesError_(0.1),
65  fillIterations_(1),
66  decimation_(1),
67  approxSync_(0),
68  exactSync_(0)
69  {}
70 
72  {
73  delete listener_;
74  if(approxSync_)
75  {
76  delete approxSync_;
77  }
78  if(exactSync_)
79  {
80  delete exactSync_;
81  }
82  }
83 
84 private:
85  virtual void onInit()
86  {
88 
91 
92  int queueSize = 10;
93  bool approx = true;
94  pnh.param("queue_size", queueSize, queueSize);
95  pnh.param("fixed_frame_id", fixedFrameId_, fixedFrameId_);
96  pnh.param("wait_for_transform", waitForTransform_, waitForTransform_);
97  pnh.param("fill_holes_size", fillHolesSize_, fillHolesSize_);
98  pnh.param("fill_holes_error", fillHolesError_, fillHolesError_);
99  pnh.param("fill_iterations", fillIterations_, fillIterations_);
100  pnh.param("decimation", decimation_, decimation_);
101  pnh.param("approx", approx, approx);
102 
103  if(fixedFrameId_.empty() && approx)
104  {
105  ROS_FATAL("fixed_frame_id should be set when using approximate "
106  "time synchronization (approx=true)! If the robot "
107  "is moving, it could be \"odom\". If not moving, it "
108  "could be \"base_link\".");
109  }
110 
111  ROS_INFO("Params:");
112  ROS_INFO(" approx=%s", approx?"true":"false");
113  ROS_INFO(" queue_size=%d", queueSize);
114  ROS_INFO(" fixed_frame_id=%s", fixedFrameId_.c_str());
115  ROS_INFO(" wait_for_transform=%fs", waitForTransform_);
116  ROS_INFO(" fill_holes_size=%d pixels (0=disabled)", fillHolesSize_);
117  ROS_INFO(" fill_holes_error=%f", fillHolesError_);
118  ROS_INFO(" fill_iterations=%d", fillIterations_);
119  ROS_INFO(" decimation=%d", decimation_);
120 
122  depthImage16Pub_ = it.advertise("image_raw", 1); // 16 bits unsigned in mm
123  depthImage32Pub_ = it.advertise("image", 1); // 32 bits float in meters
124 
125  if(approx)
126  {
128  approxSync_->registerCallback(boost::bind(&PointCloudToDepthImage::callback, this, _1, _2));
129  }
130  else
131  {
132  fixedFrameId_.clear();
134  exactSync_->registerCallback(boost::bind(&PointCloudToDepthImage::callback, this, _1, _2));
135  }
136 
137  pointCloudSub_.subscribe(nh, "cloud", 1);
138  cameraInfoSub_.subscribe(nh, "camera_info", 1);
139  }
140 
141  void callback(
142  const sensor_msgs::PointCloud2ConstPtr & pointCloud2Msg,
143  const sensor_msgs::CameraInfoConstPtr & cameraInfoMsg)
144  {
146  {
148  if(!fixedFrameId_.empty())
149  {
150  // approx sync
151  cloudDisplacement = rtabmap_ros::getTransform(
152  pointCloud2Msg->header.frame_id,
154  pointCloud2Msg->header.stamp,
155  cameraInfoMsg->header.stamp,
156  *listener_,
158  }
159 
160  if(cloudDisplacement.isNull())
161  {
162  return;
163  }
164 
166  pointCloud2Msg->header.frame_id,
167  cameraInfoMsg->header.frame_id,
168  cameraInfoMsg->header.stamp,
169  *listener_,
171 
172  if(cloudToCamera.isNull())
173  {
174  return;
175  }
176 
177  rtabmap::Transform localTransform = cloudDisplacement.inverse()*cloudToCamera;
178 
179  rtabmap::CameraModel model = rtabmap_ros::cameraModelFromROS(*cameraInfoMsg, localTransform);
180 
181  if(decimation_ > 1)
182  {
183  if(model.imageWidth()%decimation_ == 0 && model.imageHeight()%decimation_ == 0)
184  {
185  model = model.scaled(1.0f/float(decimation_));
186  }
187  else
188  {
189  ROS_ERROR("decimation (%d) not valid for image size %dx%d",
190  decimation_,
191  model.imageWidth(),
192  model.imageHeight());
193  }
194  }
195 
196  pcl::PCLPointCloud2::Ptr cloud(new pcl::PCLPointCloud2);
197  pcl_conversions::toPCL(*pointCloud2Msg, *cloud);
198 
199  cv_bridge::CvImage depthImage;
200  depthImage.image = rtabmap::util3d::projectCloudToCamera(model.imageSize(), model.K(), cloud, model.localTransform());
201 
202  if(fillHolesSize_ > 0 && fillIterations_ > 0)
203  {
204  for(int i=0; i<fillIterations_;++i)
205  {
207  }
208  }
209 
210  depthImage.header = cameraInfoMsg->header;
211 
213  {
215  depthImage32Pub_.publish(depthImage.toImageMsg());
216  }
217 
219  {
221  depthImage.image = rtabmap::util2d::cvtDepthFromFloat(depthImage.image);
222  depthImage16Pub_.publish(depthImage.toImageMsg());
223  }
224  }
225  }
226 
227 private:
232  std::string fixedFrameId_;
239 
244 };
245 
247 }
void callback(const sensor_msgs::PointCloud2ConstPtr &pointCloud2Msg, const sensor_msgs::CameraInfoConstPtr &cameraInfoMsg)
int imageWidth() const
#define ROS_FATAL(...)
const cv::Size & imageSize() const
f
static Transform getIdentity()
std::string encoding
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
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)
uint32_t getNumSubscribers() const
ros::NodeHandle & getPrivateNodeHandle() const
bool isNull() const
void publish(const sensor_msgs::Image &message) const
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
const std::string TYPE_32FC1
rtabmap::CameraModel cameraModelFromROS(const sensor_msgs::CameraInfo &camInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
const std::string TYPE_16UC1
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
ros::NodeHandle & getNodeHandle() const
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)
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)
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)
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
cv::Mat RTABMAP_EXP cvtDepthFromFloat(const cv::Mat &depth32F)
Transform inverse() const
cv::Mat K() const
#define ROS_ERROR(...)
int imageHeight() const
sensor_msgs::ImagePtr toImageMsg() const
CameraModel scaled(double scale) const
std_msgs::Header header
void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > MyApproxSyncPolicy
const Transform & localTransform() const


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:04