Skip to content

Commit 83b8292

Browse files
committed
Use gdal transforms
Remove geoconversion library F F
1 parent 53e1ecb commit 83b8292

File tree

4 files changed

+41
-134
lines changed

4 files changed

+41
-134
lines changed

grid_map_geo/include/grid_map_geo/geo_conversions.h

Lines changed: 0 additions & 115 deletions
This file was deleted.

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, const Eigen::Vector2d &map_center, Eigen::Vector2d &extent);
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: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -141,7 +141,8 @@ bool GridMapGeo::initializeFromGeotiff(const std::string &path) {
141141
return true;
142142
}
143143

144-
bool GridMapGeo::initializeFromVrt(const std::string &path, const Eigen::Vector2d &map_center, Eigen::Vector2d &extent) {
144+
bool GridMapGeo::initializeFromVrt(const std::string &path, const Eigen::Vector2d &map_center,
145+
Eigen::Vector2d &extent) {
145146
GDALAllRegister();
146147
GDALDataset *dataset = (GDALDataset *)GDALOpen(path.c_str(), GA_ReadOnly);
147148
if (!dataset) {
@@ -175,9 +176,9 @@ bool GridMapGeo::initializeFromVrt(const std::string &path, const Eigen::Vector2
175176
std::cout << "Width: " << width << " Height: " << height << " Resolution: " << resolution << std::endl;
176177

177178
// 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-
int grid_width = extent(0)/std::abs(resolution);
180-
int grid_height = extent(1)/std::abs(resolution);
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);
181182
const double lengthX = resolution * grid_width;
182183
const double lengthY = resolution * grid_height;
183184
grid_map::Length length(lengthX, lengthY);
@@ -195,13 +196,13 @@ bool GridMapGeo::initializeFromVrt(const std::string &path, const Eigen::Vector2
195196
grid_map_.add("elevation");
196197
GDALRasterBand *elevationBand = dataset->GetRasterBand(1);
197198

198-
Eigen::Vector2d center_px((map_center(1) - geoTransform[0])/geoTransform[1], (map_center(0) - geoTransform[3])/geoTransform[5]);
199+
Eigen::Vector2d center_px((map_center(1) - geoTransform[0]) / geoTransform[1],
200+
(map_center(0) - geoTransform[3]) / geoTransform[5]);
199201

200202
const auto raster_io_x_offset = center_px.x() - grid_width / 2;
201203
const auto raster_io_y_offset = center_px.y() - grid_height / 2;
202204
std::cout << "center_px: " << center_px.transpose() << std::endl;
203205

204-
205206
std::vector<float> data(grid_width * grid_height, 0.0f);
206207
const auto raster_err = elevationBand->RasterIO(GF_Read, raster_io_x_offset, raster_io_y_offset, grid_width,
207208
grid_height, &data[0], grid_width, grid_height, GDT_Float32, 0, 0);

grid_map_geo/src/terrain_loader.cpp

Lines changed: 33 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -42,20 +42,43 @@
4242
#include <ros/ros.h>
4343
#include <grid_map_ros/GridMapRosConverter.hpp>
4444

45-
#include "grid_map_geo/geo_conversions.h"
45+
#include <gdal/ogr_spatialref.h>
46+
47+
constexpr int ESPG_WGS84 = 4326;
48+
constexpr int ESPG_CH1903_LV03 = 21781;
49+
50+
void transformCoordinates(int src_coord, const double &x, const double &y, const double &z, int tgt_coord, double &x_t,
51+
double &y_t, double &z_t) {
52+
OGRSpatialReference source, target;
53+
source.importFromEPSG(src_coord);
54+
target.importFromEPSG(tgt_coord);
55+
56+
OGRPoint p;
57+
p.setX(x);
58+
p.setY(y);
59+
p.setZ(z);
60+
p.assignSpatialReference(&source);
61+
62+
p.transformTo(&target);
63+
x_t = p.getX();
64+
y_t = p.getY();
65+
z_t = p.getZ();
66+
return;
67+
}
4668

47-
void LoadTerrainFromVrt(std::string path, const Eigen::Vector3d &query_position, const Eigen::Vector2d &offset, grid_map::GridMap &map, grid_map::GridMap &vrt_map_object) {
69+
void LoadTerrainFromVrt(std::string path, const Eigen::Vector3d &query_position, const Eigen::Vector2d &offset,
70+
grid_map::GridMap &map, grid_map::GridMap &vrt_map_object) {
4871
std::shared_ptr<GridMapGeo> vrt_map = std::make_shared<GridMapGeo>();
4972

5073
Eigen::Vector3d query_position_lv03 = query_position;
5174
/// Convert LV03 to WGS84
5275
Eigen::Vector3d map_center_wgs84; // Map center in WGS84
53-
GeoConversions::reverse(query_position_lv03(0), query_position_lv03(1), query_position_lv03(2), map_center_wgs84.x(),
54-
map_center_wgs84.y(), map_center_wgs84.z());
76+
transformCoordinates(ESPG_CH1903_LV03, query_position_lv03(0), query_position_lv03(1), query_position_lv03(2),
77+
ESPG_WGS84, map_center_wgs84.x(), map_center_wgs84.y(), map_center_wgs84.z());
5578

5679
std::cout << "Loading VRT Map:" << std::endl;
5780
std::cout << " - map_center_wgs84:" << map_center_wgs84.transpose() << std::endl;
58-
///TODO: Discover extent from corners
81+
/// TODO: Discover extent from corners
5982
Eigen::Vector2d extent_wgs84(0.5, 0.5);
6083
vrt_map->initializeFromVrt(path, map_center_wgs84.head(2), extent_wgs84);
6184
std::cout << " - Success!" << std::endl;
@@ -70,13 +93,13 @@ void LoadTerrainFromVrt(std::string path, const Eigen::Vector3d &query_position,
7093
map.setFrameId("map");
7194
for (grid_map::GridMapIterator iterator(map); !iterator.isPastEnd(); ++iterator) {
7295
const grid_map::Index index = *iterator;
73-
Eigen::Vector2d cell_position; // Position of cell relative to map coordinates
96+
Eigen::Vector2d cell_position; // Position of cell relative to map coordinates
7497
map.getPosition(index, cell_position);
75-
auto cell_position_lv03 = cell_position + query_position_lv03.head(2);// Position of cell in CH1903/LV03
98+
auto cell_position_lv03 = cell_position + query_position_lv03.head(2); // Position of cell in CH1903/LV03
7699
double dummy;
77100
Eigen::Vector2d cell_position_wgs84;
78-
GeoConversions::reverse(cell_position_lv03(0), cell_position_lv03(1), 0.0, cell_position_wgs84.x(),
79-
cell_position_wgs84.y(), dummy);
101+
transformCoordinates(ESPG_CH1903_LV03, cell_position_lv03(0), cell_position_lv03(1), cell_position_lv03(2),
102+
ESPG_WGS84, cell_position_wgs84.x(), cell_position_wgs84.y(), dummy);
80103
// std::cout << " - cell_position_wgs84:" << cell_position_wgs84.transpose() << std::endl;
81104

82105
Eigen::Vector2d local_wgs84 = cell_position_wgs84 - map_center_wgs84.head(2);
@@ -106,7 +129,7 @@ int main(int argc, char **argv) {
106129

107130
for (int i = 0; i < 4; i++) {
108131
Eigen::Vector3d offset = static_cast<double>(i) * Eigen::Vector3d(2500.0, 2500.0, 0.0);
109-
Eigen::Vector3d query_position = test_position + offset;
132+
Eigen::Vector3d query_position = test_position + offset;
110133

111134
grid_map::GridMap map;
112135
grid_map::GridMap vrt_map;
@@ -117,13 +140,11 @@ int main(int argc, char **argv) {
117140
grid_map::GridMapRosConverter::toMessage(map, msg);
118141
map_pub.publish(msg);
119142

120-
121143
grid_map_msgs::GridMap msg2;
122144
grid_map::GridMapRosConverter::toMessage(vrt_map, msg2);
123145
map_pub2.publish(msg2);
124146
}
125147

126-
127148
ros::spin();
128149
return 0;
129150
}

0 commit comments

Comments
 (0)