Skip to content

Commit af0f113

Browse files
committed
Fix XY flip error
Signed-off-by: Ryan Friedman <[email protected]>
1 parent 39f4ea6 commit af0f113

File tree

4 files changed

+10
-8
lines changed

4 files changed

+10
-8
lines changed

README.md

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -51,3 +51,6 @@ grid_map_geo map_publisher --ros-args \
5151
# To debug from the launch file
5252
ros2 launch grid_map_geo load_vrt_launch.xml
5353
```
54+
55+
**Note:** `grid_map_geo` uses asserts to catch coding errors; they are enabled by default when
56+
building in debug mode, and removed from release mode.

include/grid_map_geo/transform.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -171,7 +171,6 @@ inline Eigen::Vector2d geoToImageNoRot(const std::array<double, 6>& geoTransform
171171
* @return
172172
*/
173173
inline bool getGeoCorners(const GDALDatasetUniquePtr& datasetPtr, Corners& corners) {
174-
double originX, originY, pixelSizeX, pixelSizeY;
175174
std::array<double, 6> geoTransform;
176175

177176
// https://gdal.org/tutorials/geotransforms_tut.html#introduction-to-geotransforms

src/grid_map_geo.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -154,9 +154,9 @@ bool GridMapGeo::initializeFromGdalDataset(const std::string &path, bool align_t
154154
} else {
155155
if (maporigin_.position.x() < corners.top_left.x() ||
156156
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;
160160
return false;
161161
}
162162
}
@@ -189,11 +189,11 @@ bool GridMapGeo::initializeFromGdalDataset(const std::string &path, bool align_t
189189

190190
// Compute the center in pixel space, then get the raster bounds nXOff and nYOff to extract with RasterIO
191191
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;
194194

195195
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);
197197
if (raster_err != CPLE_None ) {
198198
return false;
199199
}

src/map_publisher.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -106,7 +106,7 @@ class MapPublisher : public rclcpp::Node {
106106

107107
map_ = std::make_shared<GridMapGeo>();
108108
map_->setMaxMapSizePixels(max_map_width, max_map_height);
109-
map_->setGlobalOrigin(ESPG::WGS84, Eigen::Vector3d(map_origin_latitude, map_origin_longitude, 0.0));
109+
map_->setGlobalOrigin(ESPG::WGS84, Eigen::Vector3d(map_origin_longitude, map_origin_latitude, 0.0));
110110
map_->Load(gdal_dataset_path, false, color_path);
111111

112112
auto timer_callback = [this]() -> void {

0 commit comments

Comments
 (0)