GridMapCvConverter.hpp
Go to the documentation of this file.
1 /*
2  * GridMapCvConverter.hpp
3  *
4  * Created on: Apr 14, 2016
5  * Author: Péter Fankhauser
6  * Institute: ETH Zurich, ANYbotics
7  */
8 
9 #pragma once
10 
12 
13 // OpenCV
14 #include <cv_bridge/cv_bridge.h>
15 
16 // STD
17 #include <iostream>
18 
19 namespace grid_map {
20 
25 {
26  public:
36  static bool initializeFromImage(const cv::Mat& image, const double resolution,
37  grid_map::GridMap& gridMap, const grid_map::Position& position)
38  {
39  const double lengthX = resolution * image.rows;
40  const double lengthY = resolution * image.cols;
41  Length length(lengthX, lengthY);
42  gridMap.setGeometry(length, resolution, position);
43  return true;
44  }
45 
58  template<typename Type_, int NChannels_>
59  static bool addLayerFromImage(const cv::Mat& image, const std::string& layer,
60  grid_map::GridMap& gridMap, const float lowerValue = 0.0,
61  const float upperValue = 1.0, const double alphaThreshold = 0.5)
62  {
63  if (gridMap.getSize()(0) != image.rows || gridMap.getSize()(1) != image.cols) {
64  std::cerr << "Image size does not correspond to grid map size!" << std::endl;
65  return false;
66  }
67 
68  bool isColor = false;
69  if (image.channels() >= 3) isColor = true;
70  bool hasAlpha = false;
71  if (image.channels() >= 4) hasAlpha = true;
72 
73  cv::Mat imageMono;
74  if (isColor && !hasAlpha) {
75  cv::cvtColor(image, imageMono, CV_BGR2GRAY);
76  } else if (isColor && hasAlpha) {
77  cv::cvtColor(image, imageMono, CV_BGRA2GRAY);
78  } else if (!isColor && !hasAlpha){
79  imageMono = image;
80  } else {
81  std::cerr << "Something went wrong when adding grid map layer form image!" << std::endl;
82  return false;
83  }
84 
85  const float mapValueDifference = upperValue - lowerValue;
86 
87  float maxImageValue;
88  if (std::is_same<Type_, float>::value || std::is_same<Type_, double>::value) {
89  maxImageValue = 1.0;
90  } else if (std::is_same<Type_, unsigned short>::value || std::is_same<Type_, unsigned char>::value) {
91  maxImageValue = (float)std::numeric_limits<Type_>::max();
92  } else {
93  std::cerr << "This image type is not supported." << std::endl;
94  return false;
95  }
96 
97  const Type_ alphaTreshold = (Type_)(alphaThreshold * maxImageValue);
98 
99  gridMap.add(layer);
100  grid_map::Matrix& data = gridMap[layer];
101 
102  for (GridMapIterator iterator(gridMap); !iterator.isPastEnd(); ++iterator) {
103  const Index index(*iterator);
104 
105  // Check for alpha layer.
106  if (hasAlpha) {
107  const Type_ alpha = image.at<cv::Vec<Type_, NChannels_>>(index(0), index(1))[NChannels_ - 1];
108  if (alpha < alphaTreshold) continue;
109  }
110 
111  // Compute value.
112  const Type_ imageValue = imageMono.at<Type_>(index(0), index(1));
113  const float mapValue = lowerValue + mapValueDifference * ((float) imageValue / maxImageValue);
114  data(index(0), index(1)) = mapValue;
115  }
116 
117  return true;
118  };
119 
127  template<typename Type_, int NChannels_>
128  static bool addColorLayerFromImage(const cv::Mat& image, const std::string& layer,
129  grid_map::GridMap& gridMap)
130  {
131  if (gridMap.getSize()(0) != image.rows || gridMap.getSize()(1) != image.cols) {
132  std::cerr << "Image size does not correspond to grid map size!" << std::endl;
133  return false;
134  }
135 
136  bool hasAlpha = false;
137  if (image.channels() >= 4) hasAlpha = true;
138 
139  cv::Mat imageRGB;
140  if (hasAlpha) {
141  cv::cvtColor(image, imageRGB, CV_BGRA2RGB);
142  } else {
143  imageRGB = image;
144  }
145 
146  gridMap.add(layer);
147 
148  for (GridMapIterator iterator(gridMap); !iterator.isPastEnd(); ++iterator) {
149  const auto& cvColor = imageRGB.at<cv::Vec<Type_, 3>>((*iterator)(0), (*iterator)(1));
150  Eigen::Vector3i colorVector;
151  colorVector(0) = cvColor[0];
152  colorVector(1) = cvColor[1];
153  colorVector(2) = cvColor[2];
154  colorVectorToValue(colorVector, gridMap.at(layer, *iterator));
155  }
156 
157  return true;
158  }
159 
172  template<typename Type_, int NChannels_>
173  static bool toImage(const grid_map::GridMap& gridMap, const std::string& layer,
174  const int encoding, cv::Mat& image)
175  {
176  const float minValue = gridMap.get(layer).minCoeffOfFinites();
177  const float maxValue = gridMap.get(layer).maxCoeffOfFinites();
178  return toImage<Type_, NChannels_>(gridMap, layer, encoding, minValue, maxValue, image);
179  };
180 
191  template<typename Type_, int NChannels_>
192  static bool toImage(const grid_map::GridMap& gridMap, const std::string& layer,
193  const int encoding, const float lowerValue, const float upperValue,
194  cv::Mat& image)
195  {
196  // Initialize image.
197  if (gridMap.getSize()(0) > 0 && gridMap.getSize()(1) > 0) {
198  image = cv::Mat::zeros(gridMap.getSize()(0), gridMap.getSize()(1), encoding);
199  } else {
200  std::cerr << "Invalid grid map?" << std::endl;
201  return false;
202  }
203 
204  // Get max image value.
205  Type_ imageMax;
206  if (std::is_same<Type_, float>::value || std::is_same<Type_, double>::value) {
207  imageMax = 1.0;
208  } else if (std::is_same<Type_, unsigned short>::value || std::is_same<Type_, unsigned char>::value) {
209  imageMax = (Type_)std::numeric_limits<Type_>::max();
210  } else {
211  std::cerr << "This image type is not supported." << std::endl;
212  return false;
213  }
214 
215  // Clamp outliers.
216  grid_map::GridMap map = gridMap;
217  map.get(layer) = map.get(layer).unaryExpr(grid_map::Clamp<float>(lowerValue, upperValue));
218  const grid_map::Matrix& data = map[layer];
219 
220  // Convert to image.
221  bool isColor = false;
222  if (image.channels() >= 3) isColor = true;
223  bool hasAlpha = false;
224  if (image.channels() >= 4) hasAlpha = true;
225 
226  for (GridMapIterator iterator(map); !iterator.isPastEnd(); ++iterator) {
227  const Index index(*iterator);
228  if (std::isfinite(data(index(0), index(1)))) {
229  const float& value = data(index(0), index(1));
230  const Type_ imageValue = (Type_) (((value - lowerValue) / (upperValue - lowerValue)) * (float) imageMax);
231  const Index imageIndex(iterator.getUnwrappedIndex());
232  unsigned int channel = 0;
233  image.at<cv::Vec<Type_, NChannels_>>(imageIndex(0), imageIndex(1))[channel] = imageValue;
234 
235  if (isColor) {
236  image.at<cv::Vec<Type_, NChannels_>>(imageIndex(0), imageIndex(1))[++channel] = imageValue;
237  image.at<cv::Vec<Type_, NChannels_>>(imageIndex(0), imageIndex(1))[++channel] = imageValue;
238  }
239  if (hasAlpha) {
240  image.at<cv::Vec<Type_, NChannels_>>(imageIndex(0), imageIndex(1))[++channel] = imageMax;
241  }
242  }
243  }
244 
245  return true;
246  };
247 
248 };
249 
250 } /* namespace */
static bool toImage(const grid_map::GridMap &gridMap, const std::string &layer, const int encoding, const float lowerValue, const float upperValue, cv::Mat &image)
static bool toImage(const grid_map::GridMap &gridMap, const std::string &layer, const int encoding, cv::Mat &image)
Eigen::Array2i Index
void setGeometry(const Length &length, const double resolution, const Position &position=Position::Zero())
Eigen::MatrixXf Matrix
static bool addColorLayerFromImage(const cv::Mat &image, const std::string &layer, grid_map::GridMap &gridMap)
static bool initializeFromImage(const cv::Mat &image, const double resolution, grid_map::GridMap &gridMap, const grid_map::Position &position)
static bool addLayerFromImage(const cv::Mat &image, const std::string &layer, grid_map::GridMap &gridMap, const float lowerValue=0.0, const float upperValue=1.0, const double alphaThreshold=0.5)
Eigen::Vector2d Position
bool colorVectorToValue(const Eigen::Vector3i &colorVector, unsigned long &colorValue)
const Matrix & get(const std::string &layer) const
float & at(const std::string &layer, const Index &index)
void add(const std::string &layer, const double value=NAN)
Eigen::Array2d Length
const Size & getSize() const


grid_map_cv
Author(s): Péter Fankhauser
autogenerated on Tue Jun 25 2019 20:02:13