Skip to content

Commit 64161b8

Browse files
authored
Always place dem at center of the map (#21)
* Always place dem at center of the map F Do not align altitude F * remove local origins
1 parent cd568e9 commit 64161b8

File tree

2 files changed

+26
-23
lines changed

2 files changed

+26
-23
lines changed

include/grid_map_geo/grid_map_geo.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -84,8 +84,8 @@ class GridMapGeo {
8484
* @param origin
8585
*/
8686
void getGlobalOrigin(ESPG& src_coord, Eigen::Vector3d& origin) {
87-
src_coord = localorigin_wgs84_.espg;
88-
origin = localorigin_wgs84_.position;
87+
src_coord = maporigin_.espg;
88+
origin = maporigin_.position;
8989
};
9090

9191
/**
@@ -173,6 +173,6 @@ class GridMapGeo {
173173
double localorigin_e_{789823.93}; // duerrboden berghaus
174174
double localorigin_n_{177416.56};
175175
double localorigin_altitude_{0.0};
176-
Location localorigin_wgs84_;
176+
Location maporigin_;
177177
};
178178
#endif

src/grid_map_geo.cpp

Lines changed: 23 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -94,25 +94,28 @@ bool GridMapGeo::initializeFromGeotiff(const std::string &path, bool align_terra
9494

9595
double mapcenter_e = originX + pixelSizeX * width * 0.5;
9696
double mapcenter_n = originY + pixelSizeY * height * 0.5;
97-
98-
Eigen::Vector3d origin_lv03 =
99-
transformCoordinates(ESPG::WGS84, std::string(pszProjection), localorigin_wgs84_.position);
100-
localorigin_e_ = origin_lv03(0);
101-
localorigin_n_ = origin_lv03(1);
102-
localorigin_altitude_ = origin_lv03(2);
97+
maporigin_.espg = ESPG::CH1903_LV03;
98+
maporigin_.position = Eigen::Vector3d(mapcenter_e, mapcenter_n, 0.0);
10399

104100
Eigen::Vector2d position{Eigen::Vector2d::Zero()};
105101

106-
if (align_terrain) {
107-
std::cout << "[GridMapGeo] Aligning terrain!" << std::endl;
108-
double map_position_x = mapcenter_e - localorigin_e_;
109-
double map_position_y = mapcenter_n - localorigin_n_;
110-
position = Eigen::Vector2d(map_position_x, map_position_y);
111-
} else {
112-
std::cout << "[GridMapGeo] Not aligning terrain!" << std::endl;
113-
}
102+
/// TODO: Generalize to set local origin as center of map position
103+
// Eigen::Vector3d origin_lv03 =
104+
// transformCoordinates(ESPG::WGS84, std::string(pszProjection), localorigin_wgs84_.position);
105+
// localorigin_e_ = origin_lv03(0);
106+
// localorigin_n_ = origin_lv03(1);
107+
// localorigin_altitude_ = origin_lv03(2);
108+
// if (align_terrain) {
109+
// std::cout << "[GridMapGeo] Aligning terrain!" << std::endl;
110+
// double map_position_x = mapcenter_e - localorigin_e_;
111+
// double map_position_y = mapcenter_n - localorigin_n_;
112+
// position = Eigen::Vector2d(map_position_x, map_position_y);
113+
// } else {
114+
// std::cout << "[GridMapGeo] Not aligning terrain!" << std::endl;
115+
// }
114116

115117
grid_map_.setGeometry(length, resolution, position);
118+
/// TODO: Use TF for geocoordinates
116119
grid_map_.setFrameId("map");
117120
grid_map_.add("elevation");
118121
GDALRasterBand *elevationBand = dataset->GetRasterBand(1);
@@ -137,10 +140,10 @@ bool GridMapGeo::initializeFromGeotiff(const std::string &path, bool align_terra
137140
altitude = grid_map_.atPosition("elevation", Eigen::Vector2d(0.0, 0.0));
138141
}
139142

140-
Eigen::Translation3d meshlab_translation(0.0, 0.0, -altitude);
141-
Eigen::AngleAxisd meshlab_rotation(Eigen::AngleAxisd::Identity());
142-
Eigen::Isometry3d transform = meshlab_translation * meshlab_rotation; // Apply affine transformation.
143-
grid_map_ = grid_map_.getTransformedMap(transform, "elevation", grid_map_.getFrameId(), true);
143+
// Eigen::Translation3d meshlab_translation(0.0, 0.0, -altitude);
144+
// Eigen::AngleAxisd meshlab_rotation(Eigen::AngleAxisd::Identity());
145+
// Eigen::Isometry3d transform = meshlab_translation * meshlab_rotation; // Apply affine transformation.
146+
// grid_map_ = grid_map_.getTransformedMap(transform, "elevation", grid_map_.getFrameId(), true);
144147
return true;
145148
}
146149

@@ -323,6 +326,6 @@ bool GridMapGeo::AddLayerOffset(const double offset_distance, const std::string
323326

324327
void GridMapGeo::setGlobalOrigin(ESPG src_coord, const Eigen::Vector3d origin) {
325328
// Transform global origin into CH1903 / LV03 coordinates
326-
localorigin_wgs84_.espg = src_coord;
327-
localorigin_wgs84_.position = origin;
329+
maporigin_.espg = src_coord;
330+
maporigin_.position = origin;
328331
}

0 commit comments

Comments
 (0)