DepthImageToLaserScan.cpp
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 
35 
36 using namespace depthimage_to_laserscan;
37 
39 }
40 
42 }
43 
44 double DepthImageToLaserScan::magnitude_of_ray(const cv::Point3d& ray) const{
45  return sqrt(pow(ray.x, 2.0) + pow(ray.y, 2.0) + pow(ray.z, 2.0));
46 }
47 
48 double DepthImageToLaserScan::angle_between_rays(const cv::Point3d& ray1, const cv::Point3d& ray2) const{
49  double dot_product = ray1.x*ray2.x + ray1.y*ray2.y + ray1.z*ray2.z;
50  double magnitude1 = magnitude_of_ray(ray1);
51  double magnitude2 = magnitude_of_ray(ray2);;
52  return acos(dot_product / (magnitude1 * magnitude2));
53 }
54 
55 bool DepthImageToLaserScan::use_point(const float new_value, const float old_value, const float range_min, const float range_max) const{
56  // Check for NaNs and Infs, a real number within our limits is more desirable than these.
57  bool new_finite = std::isfinite(new_value);
58  bool old_finite = std::isfinite(old_value);
59 
60  // Infs are preferable over NaNs (more information)
61  if(!new_finite && !old_finite){ // Both are not NaN or Inf.
62  if(!std::isnan(new_value)){ // new is not NaN, so use it's +-Inf value.
63  return true;
64  }
65  return false; // Do not replace old_value
66  }
67 
68  // If not in range, don't bother
69  bool range_check = range_min <= new_value && new_value <= range_max;
70  if(!range_check){
71  return false;
72  }
73 
74  if(!old_finite){ // New value is in range and finite, use it.
75  return true;
76  }
77 
78  // Finally, if they are both numerical and new_value is closer than old_value, use new_value.
79  bool shorter_check = new_value < old_value;
80  return shorter_check;
81 }
82 
83 sensor_msgs::LaserScanPtr DepthImageToLaserScan::convert_msg(const sensor_msgs::ImageConstPtr& depth_msg,
84  const sensor_msgs::CameraInfoConstPtr& info_msg){
85  // Set camera model
86  cam_model_.fromCameraInfo(info_msg);
87 
88  // Calculate angle_min and angle_max by measuring angles between the left ray, right ray, and optical center ray
89  cv::Point2d raw_pixel_left(0, cam_model_.cy());
90  cv::Point2d rect_pixel_left = cam_model_.rectifyPoint(raw_pixel_left);
91  cv::Point3d left_ray = cam_model_.projectPixelTo3dRay(rect_pixel_left);
92 
93  cv::Point2d raw_pixel_right(depth_msg->width-1, cam_model_.cy());
94  cv::Point2d rect_pixel_right = cam_model_.rectifyPoint(raw_pixel_right);
95  cv::Point3d right_ray = cam_model_.projectPixelTo3dRay(rect_pixel_right);
96 
97  cv::Point2d raw_pixel_center(cam_model_.cx(), cam_model_.cy());
98  cv::Point2d rect_pixel_center = cam_model_.rectifyPoint(raw_pixel_center);
99  cv::Point3d center_ray = cam_model_.projectPixelTo3dRay(rect_pixel_center);
100 
101  double angle_max = angle_between_rays(left_ray, center_ray);
102  double angle_min = -angle_between_rays(center_ray, right_ray); // Negative because the laserscan message expects an opposite rotation of that from the depth image
103 
104  // Fill in laserscan message
105  sensor_msgs::LaserScanPtr scan_msg(new sensor_msgs::LaserScan());
106  scan_msg->header = depth_msg->header;
107  if(output_frame_id_.length() > 0){
108  scan_msg->header.frame_id = output_frame_id_;
109  }
110  scan_msg->angle_min = angle_min;
111  scan_msg->angle_max = angle_max;
112  scan_msg->angle_increment = (scan_msg->angle_max - scan_msg->angle_min) / (depth_msg->width - 1);
113  scan_msg->time_increment = 0.0;
114  scan_msg->scan_time = scan_time_;
115  scan_msg->range_min = range_min_;
116  scan_msg->range_max = range_max_;
117 
118  // Check scan_height vs image_height
119  if(scan_height_/2 > cam_model_.cy() || scan_height_/2 > depth_msg->height - cam_model_.cy()){
120  std::stringstream ss;
121  ss << "scan_height ( " << scan_height_ << " pixels) is too large for the image height.";
122  throw std::runtime_error(ss.str());
123  }
124 
125  // Calculate and fill the ranges
126  uint32_t ranges_size = depth_msg->width;
127  scan_msg->ranges.assign(ranges_size, std::numeric_limits<float>::quiet_NaN());
128 
129  if (depth_msg->encoding == sensor_msgs::image_encodings::TYPE_16UC1)
130  {
131  convert<uint16_t>(depth_msg, cam_model_, scan_msg, scan_height_);
132  }
133  else if (depth_msg->encoding == sensor_msgs::image_encodings::TYPE_32FC1)
134  {
135  convert<float>(depth_msg, cam_model_, scan_msg, scan_height_);
136  }
137  else
138  {
139  std::stringstream ss;
140  ss << "Depth image has unsupported encoding: " << depth_msg->encoding;
141  throw std::runtime_error(ss.str());
142  }
143 
144  return scan_msg;
145 }
146 
147 void DepthImageToLaserScan::set_scan_time(const float scan_time){
148  scan_time_ = scan_time;
149 }
150 
151 void DepthImageToLaserScan::set_range_limits(const float range_min, const float range_max){
152  range_min_ = range_min;
153  range_max_ = range_max;
154 }
155 
156 void DepthImageToLaserScan::set_scan_height(const int scan_height){
157  scan_height_ = scan_height;
158 }
159 
160 void DepthImageToLaserScan::set_output_frame(const std::string output_frame_id){
161  output_frame_id_ = output_frame_id;
162 }
sensor_msgs::LaserScanPtr convert_msg(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
cv::Point3d projectPixelTo3dRay(const cv::Point2d &uv_rect) const
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.
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.
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
const std::string TYPE_32FC1
float range_max_
Stores the current maximum range to use.
const std::string TYPE_16UC1
int scan_height_
Number of pixel rows to use when producing a laserscan from an area.
cv::Point2d rectifyPoint(const cv::Point2d &uv_raw) const
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