DepthImageToLaserScan.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, Willow Garage, Inc.
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  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /*
31  * Author: Chad Rockey
32  */
33 
34 #ifndef DEPTH_IMAGE_TO_LASERSCAN
35 #define DEPTH_IMAGE_TO_LASERSCAN
36 
37 #include <sensor_msgs/Image.h>
38 #include <sensor_msgs/LaserScan.h>
42 #include <sstream>
43 #include <limits.h>
44 #include <math.h>
45 
47 {
49  {
50  public:
53 
66  sensor_msgs::LaserScanPtr convert_msg(const sensor_msgs::ImageConstPtr& depth_msg,
67  const sensor_msgs::CameraInfoConstPtr& info_msg);
68 
79  void set_scan_time(const float scan_time);
80 
91  void set_range_limits(const float range_min, const float range_max);
92 
103  void set_scan_height(const int scan_height);
104 
114  void set_output_frame(const std::string output_frame_id);
115 
116  private:
126  double magnitude_of_ray(const cv::Point3d& ray) const;
127 
139  double angle_between_rays(const cv::Point3d& ray1, const cv::Point3d& ray2) const;
140 
154  bool use_point(const float new_value, const float old_value, const float range_min, const float range_max) const;
155 
169  template<typename T>
170  void convert(const sensor_msgs::ImageConstPtr& depth_msg, const image_geometry::PinholeCameraModel& cam_model,
171  const sensor_msgs::LaserScanPtr& scan_msg, const int& scan_height) const{
172  // Use correct principal point from calibration
173  float center_x = cam_model.cx();
174  float center_y = cam_model.cy();
175 
176  // Combine unit conversion (if necessary) with scaling by focal length for computing (X,Y)
177  double unit_scaling = depthimage_to_laserscan::DepthTraits<T>::toMeters( T(1) );
178  float constant_x = unit_scaling / cam_model.fx();
179  float constant_y = unit_scaling / cam_model.fy();
180 
181  const T* depth_row = reinterpret_cast<const T*>(&depth_msg->data[0]);
182  int row_step = depth_msg->step / sizeof(T);
183 
184  int offset = (int)(cam_model.cy()-scan_height/2);
185  depth_row += offset*row_step; // Offset to center of image
186 
187  for(int v = offset; v < offset+scan_height_; v++, depth_row += row_step){
188  for (int u = 0; u < (int)depth_msg->width; u++) // Loop over each pixel in row
189  {
190  T depth = depth_row[u];
191 
192  double r = depth; // Assign to pass through NaNs and Infs
193  double th = -atan2((double)(u - center_x) * constant_x, unit_scaling); // Atan2(x, z), but depth divides out
194  int index = (th - scan_msg->angle_min) / scan_msg->angle_increment;
195 
196  if (depthimage_to_laserscan::DepthTraits<T>::valid(depth)){ // Not NaN or Inf
197  // Calculate in XYZ
198  double x = (u - center_x) * depth * constant_x;
200 
201  // Calculate actual distance
202  r = sqrt(pow(x, 2.0) + pow(z, 2.0));
203  }
204 
205  // Determine if this point should be used.
206  if(use_point(r, scan_msg->ranges[index], scan_msg->range_min, scan_msg->range_max)){
207  scan_msg->ranges[index] = r;
208  }
209  }
210  }
211  }
212 
214 
215  float scan_time_;
216  float range_min_;
217  float range_max_;
219  std::string output_frame_id_;
220  };
221 
222 
223 }; // depthimage_to_laserscan
224 
225 #endif
sensor_msgs::LaserScanPtr convert_msg(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
void set_output_frame(const std::string output_frame_id)
image_geometry::PinholeCameraModel cam_model_
image_geometry helper class for managing sensor_msgs/CameraInfo messages.
void convert(const sensor_msgs::ImageConstPtr &depth_msg, const image_geometry::PinholeCameraModel &cam_model, const sensor_msgs::LaserScanPtr &scan_msg, const int &scan_height) const
double angle_between_rays(const cv::Point3d &ray1, const cv::Point3d &ray2) const
bool use_point(const float new_value, const float old_value, const float range_min, const float range_max) const
float scan_time_
Stores the time between scans.
float range_min_
Stores the current minimum range to use.
float range_max_
Stores the current maximum range to use.
int scan_height_
Number of pixel rows to use when producing a laserscan from an area.
double magnitude_of_ray(const cv::Point3d &ray) const
void set_range_limits(const float range_min, const float range_max)
std::string output_frame_id_
Output frame_id for each laserscan. This is likely NOT the camera&#39;s frame_id.


depthimage_to_laserscan
Author(s): Chad Rockey
autogenerated on Sun Jan 5 2020 03:45:46