4343#include < grid_map_core/iterators/CircleIterator.hpp>
4444#include < grid_map_core/iterators/GridMapIterator.hpp>
4545
46+ #include < cassert>
47+
4648#if __APPLE__
4749#include < cpl_string.h>
4850#include < gdal.h>
@@ -83,16 +85,17 @@ bool GridMapGeo::Load(const std::string &map_path, bool algin_terrain, const std
8385
8486bool GridMapGeo::initializeFromGdalDataset (const std::string &path, bool align_terrain) {
8587 GDALAllRegister ();
86- GDALDataset *dataset = (GDALDataset *)GDALOpen (path.c_str (), GA_ReadOnly);
88+ GDALDatasetUniquePtr dataset;
89+ dataset = GDALDatasetUniquePtr (GDALDataset::FromHandle (GDALOpen ( path.c_str (), GA_ReadOnly )));
8790 if (!dataset) {
8891 std::cout << __func__ << " Failed to open '" << path << " '" << std::endl;
8992 return false ;
9093 }
9194 std::cout << std::endl << " Loading GDAL Dataset for gridmap" << std::endl;
9295
9396 double originX, originY, pixelSizeX, pixelSizeY;
94- double geoTransform[ 6 ] ;
95- if (dataset->GetGeoTransform (geoTransform) == CE_None) {
97+ std::array< double , 6 > geoTransform ;
98+ if (dataset->GetGeoTransform (geoTransform. data () ) == CE_None) {
9699 originX = geoTransform[0 ];
97100 originY = geoTransform[3 ];
98101 pixelSizeX = geoTransform[1 ];
@@ -133,10 +136,30 @@ bool GridMapGeo::initializeFromGdalDataset(const std::string &path, bool align_t
133136 grid_map::Length length (lengthX, lengthY);
134137 std::cout << " GMLX: " << lengthX << " GMLY: " << lengthY << std::endl;
135138
136- double mapcenter_e = originX + pixelSizeX * grid_width * 0.5 ;
137- double mapcenter_n = originY + pixelSizeY * grid_height * 0.5 ;
138- maporigin_.espg = ESPG::CH1903_LV03;
139- maporigin_.position = Eigen::Vector3d (mapcenter_e, mapcenter_n, 0.0 );
139+ // ! @todo use WGS-84 as map origin if specified
140+ // ! @todo
141+ // ! @todo check the origin point is non-void (not in the middle of the ocean)
142+ Corners corners;
143+ if (!getGeoCorners (dataset, corners)) {
144+ std::cerr << " Failed to get geographic corners of dataset!" << std::endl;
145+ return false ;
146+ }
147+
148+ if (std::isnan (maporigin_.position .x ()) || std::isnan (maporigin_.position .y ())) {
149+ // ! @todo Figure out how to not hard code the espg, perhaps using the dataset GEOGCRS attribute.
150+ // maporigin_.espg = ESPG::CH1903_LV03;
151+ const double mapcenter_e = (corners.top_left .x () + corners.bottom_right .x ()) / 2.0 ;
152+ const double mapcenter_n = (corners.top_left .y () + corners.bottom_right .y ()) / 2.0 ;
153+ maporigin_.position = Eigen::Vector3d (mapcenter_e, mapcenter_n, 0.0 );
154+ } else {
155+ if (maporigin_.position .x () < corners.top_left .x () ||
156+ maporigin_.position .x () > corners.bottom_right .x () ||
157+ maporigin_.position .y () < corners.top_left .y () ||
158+ maporigin_.position .y () > corners.bottom_left .y ()) {
159+ std::cerr << " Requested map origin is outside of raster dataset" << std::endl;
160+ return false ;
161+ }
162+ }
140163
141164 Eigen::Vector2d position{Eigen::Vector2d::Zero ()};
142165
@@ -164,8 +187,13 @@ bool GridMapGeo::initializeFromGdalDataset(const std::string &path, bool align_t
164187 assert (raster_count == 1 ); // expect only elevation data, otherwise it's the wrong dataset.
165188 GDALRasterBand *elevationBand = dataset->GetRasterBand (1 );
166189
190+ // Compute the center in pixel space, then get the raster bounds nXOff and nYOff to extract with RasterIO
191+ const auto center_px = geoToImageNoRot (geoTransform, {maporigin_.position .x (), maporigin_.position .y ()});
192+ const auto nxOff = center_px.x () - grid_width / 2 ;
193+ const auto nYOff = center_px.y () - grid_height / 2 ;
194+
167195 std::vector<float > data (grid_width * grid_height, 0 .0f );
168- const auto raster_err = elevationBand->RasterIO (GF_Read, 0 , 0 , grid_width, grid_height, &data[0 ], grid_width, grid_height, GDT_Float32, 0 , 0 );
196+ const auto raster_err = elevationBand->RasterIO (GF_Read, nxOff, nYOff , grid_width, grid_height, &data[0 ], grid_width, grid_height, GDT_Float32, 0 , 0 );
169197 if (raster_err != CPLE_None ) {
170198 return false ;
171199 }
@@ -186,10 +214,10 @@ bool GridMapGeo::initializeFromGdalDataset(const std::string &path, bool align_t
186214 altitude = grid_map_.atPosition (" elevation" , Eigen::Vector2d (0.0 , 0.0 ));
187215 }
188216
189- Eigen::Translation3d meshlab_translation (0.0 , 0.0 , -altitude);
190- Eigen::AngleAxisd meshlab_rotation (Eigen::AngleAxisd::Identity ());
191- Eigen::Isometry3d transform = meshlab_translation * meshlab_rotation; // Apply affine transformation.
192- grid_map_ = grid_map_.getTransformedMap (transform, " elevation" , grid_map_.getFrameId (), true );
217+ // Eigen::Translation3d meshlab_translation(0.0, 0.0, -altitude);
218+ // Eigen::AngleAxisd meshlab_rotation(Eigen::AngleAxisd::Identity());
219+ // Eigen::Isometry3d transform = meshlab_translation * meshlab_rotation; // Apply affine transformation.
220+ // grid_map_ = grid_map_.getTransformedMap(transform, "elevation", grid_map_.getFrameId(), true);
193221 return true ;
194222}
195223
@@ -203,8 +231,8 @@ bool GridMapGeo::addColorFromGeotiff(const std::string &path) {
203231 std::cout << std::endl << " Loading color layer from GeoTIFF file for gridmap" << std::endl;
204232
205233 double originX, originY, pixelSizeX, pixelSizeY;
206- double geoTransform[ 6 ] ;
207- if (dataset->GetGeoTransform (geoTransform) == CE_None) {
234+ std::array< double , 6 > geoTransform ;
235+ if (dataset->GetGeoTransform (geoTransform. data () ) == CE_None) {
208236 originX = geoTransform[0 ];
209237 originY = geoTransform[3 ];
210238 pixelSizeX = geoTransform[1 ];
@@ -264,8 +292,8 @@ bool GridMapGeo::addLayerFromGeotiff(const std::string &layer_name, const std::s
264292 std::cout << std::endl << " Loading color layer from GeoTIFF file for gridmap" << std::endl;
265293
266294 double originX, originY, pixelSizeX, pixelSizeY;
267- double geoTransform[ 6 ] ;
268- if (dataset->GetGeoTransform (geoTransform) == CE_None) {
295+ std::array< double , 6 > geoTransform ;
296+ if (dataset->GetGeoTransform (geoTransform. data () ) == CE_None) {
269297 originX = geoTransform[0 ];
270298 originY = geoTransform[3 ];
271299 pixelSizeX = geoTransform[1 ];
0 commit comments