37 #ifndef JSK_PCL_ROS_HEIGHTMAP_UTILS_H_ 38 #define JSK_PCL_ROS_HEIGHTMAP_UTILS_H_ 40 #include <jsk_recognition_msgs/HeightmapConfig.h> 49 return base_topic +
"/config";
53 pcl::PointCloud<HeightMapPointType > &cloud,
54 float max_x_,
float min_x_,
float max_y_,
float min_y_)
56 int height = float_image.rows;
57 int width = float_image.cols;
58 cloud.points.reserve(float_image.rows * float_image.cols);
59 double dx = (max_x_ - min_x_) / width;
60 double dy = (max_y_ - min_y_) / height;
61 for (
size_t j = 0; j < height; j++) {
62 for (
size_t i = 0; i < width; i++) {
63 float v = float_image.at<cv::Vec2f>(j, i)[0];
64 float fint = float_image.at<cv::Vec2f>(j, i)[1];
67 p.y = j * dy + min_y_ + dy / 2.0;
68 p.x = i * dx + min_x_ + dx / 2.0;
71 cloud.points.push_back(p);
78 pcl::PointCloud<HeightMapPointType > &cloud,
79 float max_x_,
float min_x_,
float max_y_,
float min_y_)
81 int height = float_image.rows;
82 int width = float_image.cols;
83 cloud.points.resize(height * width);
85 cloud.height = height;
86 double dx = (max_x_ - min_x_) / width;
87 double dy = (max_y_ - min_y_) / height;
88 for (
size_t j = 0; j < height; j++) {
89 for (
size_t i = 0; i < width; i++) {
90 float v = float_image.at<cv::Vec2f>(j, i)[0];
91 float fint = float_image.at<cv::Vec2f>(j, i)[1];
93 p.x = p.y = p.z = std::numeric_limits<float>::quiet_NaN();
95 p.y = j * dy + min_y_ + dy / 2.0;
96 p.x = i * dx + min_x_ + dx / 2.0;
100 cloud.points[(j * width) + i] = p;
std::string getHeightmapConfigTopic(const std::string &base_topic)
void convertHeightMapToPCLOrganize(const cv::Mat &float_image, pcl::PointCloud< HeightMapPointType > &cloud, float max_x_, float min_x_, float max_y_, float min_y_)
pcl::PointXYZI HeightMapPointType
void convertHeightMapToPCL(const cv::Mat &float_image, pcl::PointCloud< HeightMapPointType > &cloud, float max_x_, float min_x_, float max_y_, float min_y_)