Skip to content

Commit 0196574

Browse files
authored
Add normal computation (#30)
This commit adds a normal computation and ports it to ros2 branch
1 parent ef21a5d commit 0196574

File tree

2 files changed

+45
-0
lines changed

2 files changed

+45
-0
lines changed

include/grid_map_geo/grid_map_geo.hpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -177,6 +177,14 @@ class GridMapGeo {
177177
*/
178178
bool AddLayerOffset(const double offset_distance, const std::string& layer_name);
179179

180+
/**
181+
* @brief Compute normal vectors of the surface
182+
*
183+
* @param layer_name
184+
* @param reference_layer
185+
*/
186+
void AddLayerNormals(std::string reference_layer);
187+
180188
protected:
181189
grid_map::GridMap grid_map_;
182190
double localorigin_e_{789823.93}; // duerrboden berghaus

src/grid_map_geo.cpp

Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -329,3 +329,40 @@ void GridMapGeo::setGlobalOrigin(ESPG src_coord, const Eigen::Vector3d origin) {
329329
maporigin_.espg = src_coord;
330330
maporigin_.position = origin;
331331
}
332+
333+
void GridMapGeo::AddLayerNormals(const std::string reference_layer) {
334+
grid_map_.add(reference_layer + "_normal_x");
335+
grid_map_.add(reference_layer + "_normal_y");
336+
grid_map_.add(reference_layer + "_normal_z");
337+
338+
grid_map::Matrix &layer_elevation = grid_map_[reference_layer];
339+
grid_map::Matrix &layer_normal_x = grid_map_[reference_layer + "_normal_x"];
340+
grid_map::Matrix &layer_normal_y = grid_map_[reference_layer + "_normal_y"];
341+
grid_map::Matrix &layer_normal_z = grid_map_[reference_layer + "_normal_z"];
342+
343+
unsigned width = grid_map_.getSize()(0);
344+
unsigned height = grid_map_.getSize()(1);
345+
double resolution = grid_map_.getResolution();
346+
// Compute normals from elevation map
347+
// Surface normal calculation from: https://www.flipcode.com/archives/Calculating_Vertex_Normals_for_Height_Maps.shtml
348+
for (grid_map::GridMapIterator iterator(grid_map_); !iterator.isPastEnd(); ++iterator) {
349+
const grid_map::Index gridMapIndex = *iterator;
350+
351+
/// TODO: Verify normal by visualization
352+
int x = gridMapIndex(0);
353+
int y = height - 1 - gridMapIndex(1);
354+
355+
float sx = layer_elevation(x < width - 1 ? x + 1 : x, y) - layer_elevation(x > 0 ? x - 1 : x, y);
356+
if (x == 0 || x == width - 1) sx *= 2;
357+
358+
float sy = layer_elevation(x, y < height - 1 ? y + 1 : y) - layer_elevation(x, y > 0 ? y - 1 : y);
359+
if (y == 0 || y == height - 1) sy *= 2;
360+
361+
Eigen::Vector3d normal(Eigen::Vector3d(sx, sy, 2 * resolution));
362+
normal.normalize();
363+
364+
layer_normal_x(x, y) = normal(0);
365+
layer_normal_y(x, y) = normal(1);
366+
layer_normal_z(x, y) = normal(2);
367+
}
368+
}

0 commit comments

Comments
 (0)