disparity_to_depth.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 
32 #include <sensor_msgs/Image.h>
34 #include <stereo_msgs/DisparityImage.h>
35 
37 
38 #include <cv_bridge/cv_bridge.h>
39 
40 namespace rtabmap_ros
41 {
42 
44 {
45 public:
47 
48  virtual ~DisparityToDepth(){}
49 
50 private:
51  virtual void onInit()
52  {
55 
57  pub32f_ = it.advertise("depth", 1);
58  pub16u_ = it.advertise("depth_raw", 1);
59  sub_ = nh.subscribe("disparity", 1, &DisparityToDepth::callback, this);
60  }
61 
62  void callback(const stereo_msgs::DisparityImageConstPtr& disparityMsg)
63  {
64  if(disparityMsg->image.encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1) !=0)
65  {
66  NODELET_ERROR("Input type must be disparity=32FC1");
67  return;
68  }
69 
70  bool publish32f = pub32f_.getNumSubscribers();
71  bool publish16u = pub16u_.getNumSubscribers();
72 
73  if(publish32f || publish16u)
74  {
75  // sensor_msgs::image_encodings::TYPE_32FC1
76  cv::Mat disparity(disparityMsg->image.height, disparityMsg->image.width, CV_32FC1, const_cast<uchar*>(disparityMsg->image.data.data()));
77 
78  cv::Mat depth32f;
79  cv::Mat depth16u;
80  if(publish32f)
81  {
82  depth32f = cv::Mat::zeros(disparity.rows, disparity.cols, CV_32F);
83  }
84  if(publish16u)
85  {
86  depth16u = cv::Mat::zeros(disparity.rows, disparity.cols, CV_16U);
87  }
88  for (int i = 0; i < disparity.rows; i++)
89  {
90  for (int j = 0; j < disparity.cols; j++)
91  {
92  float disparity_value = disparity.at<float>(i,j);
93  if (disparity_value > disparityMsg->min_disparity && disparity_value < disparityMsg->max_disparity)
94  {
95  // baseline * focal / disparity
96  float depth = disparityMsg->T * disparityMsg->f / disparity_value;
97  if(publish32f)
98  {
99  depth32f.at<float>(i,j) = depth;
100  }
101  if(publish16u)
102  {
103  depth16u.at<unsigned short>(i,j) = (unsigned short)(depth*1000.0f);
104  }
105  }
106  }
107  }
108 
109  if(publish32f)
110  {
111  // convert to ROS sensor_msg::Image
112  cv_bridge::CvImage cvDepth(disparityMsg->header, sensor_msgs::image_encodings::TYPE_32FC1, depth32f);
113  sensor_msgs::Image depthMsg;
114  cvDepth.toImageMsg(depthMsg);
115 
116  //publish the message
117  pub32f_.publish(depthMsg);
118  }
119 
120  if(publish16u)
121  {
122  // convert to ROS sensor_msg::Image
123  cv_bridge::CvImage cvDepth(disparityMsg->header, sensor_msgs::image_encodings::TYPE_16UC1, depth16u);
124  sensor_msgs::Image depthMsg;
125  cvDepth.toImageMsg(depthMsg);
126 
127  //publish the message
128  pub16u_.publish(depthMsg);
129  }
130  }
131 }
132 
133 private:
137 };
138 
140 }
void callback(const stereo_msgs::DisparityImageConstPtr &disparityMsg)
#define NODELET_ERROR(...)
uint32_t getNumSubscribers() const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::NodeHandle & getNodeHandle() const
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
image_transport::Publisher pub32f_
ros::NodeHandle & getPrivateNodeHandle() const
sensor_msgs::ImagePtr toImageMsg() const
const std::string TYPE_32FC1
const std::string TYPE_16UC1
image_transport::Publisher pub16u_
void publish(const sensor_msgs::Image &message) const
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)


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