@@ -141,7 +141,7 @@ bool GridMapGeo::initializeFromGeotiff(const std::string &path) {
141
141
return true ;
142
142
}
143
143
144
- bool GridMapGeo::initializeFromVrt (const std::string &path) {
144
+ bool GridMapGeo::initializeFromVrt (const std::string &path, const Eigen::Vector2d &map_center, Eigen::Vector2d &extent ) {
145
145
GDALAllRegister ();
146
146
GDALDataset *dataset = (GDALDataset *)GDALOpen (path.c_str (), GA_ReadOnly);
147
147
if (!dataset) {
@@ -175,35 +175,50 @@ bool GridMapGeo::initializeFromVrt(const std::string &path) {
175
175
std::cout << " Width: " << width << " Height: " << height << " Resolution: " << resolution << std::endl;
176
176
177
177
// pixelSizeY is negative because the origin of the image is the north-east corner and positive
178
- // Y pixel coordinates go towards the south
179
- const double lengthX = resolution * width;
180
- const double lengthY = resolution * height;
178
+ // Y pixel coordinates go towards the south
179
+ int grid_width = extent (0 )/std::abs (resolution);
180
+ int grid_height = extent (1 )/std::abs (resolution);
181
+ const double lengthX = resolution * grid_width;
182
+ const double lengthY = resolution * grid_height;
181
183
grid_map::Length length (lengthX, lengthY);
184
+ std::cout << " length: " << length.transpose () << std::endl;
182
185
183
- double mapcenter_e = originX + pixelSizeX * width * 0.5 ;
184
- double mapcenter_n = originY + pixelSizeY * height * 0.5 ;
186
+ double mapcenter_e = map_center ( 0 ) ;
187
+ double mapcenter_n = map_center ( 1 ) ;
185
188
maporigin_.espg = static_cast <ESPG>(std::stoi (epsg_code));
186
189
maporigin_.position = Eigen::Vector3d (mapcenter_e, mapcenter_n, 0.0 );
187
190
188
191
Eigen::Vector2d position{Eigen::Vector2d::Zero ()};
189
192
190
193
grid_map_.setGeometry (length, resolution, position);
194
+ std::cout << " position: " << position.transpose () << std::endl;
191
195
// / TODO: Use TF for geocoordinates
192
196
grid_map_.setFrameId (frame_id_);
193
197
grid_map_.add (" elevation" );
194
198
GDALRasterBand *elevationBand = dataset->GetRasterBand (1 );
195
199
196
- std::vector<float > data (width * height, 0 .0f );
197
- elevationBand->RasterIO (GF_Read, 0 , 0 , width, height, &data[0 ], width, height, GDT_Float32, 0 , 0 );
200
+ Eigen::Vector2d center_px ((mapcenter_e - geoTransform[0 ])/geoTransform[1 ], (mapcenter_n - geoTransform[3 ])/geoTransform[5 ]);
198
201
202
+ const auto raster_io_x_offset = center_px.x () - grid_width / 2 ;
203
+ const auto raster_io_y_offset = center_px.y () - grid_height / 2 ;
204
+ std::cout << " center_px: " << center_px.transpose () << std::endl;
205
+
206
+
207
+ std::vector<float > data (grid_width * grid_height, 0 .0f );
208
+ const auto raster_err = elevationBand->RasterIO (GF_Read, raster_io_x_offset, raster_io_y_offset, grid_width,
209
+ grid_height, &data[0 ], grid_width, grid_height, GDT_Float32, 0 , 0 );
210
+ if (raster_err != CPLE_None) {
211
+ std::cout << " Error loading raster" << std::endl;
212
+ return false ;
213
+ }
199
214
grid_map::Matrix &layer_elevation = grid_map_[" elevation" ];
200
215
for (grid_map::GridMapIterator iterator (grid_map_); !iterator.isPastEnd (); ++iterator) {
201
216
const grid_map::Index gridMapIndex = *iterator;
202
217
// TODO: This may be wrong if the pixelSizeY > 0
203
- int x = width - 1 - gridMapIndex (0 );
218
+ int x = grid_width - 1 - gridMapIndex (0 );
204
219
int y = gridMapIndex (1 );
205
220
206
- layer_elevation (x, y) = data[gridMapIndex (0 ) + width * gridMapIndex (1 )];
221
+ layer_elevation (x, y) = data[gridMapIndex (0 ) + grid_width * gridMapIndex (1 )];
207
222
}
208
223
209
224
static tf2_ros::StaticTransformBroadcaster static_broadcaster;
@@ -220,7 +235,6 @@ bool GridMapGeo::initializeFromVrt(const std::string &path) {
220
235
static_transformStamped.transform .rotation .z = 0.0 ;
221
236
static_transformStamped.transform .rotation .w = 1.0 ;
222
237
static_broadcaster.sendTransform (static_transformStamped);
223
-
224
238
return true ;
225
239
}
226
240
0 commit comments