42
42
#include < ros/ros.h>
43
43
#include < grid_map_ros/GridMapRosConverter.hpp>
44
44
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
+ }
46
68
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) {
48
71
std::shared_ptr<GridMapGeo> vrt_map = std::make_shared<GridMapGeo>();
49
72
50
73
Eigen::Vector3d query_position_lv03 = query_position;
51
74
// / Convert LV03 to WGS84
52
75
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 ());
55
78
56
79
std::cout << " Loading VRT Map:" << std::endl;
57
80
std::cout << " - map_center_wgs84:" << map_center_wgs84.transpose () << std::endl;
58
- // /TODO: Discover extent from corners
81
+ // / TODO: Discover extent from corners
59
82
Eigen::Vector2d extent_wgs84 (0.5 , 0.5 );
60
83
vrt_map->initializeFromVrt (path, map_center_wgs84.head (2 ), extent_wgs84);
61
84
std::cout << " - Success!" << std::endl;
@@ -70,13 +93,13 @@ void LoadTerrainFromVrt(std::string path, const Eigen::Vector3d &query_position,
70
93
map.setFrameId (" map" );
71
94
for (grid_map::GridMapIterator iterator (map); !iterator.isPastEnd (); ++iterator) {
72
95
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
74
97
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
76
99
double dummy;
77
100
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);
80
103
// std::cout << " - cell_position_wgs84:" << cell_position_wgs84.transpose() << std::endl;
81
104
82
105
Eigen::Vector2d local_wgs84 = cell_position_wgs84 - map_center_wgs84.head (2 );
@@ -106,7 +129,7 @@ int main(int argc, char **argv) {
106
129
107
130
for (int i = 0 ; i < 4 ; i++) {
108
131
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;
110
133
111
134
grid_map::GridMap map;
112
135
grid_map::GridMap vrt_map;
@@ -117,13 +140,11 @@ int main(int argc, char **argv) {
117
140
grid_map::GridMapRosConverter::toMessage (map, msg);
118
141
map_pub.publish (msg);
119
142
120
-
121
143
grid_map_msgs::GridMap msg2;
122
144
grid_map::GridMapRosConverter::toMessage (vrt_map, msg2);
123
145
map_pub2.publish (msg2);
124
146
}
125
147
126
-
127
148
ros::spin ();
128
149
return 0 ;
129
150
}
0 commit comments