Skip to content

Commit 85b075f

Browse files
committed
Add normal computation
1 parent 64161b8 commit 85b075f

File tree

2 files changed

+43
-4
lines changed

2 files changed

+43
-4
lines changed

include/grid_map_geo/grid_map_geo.h

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

171+
/**
172+
* @brief Compute normal vectors of the surface
173+
*
174+
* @param layer_name
175+
* @param reference_layer
176+
*/
177+
void AddLayerNormals(std::string reference_layer);
178+
171179
protected:
172180
grid_map::GridMap grid_map_;
173181
double localorigin_e_{789823.93}; // duerrboden berghaus

src/grid_map_geo.cpp

Lines changed: 35 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -324,8 +324,39 @@ bool GridMapGeo::AddLayerOffset(const double offset_distance, const std::string
324324
return true;
325325
}
326326

327-
void GridMapGeo::setGlobalOrigin(ESPG src_coord, const Eigen::Vector3d origin) {
328-
// Transform global origin into CH1903 / LV03 coordinates
329-
maporigin_.espg = src_coord;
330-
maporigin_.position = origin;
327+
void GridMapGeo::AddLayerNormals(const std::string reference_layer) {
328+
grid_map_.add(reference_layer + "_normal_x");
329+
grid_map_.add(reference_layer + "_normal_y");
330+
grid_map_.add(reference_layer + "_normal_z");
331+
332+
grid_map::Matrix &layer_elevation = grid_map_[reference_layer];
333+
grid_map::Matrix &layer_normal_x = grid_map_[reference_layer + "_normal_x"];
334+
grid_map::Matrix &layer_normal_y = grid_map_[reference_layer + "_normal_y"];
335+
grid_map::Matrix &layer_normal_z = grid_map_[reference_layer + "_normal_z"];
336+
337+
unsigned width = grid_map_.getSize()(0);
338+
unsigned height = grid_map_.getSize()(1);
339+
double resolution = grid_map_.getResolution();
340+
// Compute normals from elevation map
341+
// Surface normal calculation from: https://www.flipcode.com/archives/Calculating_Vertex_Normals_for_Height_Maps.shtml
342+
for (grid_map::GridMapIterator iterator(grid_map_); !iterator.isPastEnd(); ++iterator) {
343+
const grid_map::Index gridMapIndex = *iterator;
344+
345+
/// TODO: Verify normal by visualization
346+
int x = gridMapIndex(0);
347+
int y = height - 1 - gridMapIndex(1);
348+
349+
float sx = layer_elevation(x < width - 1 ? x + 1 : x, y) - layer_elevation(x > 0 ? x - 1 : x, y);
350+
if (x == 0 || x == width - 1) sx *= 2;
351+
352+
float sy = layer_elevation(x, y < height - 1 ? y + 1 : y) - layer_elevation(x, y > 0 ? y - 1 : y);
353+
if (y == 0 || y == height - 1) sy *= 2;
354+
355+
Eigen::Vector3d normal(Eigen::Vector3d(sx, sy, 2 * resolution));
356+
normal.normalize();
357+
358+
layer_normal_x(x, y) = normal(0);
359+
layer_normal_y(x, y) = normal(1);
360+
layer_normal_z(x, y) = normal(2);
361+
}
331362
}

0 commit comments

Comments
 (0)