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 
00035 
00036 
00037 #ifndef JSK_PCL_ROS_HEIGHTMAP_UTILS_H_
00038 #define JSK_PCL_ROS_HEIGHTMAP_UTILS_H_
00039 
00040 #include <jsk_recognition_msgs/HeightmapConfig.h>
00041 #include "jsk_recognition_utils/pcl_conversion_util.h"
00042 
00043 namespace jsk_pcl_ros
00044 {
00045   typedef pcl::PointXYZI HeightMapPointType;
00046 
00047   inline std::string getHeightmapConfigTopic(const std::string& base_topic)
00048   {
00049     return base_topic + "/config";
00050   }
00051 
00052   inline void convertHeightMapToPCL(const cv::Mat &float_image,
00053                                    pcl::PointCloud<HeightMapPointType > &cloud,
00054                                    float max_x_, float min_x_, float max_y_, float min_y_)
00055   {
00056     int height = float_image.rows;
00057     int width  = float_image.cols;
00058     cloud.points.reserve(float_image.rows * float_image.cols); 
00059     double dx = (max_x_ - min_x_) / width;
00060     double dy = (max_y_ - min_y_) / height;
00061     for (size_t j = 0; j < height; j++) {
00062       for (size_t i = 0; i < width; i++) {
00063         float v = float_image.at<cv::Vec2f>(j, i)[0];
00064         float fint = float_image.at<cv::Vec2f>(j, i)[1];
00065         if (v != -FLT_MAX) {
00066           HeightMapPointType p;
00067           p.y = j * dy + min_y_ + dy / 2.0;
00068           p.x = i * dx + min_x_ + dx / 2.0;
00069           p.z = v;
00070           p.intensity = fint;
00071           cloud.points.push_back(p); 
00072         }
00073       }
00074     }
00075   }
00076 
00077   inline void convertHeightMapToPCLOrganize(const cv::Mat &float_image,
00078                                            pcl::PointCloud<HeightMapPointType > &cloud,
00079                                            float max_x_, float min_x_, float max_y_, float min_y_)
00080   {
00081     int height = float_image.rows;
00082     int width  = float_image.cols;
00083     cloud.points.resize(height * width); 
00084     cloud.width  = width;
00085     cloud.height = height;
00086     double dx = (max_x_ - min_x_) / width;
00087     double dy = (max_y_ - min_y_) / height;
00088     for (size_t j = 0; j < height; j++) {
00089       for (size_t i = 0; i < width; i++) {
00090         float v = float_image.at<cv::Vec2f>(j, i)[0];
00091         float fint = float_image.at<cv::Vec2f>(j, i)[1];
00092         HeightMapPointType p;
00093         p.x = p.y = p.z = std::numeric_limits<float>::quiet_NaN(); 
00094         if (v != -FLT_MAX) {
00095           p.y = j * dy + min_y_ + dy / 2.0;
00096           p.x = i * dx + min_x_ + dx / 2.0;
00097           p.z = v;
00098           p.intensity = fint;
00099         }
00100         cloud.points[(j * width) + i] = p; 
00101       }
00102     }
00103   }
00104 }
00105 
00106 #endif