GridMapVisual.cpp
Go to the documentation of this file.
1 /*
2  * GridMapVisual.cpp
3  *
4  * Created on: Aug 3, 2016
5  * Author: Philipp Krüsi, Péter Fankhauser
6  * Institute: ETH Zurich, ANYbotics
7  */
8 
10 
11 #include <algorithm>
12 #include <iterator>
13 
14 #include <OGRE/OgreManualObject.h>
15 #include <OGRE/OgreMaterialManager.h>
16 #include <OGRE/OgreSceneManager.h>
17 #include <OGRE/OgreSceneNode.h>
18 #include <OGRE/OgreTechnique.h>
19 #include <OGRE/OgreTextureManager.h>
20 #include <OGRE/OgreVector3.h>
23 #include <chrono>
24 
27 
29 
30 namespace grid_map_rviz_plugin {
31 
32 GridMapVisual::GridMapVisual(Ogre::SceneManager* sceneManager, Ogre::SceneNode* parentNode) : manualObject_(0), haveMap_(false) {
33  sceneManager_ = sceneManager;
34  frameNode_ = parentNode->createChildSceneNode();
35 
36  // Create BillboardLine object.
38 }
39 
41  // Destroy the ManualObject if it was created.
42  if (manualObject_) {
43  sceneManager_->destroyManualObject(manualObject_);
44  material_->unload();
45  Ogre::MaterialManager::getSingleton().remove(material_->getName());
46  }
47 
48  // Destroy the frame node.
49  sceneManager_->destroySceneNode(frameNode_);
50 }
51 
52 void GridMapVisual::setMessage(const grid_map_msgs::GridMap::ConstPtr& msg) {
53  // Convert grid map message.
55  haveMap_ = true;
56 }
57 
58 void GridMapVisual::computeVisualization(float alpha, bool showGridLines, bool flatTerrain, std::string heightLayer, bool flatColor,
59  bool noColor, Ogre::ColourValue meshColor, bool mapLayerColor, std::string colorLayer,
60  std::string colorMap, bool useColorMap, bool invertColorMap, Ogre::ColourValue minColor,
61  Ogre::ColourValue maxColor, bool autocomputeIntensity, float minIntensity, float maxIntensity, float gridLineThickness,
62  int gridCellDecimation) {
63  const auto startTime = std::chrono::high_resolution_clock::now();
64  if (!haveMap_) {
65  ROS_DEBUG("Unable to visualize grid map, no map data. Use setMessage() first!");
66  return;
67  }
68 
69  // Get list of layers and check if the requested ones are present.
70  const std::vector<std::string> layerNames = map_.getLayers();
71  if (layerNames.size() < 1) {
72  ROS_DEBUG("Unable to visualize grid map, map must contain at least one layer.");
73  return;
74  }
75  if ((!flatTerrain && !map_.exists(heightLayer)) || (!noColor && !flatColor && !map_.exists(colorLayer))) {
76  ROS_DEBUG("Unable to visualize grid map, requested layer(s) not available.");
77  return;
78  }
79 
80  // Convert to simple format, makes things easier.
82 
83  // Basic grid map data.
84  const size_t rows = map_.getSize()(0);
85  const size_t cols = map_.getSize()(1);
86  if (rows < 2 || cols < 2) {
87  ROS_DEBUG("GridMap has not enough cells.");
88  return;
89  }
90  const double resolution = map_.getResolution();
91  const grid_map::Matrix& heightData = map_[flatTerrain ? layerNames[0] : heightLayer];
92  const grid_map::Matrix& colorData = map_[flatColor ? layerNames[0] : colorLayer];
93 
94  // Reset and begin the manualObject (mesh).
95  // For more information: https://www.ogre3d.org/docs/api/1.7/class_ogre_1_1_manual_object.html#details
96  const size_t nVertices = cols * rows;
98 
99  // Reset the mesh lines.
100  meshLines_->clear();
101  if (showGridLines) {
102  initializeMeshLines(cols, rows, resolution, alpha, gridLineThickness);
103  }
104  // Make sure gridCellDecimation is within a valid range
105  gridCellDecimation = std::max(gridCellDecimation, 1);
106 
107  // Compute a mask of valid cells.
108  auto basicLayers = map_.getBasicLayers();
109  if (std::find(basicLayers.begin(), basicLayers.end(), heightLayer) == basicLayers.end()) {
110  basicLayers.emplace_back(heightLayer);
111  }
112  const MaskArray isValid = computeIsValidMask(basicLayers);
113 
114  // Check and warn the user if any basic layers are not present in the grid map.
115  printMissingBasicLayers(basicLayers);
116 
117  // Compute the display heights for each cell.
118  Eigen::ArrayXXf heightOrFlatData;
119  if (flatTerrain) {
120  heightOrFlatData = Eigen::ArrayXXf::Zero(heightData.rows(), heightData.cols());
121  } else {
122  heightOrFlatData = heightData.array();
123  }
124 
125  // Compute the color data for each cell.
126  ColoringMethod coloringMethod;
127  if (flatColor || noColor) {
128  coloringMethod = ColoringMethod::FLAT;
129  } else if(mapLayerColor) {
130  coloringMethod = ColoringMethod::COLOR_LAYER;
131  } else if (!useColorMap) {
133  } else if (!invertColorMap) {
135  } else {
137  }
138 
139  const auto colorValues = computeColorValues(heightData, colorData, coloringMethod, colorMap, meshColor,
140  minIntensity, maxIntensity, autocomputeIntensity, minColor, maxColor);
141 
142  // Initialize loop constants.
143  grid_map::Position topLeft;
144  map_.getPosition(grid_map::Index(0, 0), topLeft);
145 
146  Eigen::ArrayXXi indexToOgreIndex;
147  indexToOgreIndex.setConstant(rows, cols, -1);
148 
149  int ogreIndex = 0;
150 
151  // Add vertices for mesh.
152  for (size_t i = 0; i < rows; ++i) {
153  for (size_t j = 0; j < cols; ++j) {
154  if(!noColor) {
155  std::vector<int> vertices;
156  std::vector<Ogre::ColourValue> colors;
157 
158  // Add the vertex to the scene
159  grid_map::Index index(i, j);
160  if (!isValid(index(0), index(1))) {
161  continue;
162  }
163  grid_map::Position position = topLeft.array() - index.cast<double>() * resolution;
164  manualObject_->position(position(0), position(1), heightOrFlatData(index(0), index(1)));
165 
166  const Ogre::ColourValue& color = colorValues(index(0), index(1));
167  manualObject_->colour(color.r, color.g, color.b, alpha);
168 
169  indexToOgreIndex(index(0), index(1)) = ogreIndex;
170  ogreIndex++;
171 
172  // We can only add triangles to the top left side of the current vertex if we have data.
173  if (i == 0 || j == 0) {
174  continue;
175  }
176 
177  // Add triangles and grid to scene.
178  std::vector<int> vertexIndices;
179  for (size_t k = 0; k < 2; k++) {
180  for (size_t l = 0; l < 2; l++) {
181  grid_map::Index index(i - k, j - l);
182  if (!isValid(index(0), index(1))) {
183  continue;
184  }
185  vertexIndices.emplace_back(indexToOgreIndex(index(0), index(1)));
186  }
187  }
188 
189  // Plot triangles if we have enough vertices.
190  if (vertexIndices.size() > 2) {
191  // Create one or two triangles from the vertices depending on how many vertices we have.
192  if (vertexIndices.size() == 3) {
193  manualObject_->triangle(vertexIndices[0], vertexIndices[1], vertexIndices[2]);
194  } else {
195  manualObject_->quad(vertexIndices[0], vertexIndices[2], vertexIndices[3], vertexIndices[1]);
196  }
197  }
198  }
199 
200  // compute grid lines vertices
201  const bool isNthRow{i % gridCellDecimation == 0};
202  const bool isNthCol{j % gridCellDecimation == 0};
203  const bool isLastRow{i == rows - 1};
204  const bool isLastCol{j == cols - 1};
205  const bool isDrawMeshLines{(isNthRow && isNthCol) || (isLastRow && isNthCol) || (isLastCol && isNthRow) || (isLastRow && isLastCol)};
206 
207  if (!showGridLines || !isDrawMeshLines) {
208  continue;
209  }
210  std::vector<Ogre::Vector3> meshLineVertices = computeMeshLineVertices(i, j, gridCellDecimation, isNthRow, isNthCol, isLastRow,
211  isLastCol, resolution, topLeft, heightOrFlatData, isValid);
212 
213  // plot grid lines if we have enough points
214  if (meshLineVertices.size() > 2) {
215  meshLines_->addPoint(meshLineVertices[0]);
216  meshLines_->addPoint(meshLineVertices[1]);
217  meshLines_->newLine();
218 
219  if (meshLineVertices.size() == 3) {
220  meshLines_->addPoint(meshLineVertices[1]);
221  meshLines_->addPoint(meshLineVertices[2]);
222  meshLines_->newLine();
223  } else {
224  meshLines_->addPoint(meshLineVertices[1]);
225  meshLines_->addPoint(meshLineVertices[3]);
226  meshLines_->newLine();
227 
228  meshLines_->addPoint(meshLineVertices[3]);
229  meshLines_->addPoint(meshLineVertices[2]);
230  meshLines_->newLine();
231  }
232 
233  meshLines_->addPoint(meshLineVertices[2]);
234  meshLines_->addPoint(meshLineVertices[0]);
235  meshLines_->newLine();
236  }
237 
238  } // end for loop cols
239  } // end for loop rows
240 
241  manualObject_->end();
242  material_->getTechnique(0)->setLightingEnabled(false);
243 
244  if (alpha < 0.9998) {
245  material_->getTechnique(0)->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
246  material_->getTechnique(0)->setDepthWriteEnabled(false);
247  } else {
248  material_->getTechnique(0)->setSceneBlending(Ogre::SBT_REPLACE);
249  material_->getTechnique(0)->setDepthWriteEnabled(true);
250  }
251 
252  const auto stopTime = std::chrono::high_resolution_clock::now();
253  const auto elapsedTime = std::chrono::duration_cast<std::chrono::milliseconds>(stopTime - startTime);
254  ROS_DEBUG_STREAM("Visualization of grid_map took: " << elapsedTime.count() << " ms.");
255 }
256 
257 std::vector<Ogre::Vector3> GridMapVisual::computeMeshLineVertices(int i, int j, int gridCellDecimation, bool isNthRow, bool isNthCol,
258  bool isLastRow, bool isLastCol, double resolution,
259  const grid_map::Position& topLeft,
260  const Eigen::ArrayXXf& heightOrFlatData, const MaskArray& isValid) const {
261  std::vector<Ogre::Vector3> meshLineVertices;
262  meshLineVertices.reserve(4);
263  for (int k = 0; k < 2; ++k) {
264  for (int l = 0; l < 2; ++l) {
265  const int strideX = isLastRow ? (i % gridCellDecimation + int(isNthRow) * gridCellDecimation) : gridCellDecimation;
266  const int strideY = isLastCol ? (j % gridCellDecimation + int(isNthCol) * gridCellDecimation) : gridCellDecimation;
267  const int x = i - k * strideX;
268  const int y = j - l * strideY;
269  grid_map::Index index(x > 0 ? x : 0, y > 0 ? y : 0);
270  if (!isValid(index(0), index(1))) {
271  continue;
272  }
273  const grid_map::Position position = topLeft.array() - index.cast<double>() * resolution;
274  meshLineVertices.emplace_back(position(0), position(1), heightOrFlatData(index(0), index(1)));
275  }
276  }
277  return meshLineVertices;
278 }
279 
281  if (!manualObject_) {
282  static uint32_t count = 0;
284  ss << "Mesh" << count++;
285  manualObject_ = sceneManager_->createManualObject(ss.str());
286  manualObject_->setDynamic(true);
287  frameNode_->attachObject(manualObject_);
288 
289  ss << "Material";
290  materialName_ = ss.str();
291  material_ = Ogre::MaterialManager::getSingleton().create(materialName_, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
292  material_->setReceiveShadows(false);
293  material_->getTechnique(0)->setLightingEnabled(true);
294  material_->setCullingMode(Ogre::CULL_NONE);
295  }
296 
297  manualObject_->clear();
298  manualObject_->estimateVertexCount(nVertices);
299  manualObject_->begin(materialName_, Ogre::RenderOperation::OT_TRIANGLE_LIST);
300 }
301 
304  GridMapVisual::ColoringMethod coloringMethod, std::string cmap,
305  Ogre::ColourValue flatColor, double minIntensity, double maxIntensity,
306  bool autocomputeIntensity, Ogre::ColourValue minColor, Ogre::ColourValue maxColor) {
307  // Determine max and min intensity.
308  bool isIntensityColoringMethod = coloringMethod == ColoringMethod::INTENSITY_LAYER_INVERTED_COLORMAP ||
309  coloringMethod == ColoringMethod::INTENSITY_LAYER_COLORMAP ||
310  coloringMethod == ColoringMethod::INTENSITY_LAYER_MANUAL;
311  if (autocomputeIntensity && isIntensityColoringMethod) {
312  minIntensity = colorData.minCoeffOfFinites();
313  maxIntensity = minIntensity + std::max(colorData.maxCoeffOfFinites() - minIntensity, 0.2); // regularize the intensity range.
314  }
315 
316  const std::vector<std::vector<float>>& ctable = colorMap.at(cmap);
317 
318  switch (coloringMethod) {
320  return ColorArray::Constant(heightData.rows(), heightData.cols(), flatColor);
322  return colorData.unaryExpr([](float color) {
323  Eigen::Vector3f colorVectorRGB;
324  grid_map::colorValueToVector(color, colorVectorRGB);
325  return Ogre::ColourValue(colorVectorRGB(0), colorVectorRGB(1), colorVectorRGB(2));
326  });
328  return colorData.unaryExpr([&](float color) {
329  normalizeIntensity(color, minIntensity, maxIntensity);
330  return getInterpolatedColor(color, minColor, maxColor);
331  });
333  return colorData.unaryExpr([&](float color) {
334  normalizeIntensity(color, minIntensity, maxIntensity);
335  return getColorMap(color, ctable);
336  });
338  return colorData.unaryExpr([&](float color) {
339  normalizeIntensity(color, minIntensity, maxIntensity);
340  return getColorMap(1.f - color, ctable);
341  });
342  default:
343  throw std::invalid_argument(std::string("An unknown coloring method was provided: ") +
344  std::to_string(static_cast<int>(coloringMethod)));
345  }
346 }
347 
348 void GridMapVisual::initializeMeshLines(size_t cols, size_t rows, double resolution, double alpha, double lineWidth) {
349  meshLines_->setColor(0.0, 0.0, 0.0, alpha);
350  meshLines_->setLineWidth(resolution * lineWidth);
351  meshLines_->setMaxPointsPerLine(2);
352  // In the algorithm below, we have to account for max. 4 lines per cell.
353  const size_t nLines = 2 * (rows * (cols - 1) + cols * (rows - 1));
354  meshLines_->setNumLines(nLines);
355 }
356 
357 GridMapVisual::MaskArray GridMapVisual::computeIsValidMask(std::vector<std::string> basicLayers) {
358  MaskArray isValid = MaskArray::Ones(map_.getSize()(0), map_.getSize()(1));
359  for (const std::string& layer : basicLayers) {
360  if (map_.exists(layer)) {
361  isValid = isValid && map_.get(layer).array().unaryExpr([](float v) { return std::isfinite(v); });
362  }
363  }
364  return isValid;
365 }
366 
367 void GridMapVisual::printMissingBasicLayers(const std::vector<std::string>& basicLayers) const {
368  std::stringstream missingBasicLayers{};
369  std::copy_if(basicLayers.cbegin(), basicLayers.cend(), std::ostream_iterator<std::string>(missingBasicLayers, "\n"),
370  [&](const std::string& basicLayer) { return !map_.exists(basicLayer); });
371 
372  if (missingBasicLayers.str().empty()) {
373  return;
374  }
375 
376  ROS_WARN_STREAM_THROTTLE(warningMessageThrottlePeriod_, "The following basic layers are missing from the grid map:\n"
377  << missingBasicLayers.str());
378 }
379 
380 void GridMapVisual::setFramePosition(const Ogre::Vector3& position) {
381  frameNode_->setPosition(position);
382 }
383 
384 void GridMapVisual::setFrameOrientation(const Ogre::Quaternion& orientation) {
385  frameNode_->setOrientation(orientation);
386 }
387 
388 std::vector<std::string> GridMapVisual::getLayerNames() {
389  return map_.getLayers();
390 }
391 
392 void GridMapVisual::normalizeIntensity(float& intensity, float min_intensity, float max_intensity) {
393  intensity = std::min(intensity, max_intensity);
394  intensity = std::max(intensity, min_intensity);
395  intensity = (intensity - min_intensity) / (max_intensity - min_intensity);
396 }
397 
398 Ogre::ColourValue GridMapVisual::getRainbowColor(float intensity) {
399  intensity = std::min(intensity, 1.0f);
400  intensity = std::max(intensity, 0.0f);
401 
402  float h = intensity * 5.0f + 1.0f;
403  int i = floor(h);
404  float f = h - i;
405  if (!(i & 1)) f = 1 - f; // if i is even
406  float n = 1 - f;
407 
408  Ogre::ColourValue color;
409  if (i <= 1)
410  color[0] = n, color[1] = 0, color[2] = 1;
411  else if (i == 2)
412  color[0] = 0, color[1] = n, color[2] = 1;
413  else if (i == 3)
414  color[0] = 0, color[1] = 1, color[2] = n;
415  else if (i == 4)
416  color[0] = n, color[1] = 1, color[2] = 0;
417  else if (i >= 5)
418  color[0] = 1, color[1] = n, color[2] = 0;
419 
420  return color;
421 }
422 
423 // Get interpolated color value.
424 Ogre::ColourValue GridMapVisual::getInterpolatedColor(float intensity, Ogre::ColourValue min_color, Ogre::ColourValue max_color) {
425  intensity = std::min(intensity, 1.0f);
426  intensity = std::max(intensity, 0.0f);
427 
428  Ogre::ColourValue color;
429  color.r = intensity * (max_color.r - min_color.r) + min_color.r;
430  color.g = intensity * (max_color.g - min_color.g) + min_color.g;
431  color.b = intensity * (max_color.b - min_color.b) + min_color.b;
432 
433  return color;
434 }
435 
436 } // namespace grid_map_rviz_plugin
#define ROS_WARN_STREAM_THROTTLE(period, args)
boost::shared_ptr< rviz::BillboardLine > meshLines_
f
void setFramePosition(const Ogre::Vector3 &position)
const Matrix & get(const std::string &layer) const
const std::vector< std::string > & getBasicLayers() const
const Size & getSize() const
static void normalizeIntensity(float &intensity, float minIntensity, float maxIntensity)
const std::vector< std::string > & getLayers() const
static constexpr double warningMessageThrottlePeriod_
const std::map< std::string, std::vector< std::vector< float > > > colorMap
static Ogre::ColourValue getRainbowColor(float intensity)
void convertToDefaultStartIndex()
double getResolution() const
Ogre::ColourValue getInterpolatedColor(float intensity, Ogre::ColourValue minColor, Ogre::ColourValue maxColor)
static bool fromMessage(const grid_map_msgs::GridMap &message, grid_map::GridMap &gridMap, const std::vector< std::string > &layers, bool copyBasicLayers=true, bool copyAllNonBasicLayers=true)
Eigen::Vector2d Position
std::vector< std::string > getLayerNames()
Eigen::Array2i Index
GridMapVisual(Ogre::SceneManager *sceneManager, Ogre::SceneNode *parentNode)
void computeVisualization(float alpha, bool showGridLines, bool flatTerrain, std::string heightLayer, bool flatColor, bool noColor, Ogre::ColourValue meshColor, bool mapLayerColor, std::string colorLayer, std::string colorMap, bool useColorMap, bool invertColorMap, Ogre::ColourValue minColor, Ogre::ColourValue maxColor, bool autocomputeIntensity, float minIntensity, float maxIntensity, float gridLineThickness, int gridCellDecimation)
Eigen::MatrixXf Matrix
ColorArray computeColorValues(MatrixConstRef heightData, MatrixConstRef colorData, ColoringMethod coloringMethod, std::string colorMap, Ogre::ColourValue flatColor, double minIntensity, double maxIntensity, bool autocomputeIntensity, Ogre::ColourValue minColor, Ogre::ColourValue maxColor)
#define ROS_DEBUG_STREAM(args)
void initializeAndBeginManualObject(size_t nVertices)
void setFrameOrientation(const Ogre::Quaternion &orientation)
void printMissingBasicLayers(const std::vector< std::string > &basicLayers) const
Logs a warning message which lists the basic layers that are missing from the grid map...
Eigen::Ref< const grid_map::Matrix > MatrixConstRef
bool exists(const std::string &layer) const
MaskArray computeIsValidMask(std::vector< std::string > basicLayers)
std::vector< Ogre::Vector3 > computeMeshLineVertices(int i, int j, int gridCellDecimation, bool isNthRow, bool isNthCol, bool isLastRow, bool isLastCol, double resolution, const grid_map::Position &topLeft, const Eigen::ArrayXXf &heightOrFlatData, const MaskArray &isValid) const
bool colorValueToVector(const unsigned long &colorValue, Eigen::Vector3i &colorVector)
void initializeMeshLines(size_t cols, size_t rows, double resolution, double alpha, double lineWidth)
bool getPosition(const Index &index, Position &position) const
Eigen::Array< bool, Eigen::Dynamic, Eigen::Dynamic > MaskArray
Eigen::Array< Ogre::ColourValue, Eigen::Dynamic, Eigen::Dynamic > ColorArray
static Ogre::ColourValue getColorMap(float intensity, const std::vector< std::vector< float >> &ctable)
void setMessage(const grid_map_msgs::GridMap::ConstPtr &msg)
#define ROS_DEBUG(...)


grid_map_rviz_plugin
Author(s): Philipp Krüsi , Péter Fankhauser
autogenerated on Wed Jul 5 2023 02:23:55