@@ -142,6 +142,89 @@ bool GridMapGeo::initializeFromGeotiff(const std::string &path) {
142
142
return true ;
143
143
}
144
144
145
+ bool GridMapGeo::initializeFromVrt (const std::string &path) {
146
+ GDALAllRegister ();
147
+ GDALDataset *dataset = (GDALDataset *)GDALOpen (path.c_str (), GA_ReadOnly);
148
+ if (!dataset) {
149
+ std::cout << " Failed to open" << std::endl;
150
+ return false ;
151
+ }
152
+ std::cout << std::endl << " Loading GeoTIFF file for gridmap" << std::endl;
153
+
154
+ double originX, originY, pixelSizeX, pixelSizeY;
155
+ double geoTransform[6 ];
156
+ if (dataset->GetGeoTransform (geoTransform) == CE_None) {
157
+ originX = geoTransform[0 ];
158
+ originY = geoTransform[3 ];
159
+ pixelSizeX = geoTransform[1 ];
160
+ pixelSizeY = geoTransform[5 ];
161
+ } else {
162
+ std::cout << " Failed read geotransform" << std::endl;
163
+ return false ;
164
+ }
165
+
166
+ const char *pszProjection = dataset->GetProjectionRef ();
167
+ std::cout << std::endl << " Wkt ProjectionRef: " << pszProjection << std::endl;
168
+
169
+ const OGRSpatialReference *spatial_ref = dataset->GetSpatialRef ();
170
+ std::string name_coordinate = spatial_ref->GetAttrValue (" geogcs" );
171
+ std::string epsg_code = spatial_ref->GetAttrValue (" AUTHORITY" , 1 );
172
+ // Get image metadata
173
+ unsigned width = dataset->GetRasterXSize ();
174
+ unsigned height = dataset->GetRasterYSize ();
175
+ double resolution = pixelSizeX;
176
+ std::cout << " Width: " << width << " Height: " << height << " Resolution: " << resolution << std::endl;
177
+
178
+ // 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;
182
+ grid_map::Length length (lengthX, lengthY);
183
+
184
+ double mapcenter_e = originX + pixelSizeX * width * 0.5 ;
185
+ double mapcenter_n = originY + pixelSizeY * height * 0.5 ;
186
+ maporigin_.espg = static_cast <ESPG>(std::stoi (epsg_code));
187
+ maporigin_.position = Eigen::Vector3d (mapcenter_e, mapcenter_n, 0.0 );
188
+
189
+ Eigen::Vector2d position{Eigen::Vector2d::Zero ()};
190
+
191
+ grid_map_.setGeometry (length, resolution, position);
192
+ // / TODO: Use TF for geocoordinates
193
+ grid_map_.setFrameId (frame_id_);
194
+ grid_map_.add (" elevation" );
195
+ GDALRasterBand *elevationBand = dataset->GetRasterBand (1 );
196
+
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 );
199
+
200
+ grid_map::Matrix &layer_elevation = grid_map_[" elevation" ];
201
+ for (grid_map::GridMapIterator iterator (grid_map_); !iterator.isPastEnd (); ++iterator) {
202
+ const grid_map::Index gridMapIndex = *iterator;
203
+ // TODO: This may be wrong if the pixelSizeY > 0
204
+ int x = width - 1 - gridMapIndex (0 );
205
+ int y = gridMapIndex (1 );
206
+
207
+ layer_elevation (x, y) = data[gridMapIndex (0 ) + width * gridMapIndex (1 )];
208
+ }
209
+
210
+ static tf2_ros::StaticTransformBroadcaster static_broadcaster;
211
+ geometry_msgs::TransformStamped static_transformStamped;
212
+
213
+ static_transformStamped.header .stamp = ros::Time::now ();
214
+ static_transformStamped.header .frame_id = name_coordinate;
215
+ static_transformStamped.child_frame_id = frame_id_;
216
+ static_transformStamped.transform .translation .x = mapcenter_e;
217
+ static_transformStamped.transform .translation .y = mapcenter_n;
218
+ static_transformStamped.transform .translation .z = 0.0 ;
219
+ static_transformStamped.transform .rotation .x = 0.0 ;
220
+ static_transformStamped.transform .rotation .y = 0.0 ;
221
+ static_transformStamped.transform .rotation .z = 0.0 ;
222
+ static_transformStamped.transform .rotation .w = 1.0 ;
223
+ static_broadcaster.sendTransform (static_transformStamped);
224
+
225
+ return true ;
226
+ }
227
+
145
228
bool GridMapGeo::addColorFromGeotiff (const std::string &path) {
146
229
GDALAllRegister ();
147
230
GDALDataset *dataset = (GDALDataset *)GDALOpen (path.c_str (), GA_ReadOnly);
0 commit comments