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> 34 frameNode_ = parentNode->createChildSceneNode();
45 Ogre::MaterialManager::getSingleton().remove(
material_->getName());
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();
65 ROS_DEBUG(
"Unable to visualize grid map, no map data. Use setMessage() first!");
71 if (layerNames.size() < 1) {
72 ROS_DEBUG(
"Unable to visualize grid map, map must contain at least one layer.");
75 if ((!flatTerrain && !
map_.
exists(heightLayer)) || (!noColor && !flatColor && !
map_.
exists(colorLayer))) {
76 ROS_DEBUG(
"Unable to visualize grid map, requested layer(s) not available.");
86 if (rows < 2 || cols < 2) {
87 ROS_DEBUG(
"GridMap has not enough cells.");
96 const size_t nVertices = cols * rows;
105 gridCellDecimation = std::max(gridCellDecimation, 1);
109 if (std::find(basicLayers.begin(), basicLayers.end(), heightLayer) == basicLayers.end()) {
110 basicLayers.emplace_back(heightLayer);
118 Eigen::ArrayXXf heightOrFlatData;
120 heightOrFlatData = Eigen::ArrayXXf::Zero(heightData.rows(), heightData.cols());
122 heightOrFlatData = heightData.array();
127 if (flatColor || noColor) {
129 }
else if(mapLayerColor) {
131 }
else if (!useColorMap) {
133 }
else if (!invertColorMap) {
139 const auto colorValues =
computeColorValues(heightData, colorData, coloringMethod, colorMap, meshColor,
140 minIntensity, maxIntensity, autocomputeIntensity, minColor, maxColor);
146 Eigen::ArrayXXi indexToOgreIndex;
147 indexToOgreIndex.setConstant(rows, cols, -1);
152 for (
size_t i = 0; i < rows; ++i) {
153 for (
size_t j = 0; j < cols; ++j) {
155 std::vector<int> vertices;
156 std::vector<Ogre::ColourValue> colors;
160 if (!isValid(index(0), index(1))) {
164 manualObject_->position(position(0), position(1), heightOrFlatData(index(0), index(1)));
166 const Ogre::ColourValue& color = colorValues(index(0), index(1));
169 indexToOgreIndex(index(0), index(1)) = ogreIndex;
173 if (i == 0 || j == 0) {
178 std::vector<int> vertexIndices;
179 for (
size_t k = 0; k < 2; k++) {
180 for (
size_t l = 0; l < 2; l++) {
182 if (!isValid(index(0), index(1))) {
185 vertexIndices.emplace_back(indexToOgreIndex(index(0), index(1)));
190 if (vertexIndices.size() > 2) {
192 if (vertexIndices.size() == 3) {
193 manualObject_->triangle(vertexIndices[0], vertexIndices[1], vertexIndices[2]);
195 manualObject_->quad(vertexIndices[0], vertexIndices[2], vertexIndices[3], vertexIndices[1]);
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)};
207 if (!showGridLines || !isDrawMeshLines) {
210 std::vector<Ogre::Vector3> meshLineVertices =
computeMeshLineVertices(i, j, gridCellDecimation, isNthRow, isNthCol, isLastRow,
211 isLastCol, resolution, topLeft, heightOrFlatData, isValid);
214 if (meshLineVertices.size() > 2) {
219 if (meshLineVertices.size() == 3) {
242 material_->getTechnique(0)->setLightingEnabled(
false);
244 if (alpha < 0.9998) {
245 material_->getTechnique(0)->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
246 material_->getTechnique(0)->setDepthWriteEnabled(
false);
248 material_->getTechnique(0)->setSceneBlending(Ogre::SBT_REPLACE);
249 material_->getTechnique(0)->setDepthWriteEnabled(
true);
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.");
258 bool isLastRow,
bool isLastCol,
double resolution,
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;
270 if (!isValid(index(0), index(1))) {
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)));
277 return meshLineVertices;
282 static uint32_t count = 0;
284 ss <<
"Mesh" << count++;
291 material_ = Ogre::MaterialManager::getSingleton().create(
materialName_, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
293 material_->getTechnique(0)->setLightingEnabled(
true);
294 material_->setCullingMode(Ogre::CULL_NONE);
305 Ogre::ColourValue flatColor,
double minIntensity,
double maxIntensity,
306 bool autocomputeIntensity, Ogre::ColourValue minColor, Ogre::ColourValue maxColor) {
311 if (autocomputeIntensity && isIntensityColoringMethod) {
312 minIntensity = colorData.minCoeffOfFinites();
313 maxIntensity = minIntensity + std::max(colorData.maxCoeffOfFinites() - minIntensity, 0.2);
316 const std::vector<std::vector<float>>& ctable =
colorMap.at(cmap);
318 switch (coloringMethod) {
320 return ColorArray::Constant(heightData.rows(), heightData.cols(), flatColor);
322 return colorData.unaryExpr([](
float color) {
323 Eigen::Vector3f colorVectorRGB;
325 return Ogre::ColourValue(colorVectorRGB(0), colorVectorRGB(1), colorVectorRGB(2));
328 return colorData.unaryExpr([&](
float color) {
333 return colorData.unaryExpr([&](
float color) {
338 return colorData.unaryExpr([&](
float color) {
343 throw std::invalid_argument(std::string(
"An unknown coloring method was provided: ") +
344 std::to_string(static_cast<int>(coloringMethod)));
350 meshLines_->setLineWidth(resolution * lineWidth);
353 const size_t nLines = 2 * (rows * (cols - 1) + cols * (rows - 1));
359 for (
const std::string& layer : basicLayers) {
361 isValid = isValid &&
map_.
get(layer).array().unaryExpr([](
float v) {
return std::isfinite(v); });
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); });
372 if (missingBasicLayers.str().empty()) {
377 << missingBasicLayers.str());
393 intensity = std::min(intensity, max_intensity);
394 intensity = std::max(intensity, min_intensity);
395 intensity = (intensity - min_intensity) / (max_intensity - min_intensity);
399 intensity = std::min(intensity, 1.0
f);
400 intensity = std::max(intensity, 0.0
f);
402 float h = intensity * 5.0f + 1.0f;
405 if (!(i & 1)) f = 1 - f;
408 Ogre::ColourValue color;
410 color[0] = n, color[1] = 0, color[2] = 1;
412 color[0] = 0, color[1] = n, color[2] = 1;
414 color[0] = 0, color[1] = 1, color[2] = n;
416 color[0] = n, color[1] = 1, color[2] = 0;
418 color[0] = 1, color[1] = n, color[2] = 0;
425 intensity = std::min(intensity, 1.0
f);
426 intensity = std::max(intensity, 0.0
f);
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;
#define ROS_WARN_STREAM_THROTTLE(period, args)
boost::shared_ptr< rviz::BillboardLine > meshLines_
Ogre::SceneManager * sceneManager_
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
Ogre::MaterialPtr material_
static Ogre::ColourValue getRainbowColor(float intensity)
void convertToDefaultStartIndex()
double getResolution() const
Ogre::ManualObject * manualObject_
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)
std::vector< std::string > getLayerNames()
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)
std::string materialName_
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
Ogre::SceneNode * frameNode_
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)