@@ -154,9 +154,9 @@ bool GridMapGeo::initializeFromGdalDataset(const std::string &path, bool align_t
154
154
} else {
155
155
if (maporigin_.position .x () < corners.top_left .x () ||
156
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;
157
+ maporigin_.position .y () < corners.bottom_right .y () ||
158
+ maporigin_.position .y () > corners.top_left .y ()) {
159
+ std::cerr << " The configured map origin is outside of raster dataset! " << std::endl;
160
160
return false ;
161
161
}
162
162
}
@@ -189,11 +189,11 @@ bool GridMapGeo::initializeFromGdalDataset(const std::string &path, bool align_t
189
189
190
190
// Compute the center in pixel space, then get the raster bounds nXOff and nYOff to extract with RasterIO
191
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 ;
192
+ const auto raster_io_x_offset = center_px.x () - grid_width / 2 ;
193
+ const auto raster_io_y_offset = center_px.y () - grid_height / 2 ;
194
194
195
195
std::vector<float > data (grid_width * grid_height, 0 .0f );
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 );
196
+ const auto raster_err = elevationBand->RasterIO (GF_Read, raster_io_x_offset, raster_io_y_offset , grid_width, grid_height, &data[0 ], grid_width, grid_height, GDT_Float32, 0 , 0 );
197
197
if (raster_err != CPLE_None ) {
198
198
return false ;
199
199
}
0 commit comments