Skip to content

Commit 41b1186

Browse files
committed
Load position and extent from VRT server
F
1 parent d16e558 commit 41b1186

File tree

2 files changed

+26
-12
lines changed

2 files changed

+26
-12
lines changed

grid_map_geo/include/grid_map_geo/grid_map_geo.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -107,7 +107,7 @@ class GridMapGeo {
107107
*/
108108
bool initializeFromGeotiff(const std::string& path);
109109

110-
bool initializeFromVrt(const std::string& path);
110+
bool initializeFromVrt(const std::string& path, const Eigen::Vector2d &map_center, Eigen::Vector2d &extent);
111111

112112
/**
113113
* @brief Load a color layer from a geotiff file (orthomosaic)

grid_map_geo/src/grid_map_geo.cpp

Lines changed: 25 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -142,7 +142,7 @@ bool GridMapGeo::initializeFromGeotiff(const std::string &path) {
142142
return true;
143143
}
144144

145-
bool GridMapGeo::initializeFromVrt(const std::string &path) {
145+
bool GridMapGeo::initializeFromVrt(const std::string &path, const Eigen::Vector2d &map_center, Eigen::Vector2d &extent) {
146146
GDALAllRegister();
147147
GDALDataset *dataset = (GDALDataset *)GDALOpen(path.c_str(), GA_ReadOnly);
148148
if (!dataset) {
@@ -176,35 +176,50 @@ bool GridMapGeo::initializeFromVrt(const std::string &path) {
176176
std::cout << "Width: " << width << " Height: " << height << " Resolution: " << resolution << std::endl;
177177

178178
// pixelSizeY is negative because the origin of the image is the north-east corner and positive
179-
// Y pixel coordinates go towards the south
180-
const double lengthX = resolution * width;
181-
const double lengthY = resolution * height;
179+
// Y pixel coordinates go towards the south
180+
int grid_width = extent(0)/std::abs(resolution);
181+
int grid_height = extent(1)/std::abs(resolution);
182+
const double lengthX = resolution * grid_width;
183+
const double lengthY = resolution * grid_height;
182184
grid_map::Length length(lengthX, lengthY);
185+
std::cout << "length: " << length.transpose() << std::endl;
183186

184-
double mapcenter_e = originX + pixelSizeX * width * 0.5;
185-
double mapcenter_n = originY + pixelSizeY * height * 0.5;
187+
double mapcenter_e = map_center(0);
188+
double mapcenter_n = map_center(1);
186189
maporigin_.espg = static_cast<ESPG>(std::stoi(epsg_code));
187190
maporigin_.position = Eigen::Vector3d(mapcenter_e, mapcenter_n, 0.0);
188191

189192
Eigen::Vector2d position{Eigen::Vector2d::Zero()};
190193

191194
grid_map_.setGeometry(length, resolution, position);
195+
std::cout << "position: " << position.transpose() << std::endl;
192196
/// TODO: Use TF for geocoordinates
193197
grid_map_.setFrameId(frame_id_);
194198
grid_map_.add("elevation");
195199
GDALRasterBand *elevationBand = dataset->GetRasterBand(1);
196200

197-
std::vector<float> data(width * height, 0.0f);
198-
elevationBand->RasterIO(GF_Read, 0, 0, width, height, &data[0], width, height, GDT_Float32, 0, 0);
201+
Eigen::Vector2d center_px((mapcenter_e - geoTransform[0])/geoTransform[1], (mapcenter_n - geoTransform[3])/geoTransform[5]);
199202

203+
const auto raster_io_x_offset = center_px.x() - grid_width / 2;
204+
const auto raster_io_y_offset = center_px.y() - grid_height / 2;
205+
std::cout << "center_px: " << center_px.transpose() << std::endl;
206+
207+
208+
std::vector<float> data(grid_width * grid_height, 0.0f);
209+
const auto raster_err = elevationBand->RasterIO(GF_Read, raster_io_x_offset, raster_io_y_offset, grid_width,
210+
grid_height, &data[0], grid_width, grid_height, GDT_Float32, 0, 0);
211+
if (raster_err != CPLE_None) {
212+
std::cout << "Error loading raster" << std::endl;
213+
return false;
214+
}
200215
grid_map::Matrix &layer_elevation = grid_map_["elevation"];
201216
for (grid_map::GridMapIterator iterator(grid_map_); !iterator.isPastEnd(); ++iterator) {
202217
const grid_map::Index gridMapIndex = *iterator;
203218
// TODO: This may be wrong if the pixelSizeY > 0
204-
int x = width - 1 - gridMapIndex(0);
219+
int x = grid_width - 1 - gridMapIndex(0);
205220
int y = gridMapIndex(1);
206221

207-
layer_elevation(x, y) = data[gridMapIndex(0) + width * gridMapIndex(1)];
222+
layer_elevation(x, y) = data[gridMapIndex(0) + grid_width * gridMapIndex(1)];
208223
}
209224

210225
static tf2_ros::StaticTransformBroadcaster static_broadcaster;
@@ -221,7 +236,6 @@ bool GridMapGeo::initializeFromVrt(const std::string &path) {
221236
static_transformStamped.transform.rotation.z = 0.0;
222237
static_transformStamped.transform.rotation.w = 1.0;
223238
static_broadcaster.sendTransform(static_transformStamped);
224-
225239
return true;
226240
}
227241

0 commit comments

Comments
 (0)