-
Notifications
You must be signed in to change notification settings - Fork 21
Description
Purpose
This issue is to capture the desire and design, for dynamically loading terrain.
Current Behavior
Currently, grid_map_geo supports loading a single .tif file. Before flight, a user must create the .tif file for the region they plan to fly, and then modify their launch or parameter to point to the correct file. While this works great for small tests where the user is familiar with terrain generation and flies areas known well in advance, it doesn't work for casual users who just want terrain data working wherever they fly automatically.
Furthermore, it only works with tif files, so users can't use any terrain data supplied by other tools.
Desired Behavior
A user can fetch terrain using a common terrain server, such as ArduPilot Terrain Generator. A processing step occurs onboard, and then the terrain tile(s) are suitable for use in grid_map_geo. grid_map_geo should be able to work with more than just .tif files. If the user requests color data loaded, the color data may be in a different datum/resolution/raster size than the DEM data.
Proposed Design
Utilize GDAL's VRT format as the pre-processing step for terrain. This would allow loading multiple terrain tiles, either to cover more area, or to allow overlapping tiles of differing resolution. While the VRT generation could be done manually with a call to gdalbuildvrt, it could be automated in the future, or generated server-side.
Next, modify the grid_map_geo implementation to work off either a single .tif file, or also given a path to a .vrt file.
Finally, allow grid_map_geo to support loading partial terrain, instead of the entire vrt dataset, and then allow dynamic unload/load of regions through additional API calls.
Using GDAL tools with the ArduPilot terrain database
Fetching terrain
One can fetch terrain from the ArduPilot terrain server like so:
$ gdalinfo /vsizip/vsicurl/https://terrain.ardupilot.org/SRTM1/N00E006.hgt.zip/N00E006.hgt
Driver: SRTMHGT/SRTMHGT File Format
Files: /vsizip/vsicurl/https://terrain.ardupilot.org/SRTM1/N00E006.hgt.zip/N00E006.hgt
Size is 3601, 3601
Coordinate System is:
GEOGCRS["WGS 84",
DATUM["World Geodetic System 1984",
ELLIPSOID["WGS 84",6378137,298.257223563,
LENGTHUNIT["metre",1]]],
PRIMEM["Greenwich",0,
ANGLEUNIT["degree",0.0174532925199433]],
CS[ellipsoidal,2],
AXIS["geodetic latitude (Lat)",north,
ORDER[1],
ANGLEUNIT["degree",0.0174532925199433]],
AXIS["geodetic longitude (Lon)",east,
ORDER[2],
ANGLEUNIT["degree",0.0174532925199433]],
ID["EPSG",4326]]
Data axis to CRS axis mapping: 2,1
Origin = (5.999861111111112,1.000138888888889)
Pixel Size = (0.000277777777778,-0.000277777777778)
Metadata:
AREA_OR_POINT=Point
Corner Coordinates:
Upper Left ( 5.9998611, 1.0001389) ( 5d59'59.50"E, 1d 0' 0.50"N)
Lower Left ( 5.9998611, -0.0001389) ( 5d59'59.50"E, 0d 0' 0.50"S)
Upper Right ( 7.0001389, 1.0001389) ( 7d 0' 0.50"E, 1d 0' 0.50"N)
Lower Right ( 7.0001389, -0.0001389) ( 7d 0' 0.50"E, 0d 0' 0.50"S)
Center ( 6.5000000, 0.5000000) ( 6d30' 0.00"E, 0d30' 0.00"N)
Band 1 Block=3601x1 Type=Int16, ColorInterp=Undefined
NoData Value=-32768
Unit Type: m
Building a VRT
For a single file:
gdalbuildvrt index.vrt /vsizip/vsicurl/https://terrain.ardupilot.org/SRTM1/N00E006.hgt.zip/N00E006.hgt<VRTDataset rasterXSize="3601" rasterYSize="3601">
<SRS dataAxisToSRSAxisMapping="2,1">GEOGCS["WGS 84",DATUM["WGS_1984",SPHEROID["WGS 84",6378137,298.257223563,AUTHORITY["EPSG","7030"]],AUTHORITY["EPSG","6326"]],PRIMEM["Greenwich",0,AUTHORITY["EPSG","8901"]],UNIT["degree",0.0174532925199433,AUTHORITY["EPSG","9122"]],AXIS["Latitude",NORTH],AXIS["Longitude",EAST],AUTHORITY["EPSG","4326"]]</SRS>
<GeoTransform> 5.9998611111111115e+00, 2.7777777777777778e-04, 0.0000000000000000e+00, 1.0001388888888889e+00, 0.0000000000000000e+00, -2.7777777777777778e-04</GeoTransform>
<VRTRasterBand dataType="Int16" band="1">
<NoDataValue>-32768</NoDataValue>
<ComplexSource>
<SourceFilename relativeToVRT="0">/vsizip/vsicurl/https://terrain.ardupilot.org/SRTM1/N00E006.hgt.zip/N00E006.hgt</SourceFilename>
<SourceBand>1</SourceBand>
<SourceProperties RasterXSize="3601" RasterYSize="3601" DataType="Int16" BlockXSize="3601" BlockYSize="1" />
<SrcRect xOff="0" yOff="0" xSize="3601" ySize="3601" />
<DstRect xOff="0" yOff="0" xSize="3601" ySize="3601" />
<NODATA>-32768</NODATA>
</ComplexSource>
</VRTRasterBand>
</VRTDataset>Or, for multiple:
gdalbuildvrt index.vrt /vsizip/vsicurl/https://terrain.ardupilot.org/SRTM3/North_America/N10W110.hgt.zip/N10W110.hgt /vsizip/vsicurl/https://terrain.ardupilot.org/SRTM3/North_America/N15W062.hgt.zip/N15W062.hgt
<VRTDataset rasterXSize="58801" rasterYSize="7201">
<SRS dataAxisToSRSAxisMapping="2,1">GEOGCS["WGS 84",DATUM["WGS_1984",SPHEROID["WGS 84",6378137,298.257223563,AUTHORITY["EPSG","7030"]],AUTHORITY["EPSG","6326"]],PRIMEM["Greenwich",0,AUTHORITY["EPSG","8901"]],UNIT["degree",0.0174532925199433,AUTHORITY["EPSG","9122"]],AXIS["Latitude",NORTH],AXIS["Longitude",EAST],AUTHORITY["EPSG","4326"]]</SRS>
<GeoTransform> -1.1000041666666667e+02, 8.3333333333333339e-04, 0.0000000000000000e+00, 1.6000416666666666e+01, 0.0000000000000000e+00, -8.3333333333333339e-04</GeoTransform>
<VRTRasterBand dataType="Int16" band="1">
<NoDataValue>-32768</NoDataValue>
<ComplexSource>
<SourceFilename relativeToVRT="0">/vsizip/vsicurl/https://terrain.ardupilot.org/SRTM3/North_America/N10W110.hgt.zip/N10W110.hgt</SourceFilename>
<SourceBand>1</SourceBand>
<SourceProperties RasterXSize="1201" RasterYSize="1201" DataType="Int16" BlockXSize="1201" BlockYSize="1" />
<SrcRect xOff="0" yOff="0" xSize="1201" ySize="1201" />
<DstRect xOff="0" yOff="6000" xSize="1201" ySize="1201" />
<NODATA>-32768</NODATA>
</ComplexSource>
<ComplexSource>
<SourceFilename relativeToVRT="0">/vsizip/vsicurl/https://terrain.ardupilot.org/SRTM3/North_America/N15W062.hgt.zip/N15W062.hgt</SourceFilename>
<SourceBand>1</SourceBand>
<SourceProperties RasterXSize="1201" RasterYSize="1201" DataType="Int16" BlockXSize="1201" BlockYSize="1" />
<SrcRect xOff="0" yOff="0" xSize="1201" ySize="1201" />
<DstRect xOff="57600" yOff="0" xSize="1201" ySize="1201" />
<NODATA>-32768</NODATA>
</ComplexSource>
</VRTRasterBand>
</VRTDataset>Query height of a single point at CMAC, which returns 467m elevation
$ gdallocationinfo /vsizip/vsicurl/https://terrain.ardupilot.org/SRTM1/S35E149.hgt.zip/S35E149.hgt 149.159350 35.363272
Report:
Location: (149P,35L)
Band 1:
Value: 467