@@ -94,25 +94,28 @@ bool GridMapGeo::initializeFromGeotiff(const std::string &path, bool align_terra
94
94
95
95
double mapcenter_e = originX + pixelSizeX * width * 0.5 ;
96
96
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 );
103
99
104
100
Eigen::Vector2d position{Eigen::Vector2d::Zero ()};
105
101
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
+ // }
114
116
115
117
grid_map_.setGeometry (length, resolution, position);
118
+ // / TODO: Use TF for geocoordinates
116
119
grid_map_.setFrameId (" map" );
117
120
grid_map_.add (" elevation" );
118
121
GDALRasterBand *elevationBand = dataset->GetRasterBand (1 );
@@ -137,10 +140,10 @@ bool GridMapGeo::initializeFromGeotiff(const std::string &path, bool align_terra
137
140
altitude = grid_map_.atPosition (" elevation" , Eigen::Vector2d (0.0 , 0.0 ));
138
141
}
139
142
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);
144
147
return true ;
145
148
}
146
149
@@ -323,6 +326,6 @@ bool GridMapGeo::AddLayerOffset(const double offset_distance, const std::string
323
326
324
327
void GridMapGeo::setGlobalOrigin (ESPG src_coord, const Eigen::Vector3d origin) {
325
328
// 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;
328
331
}
0 commit comments