Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #ifndef DEPTH_IMAGE_TO_LASERSCAN
00035 #define DEPTH_IMAGE_TO_LASERSCAN
00036
00037 #include <sensor_msgs/Image.h>
00038 #include <sensor_msgs/LaserScan.h>
00039 #include <sensor_msgs/image_encodings.h>
00040 #include <image_geometry/pinhole_camera_model.h>
00041 #include <depthimage_to_laserscan/depth_traits.h>
00042 #include <sstream>
00043 #include <limits.h>
00044 #include <math.h>
00045
00046 namespace depthimage_to_laserscan
00047 {
00048 class DepthImageToLaserScan
00049 {
00050 public:
00051 DepthImageToLaserScan();
00052 ~DepthImageToLaserScan();
00053
00066 sensor_msgs::LaserScanPtr convert_msg(const sensor_msgs::ImageConstPtr& depth_msg,
00067 const sensor_msgs::CameraInfoConstPtr& info_msg);
00068
00079 void set_scan_time(const float scan_time);
00080
00091 void set_range_limits(const float range_min, const float range_max);
00092
00103 void set_scan_height(const int scan_height);
00104
00114 void set_output_frame(const std::string output_frame_id);
00115
00116 private:
00126 double magnitude_of_ray(const cv::Point3d& ray) const;
00127
00139 double angle_between_rays(const cv::Point3d& ray1, const cv::Point3d& ray2) const;
00140
00154 bool use_point(const float new_value, const float old_value, const float range_min, const float range_max) const;
00155
00169 template<typename T>
00170 void convert(const sensor_msgs::ImageConstPtr& depth_msg, const image_geometry::PinholeCameraModel& cam_model,
00171 const sensor_msgs::LaserScanPtr& scan_msg, const int& scan_height) const{
00172
00173 float center_x = cam_model.cx();
00174 float center_y = cam_model.cy();
00175
00176
00177 double unit_scaling = depthimage_to_laserscan::DepthTraits<T>::toMeters( T(1) );
00178 float constant_x = unit_scaling / cam_model.fx();
00179 float constant_y = unit_scaling / cam_model.fy();
00180
00181 const T* depth_row = reinterpret_cast<const T*>(&depth_msg->data[0]);
00182 int row_step = depth_msg->step / sizeof(T);
00183
00184 int offset = (int)(cam_model.cy()-scan_height/2);
00185 depth_row += offset*row_step;
00186
00187 for(int v = offset; v < offset+scan_height_; v++, depth_row += row_step){
00188 for (int u = 0; u < (int)depth_msg->width; u++)
00189 {
00190 T depth = depth_row[u];
00191
00192 double r = depth;
00193 double th = -atan2((double)(u - center_x) * constant_x, unit_scaling);
00194 int index = (th - scan_msg->angle_min) / scan_msg->angle_increment;
00195
00196 if (depthimage_to_laserscan::DepthTraits<T>::valid(depth)){
00197
00198 double x = (u - center_x) * depth * constant_x;
00199 double z = depthimage_to_laserscan::DepthTraits<T>::toMeters(depth);
00200
00201
00202 r = sqrt(pow(x, 2.0) + pow(z, 2.0));
00203 }
00204
00205
00206 if(use_point(r, scan_msg->ranges[index], scan_msg->range_min, scan_msg->range_max)){
00207 scan_msg->ranges[index] = r;
00208 }
00209 }
00210 }
00211 }
00212
00213 image_geometry::PinholeCameraModel cam_model_;
00214
00215 float scan_time_;
00216 float range_min_;
00217 float range_max_;
00218 int scan_height_;
00219 std::string output_frame_id_;
00220 };
00221
00222
00223 };
00224
00225 #endif