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  approxSync_(0),
69  exactSync_(0)
70  {}
71 
73  {
74  delete listener_;
75  if(approxSync_)
76  {
77  delete approxSync_;
78  }
79  if(exactSync_)
80  {
81  delete exactSync_;
82  }
83  }
84 
85 private:
86  virtual void onInit()
87  {
89 
92 
93  int queueSize = 10;
94  bool approx = true;
95  pnh.param("queue_size", queueSize, queueSize);
96  pnh.param("fixed_frame_id", fixedFrameId_, fixedFrameId_);
97  pnh.param("wait_for_transform", waitForTransform_, waitForTransform_);
98  pnh.param("fill_holes_size", fillHolesSize_, fillHolesSize_);
99  pnh.param("fill_holes_error", fillHolesError_, fillHolesError_);
100  pnh.param("fill_iterations", fillIterations_, fillIterations_);
101  pnh.param("decimation", decimation_, decimation_);
102  pnh.param("approx", approx, approx);
103 
104  if(fixedFrameId_.empty() && approx)
105  {
106  ROS_FATAL("fixed_frame_id should be set when using approximate "
107  "time synchronization (approx=true)! If the robot "
108  "is moving, it could be \"odom\". If not moving, it "
109  "could be \"base_link\".");
110  }
111 
112  ROS_INFO("Params:");
113  ROS_INFO(" approx=%s", approx?"true":"false");
114  ROS_INFO(" queue_size=%d", queueSize);
115  ROS_INFO(" fixed_frame_id=%s", fixedFrameId_.c_str());
116  ROS_INFO(" wait_for_transform=%fs", waitForTransform_);
117  ROS_INFO(" fill_holes_size=%d pixels (0=disabled)", fillHolesSize_);
118  ROS_INFO(" fill_holes_error=%f", fillHolesError_);
119  ROS_INFO(" fill_iterations=%d", fillIterations_);
120  ROS_INFO(" decimation=%d", decimation_);
121 
123  depthImage16Pub_ = it.advertise("image_raw", 1); // 16 bits unsigned in mm
124  depthImage32Pub_ = it.advertise("image", 1); // 32 bits float in meters
125  pointCloudTransformedPub_ = nh.advertise<sensor_msgs::PointCloud2>(nh.resolveName("cloud")+"_transformed", 1);
126 
127  if(approx)
128  {
130  approxSync_->registerCallback(boost::bind(&PointCloudToDepthImage::callback, this, _1, _2));
131  }
132  else
133  {
134  fixedFrameId_.clear();
136  exactSync_->registerCallback(boost::bind(&PointCloudToDepthImage::callback, this, _1, _2));
137  }
138 
139  pointCloudSub_.subscribe(nh, "cloud", 1);
140  cameraInfoSub_.subscribe(nh, "camera_info", 1);
141  }
142 
143  void callback(
144  const sensor_msgs::PointCloud2ConstPtr & pointCloud2Msg,
145  const sensor_msgs::CameraInfoConstPtr & cameraInfoMsg)
146  {
148  {
149  double cloudStamp = pointCloud2Msg->header.stamp.toSec();
150  double infoStamp = cameraInfoMsg->header.stamp.toSec();
151 
153  if(!fixedFrameId_.empty())
154  {
155  // approx sync
156  cloudDisplacement = rtabmap_ros::getTransform(
157  pointCloud2Msg->header.frame_id,
159  cameraInfoMsg->header.stamp,
160  pointCloud2Msg->header.stamp,
161  *listener_,
163  }
164 
165  if(cloudDisplacement.isNull())
166  {
167  return;
168  }
169 
171  pointCloud2Msg->header.frame_id,
172  cameraInfoMsg->header.frame_id,
173  cameraInfoMsg->header.stamp,
174  *listener_,
176 
177  if(cloudToCamera.isNull())
178  {
179  return;
180  }
181 
182  rtabmap::Transform localTransform = cloudDisplacement*cloudToCamera;
183 
184  rtabmap::CameraModel model = rtabmap_ros::cameraModelFromROS(*cameraInfoMsg, localTransform);
185 
186  if(decimation_ > 1)
187  {
188  if(model.imageWidth()%decimation_ == 0 && model.imageHeight()%decimation_ == 0)
189  {
190  model = model.scaled(1.0f/float(decimation_));
191  }
192  else
193  {
194  ROS_ERROR("decimation (%d) not valid for image size %dx%d",
195  decimation_,
196  model.imageWidth(),
197  model.imageHeight());
198  }
199  }
200 
201  pcl::PCLPointCloud2::Ptr cloud(new pcl::PCLPointCloud2);
202  pcl_conversions::toPCL(*pointCloud2Msg, *cloud);
203 
204  cv_bridge::CvImage depthImage;
205 
206  if(cloud->data.empty())
207  {
208  ROS_WARN("Received an empty cloud on topic \"%s\"! A depth image with all zeros is returned.", pointCloudSub_.getTopic().c_str());
209  depthImage.image = cv::Mat::zeros(model.imageSize(), CV_32FC1);
210  }
211  else
212  {
213  depthImage.image = rtabmap::util3d::projectCloudToCamera(model.imageSize(), model.K(), cloud, model.localTransform());
214 
215  if(fillHolesSize_ > 0 && fillIterations_ > 0)
216  {
217  for(int i=0; i<fillIterations_;++i)
218  {
220  }
221  }
222 
224  {
225  sensor_msgs::PointCloud2 pointCloud2Out;
226  pcl_ros::transformPointCloud(model.localTransform().inverse().toEigen4f(), *pointCloud2Msg, pointCloud2Out);
227  pointCloud2Out.header = cameraInfoMsg->header;
228  pointCloudTransformedPub_.publish(pointCloud2Out);
229  }
230  }
231 
232  depthImage.header = cameraInfoMsg->header;
233 
235  {
237  depthImage32Pub_.publish(depthImage.toImageMsg());
238  }
239 
241  {
243  depthImage.image = rtabmap::util2d::cvtDepthFromFloat(depthImage.image);
244  depthImage16Pub_.publish(depthImage.toImageMsg());
245  }
246 
247  if( cloudStamp != pointCloud2Msg->header.stamp.toSec() ||
248  infoStamp != cameraInfoMsg->header.stamp.toSec())
249  {
250  NODELET_ERROR("Input stamps changed between the beginning and the end of the callback! Make "
251  "sure the node publishing the topics doesn't override the same data after publishing them. A "
252  "solution is to use this node within another nodelet manager. Stamps: "
253  "cloud=%f->%f info=%f->%f",
254  cloudStamp, pointCloud2Msg->header.stamp.toSec(),
255  infoStamp, cameraInfoMsg->header.stamp.toSec());
256  }
257  }
258  }
259 
260 private:
266  std::string fixedFrameId_;
273 
278 };
279 
281 }
void callback(const sensor_msgs::PointCloud2ConstPtr &pointCloud2Msg, const sensor_msgs::CameraInfoConstPtr &cameraInfoMsg)
int imageWidth() const
std::string getTopic() const
#define ROS_FATAL(...)
#define NODELET_ERROR(...)
const cv::Size & imageSize() const
void publish(const boost::shared_ptr< M > &message) const
f
std::string resolveName(const std::string &name, bool remap=true) const
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_
#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)
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_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
uint32_t getNumSubscribers() const
Eigen::Matrix4f toEigen4f() 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)
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)
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 Mon Dec 14 2020 03:42:19