|
| 1 | +\page heightmap_dem Load image heightmaps and Digital Elevation Models (DEM) |
| 2 | + |
| 3 | +# Overview |
| 4 | + |
| 5 | +## What are heightmaps and why are they useful for simulation? |
| 6 | + |
| 7 | +Simply put, a heightmap is common term used in computer graphics to refer to a 2D image where the value of each pixel or cell corresponds to the elevation or height of that specific point in the real world. |
| 8 | + |
| 9 | + |
| 10 | + |
| 11 | +Image reference: https://www.futurelearn.com/info/courses/advanced-archaeological-remote-sensing/0/steps/356833 |
| 12 | + |
| 13 | +They are useful for simulation because they offer a simple way to provide realistic digital representation of the terrain. |
| 14 | +For fields like robotics, accurate topography can be beneficial for develop algorithms and/or models for autonomous navigation, motion planning, task planning, and control because they can provide cost effective, rapid development cycles. |
| 15 | +Engineers can develop and test algorithms in these environments before physical deployment. |
| 16 | + |
| 17 | +In this tutorial we'll dive deeper into what makes heightmaps, where to get them, and how to process them to use for simulation in Gazebo. |
| 18 | + |
| 19 | +## Gazebo's supported heightmap types |
| 20 | + |
| 21 | +Gazebo supports creating a terrain from image heightmaps, meshes, and Digital Elevation Models (DEMs). |
| 22 | +While this tutorial will be focusing more in depth with DEMs, we will provide a quick overview of the other formats available to try out. |
| 23 | + |
| 24 | +### Image heightmaps |
| 25 | + |
| 26 | +Image heightmaps use a 2D grayscale image, where each pixel corresponds to the elevation at that point. Black (or `0`) represents the lowest point and while (or `255`) represents the highest. |
| 27 | +This is a simple and efficient way to store elevation data because it can use less memory compared to meshes and DEMs. |
| 28 | + |
| 29 | +The following example will look at the [demo created for Gazebo Fortress](https://app.gazebosim.org/OpenRobotics/fuel/models/Fortress%20heightmap). Below shows the black and white image is what gets referenced in SDF and fed into Gazebo (download the model from the previous link and look at the `model.sdf` file). |
| 30 | + |
| 31 | + |
| 32 | + |
| 33 | +What ends up getting rendered in Gazebo is shown below: |
| 34 | + |
| 35 | + |
| 36 | + |
| 37 | + |
| 38 | + |
| 39 | +### Meshes |
| 40 | + |
| 41 | +Another format used for realistic topography are meshes, which are 3D polygonal models. |
| 42 | +The supported file formats for meshes in Gazebo include DAE, GLTF, OBJ, and STL, and more. These models are best suited for worlds with tunnels, caves, or overhangs. |
| 43 | + |
| 44 | +Examples: |
| 45 | + |
| 46 | +\image html files/digital_elevation_models/mesh_tunnel_entrance.png width=80% |
| 47 | + |
| 48 | +\image html files/digital_elevation_models/mesh_cave.png width=80% |
| 49 | + |
| 50 | +Meshes were the format used for the [DARPA Subterranean Challenge (SubT) simulation](https://github.com/osrf/subt/wiki) |
| 51 | +and most were created from point cloud converted data (check out this [tutorial on how to convert point cloud data to a 3D mesh model for Gazebo](http://gazebosim.org/api/sim/10/pointcloud.html)). |
| 52 | +These heightmap meshes can be found [here on Fuel](https://app.gazebosim.org/OpenRobotics/fuel/collections/SubT%20Tech%20Repo). |
| 53 | + |
| 54 | +### Digital Elevation Models |
| 55 | + |
| 56 | +A Digital Elevation Model (DEM) is a 3D representation of a terrain's surface that does not include any objects like buildings or vegetation. |
| 57 | +DEMs are frequently created by using a combination of sensors, such as satellites, LIDAR, radar, or cameras. |
| 58 | +The terrain elevations for ground positions are sampled at regularly-spaced horizontal intervals. |
| 59 | + |
| 60 | +\image html files/digital_elevation_models/dem_monterey_bay.png width=80% |
| 61 | + |
| 62 | +<!-- TODO figure out better title --> |
| 63 | +# Walkthrough with DEMs for Gazebo |
| 64 | + |
| 65 | +There are two main types of DEM formats, a vector-based Triangular Irregular Network (TIN) or a grid of elevations (raster). |
| 66 | +In Gazebo, raster based formats (more specifically GeoTiff or `.tif` files) are the most tested formats but in theory Gazebo should be able to run any [GDAL](https://gdal.org/en/stable/index.html) default supported format |
| 67 | +(since GDAL is the backend library that Gazebo uses to read DEM files). |
| 68 | +Let's look at an example of getting DEMs from publicly available data and using some common open source tools to process them for Gazebo. |
| 69 | + |
| 70 | +## Obtaining data |
| 71 | + |
| 72 | +Many resources for publicly available data exist and include: |
| 73 | + |
| 74 | +* [OpenTopography](https://portal.opentopography.org/datasets) |
| 75 | +* [earthexplorer.usgs.gov](http://earthexplorer.usgs.gov) |
| 76 | +* [NASA's EarthData](https://www.earthdata.nasa.gov/topics/land-surface/digital-elevation-terrain-model-dem/data-access-tools) |
| 77 | +* [General Bathymetric Chart of the Oceans (GEBCO) data](https://www.gebco.net/) |
| 78 | +* [Other planetary DEMs (e.g., Moon or Mars)](https://astrogeology.usgs.gov/search?target=&system=&p=1&accscope=&searchBar=) |
| 79 | + |
| 80 | +For our example, we will use [OpenTopography](https://portal.opentopography.org/datasets), |
| 81 | +* Create an account if not done so already |
| 82 | +* Look for your area of interest, in this example, in the "Search by keyword" textbox enter `half dome` |
| 83 | +* In the results section, under "High Resolution Topography" click "Get Raster Data" |
| 84 | +* In the following page, |
| 85 | + |
| 86 | + * In the map, click the blue "Select a Region" button in the top left corner of the map to select the region to extract the DEM from |
| 87 | + \image html files/digital_elevation_models/open_topography_region_selection.png width=80% |
| 88 | + |
| 89 | + * The data output format should be GeoTiff and Digital Terrain Model (DTM) should be checked for Layer types |
| 90 | + * Click Submit |
| 91 | + |
| 92 | +* Once the data has finished processing, download the bundled results and unzip the file |
| 93 | + |
| 94 | +## Processing data |
| 95 | + |
| 96 | +Common open source tools for geospatial data include: |
| 97 | + |
| 98 | +* [Geospatial Data Abstraction Library (GDAL)](https://gdal.org/en/stable/): is a library and command line toolkit for reading and maipulating DEMs. |
| 99 | +This is the library that is used in Gazebo for reading DEMs and will be installed on your system if Gazebo is installed. |
| 100 | +* [QGIS](https://qgis.org/): a GUI for viewing, analyzing, editing, and publishing DEMs and relies on GDAL. |
| 101 | + |
| 102 | +Using [QGIS](https://qgis.org/), |
| 103 | + |
| 104 | +* (optional) When working with earth DEMs, it can be helpful to add a map layer (as the base layer) to verify the imported DEM is in the correct projection. |
| 105 | + |
| 106 | + * In the top toolbar, go to Layer > Add Layer > Add XYZ Layer... |
| 107 | + * In the dropdown menu under "XYZ Connections", select 'Google Satellite' or 'OpenStreetMap' > Click 'Add' > then 'Close' |
| 108 | + |
| 109 | +* In the top toolbar, go to Layer > Add Layer > Add Raster Layer... |
| 110 | +* Select the file that we downloaded and unzipped (from the instructions above) > Click 'Add' > then 'Close' |
| 111 | +* Check the Coordinate Reference System button at the bottom right to make sure it is set to 'EPSG:4326'. If not click on it and search for 'EPSG:4326', choose 'WGS 84 - SPSG:4326' and click 'OK' |
| 112 | +* Enter the lat/lon coordinates retrieved from USGS earlier in the "Coordinate" textbox at the bottom (i.e., `37.7444, -119.5341`) > hit the Enter key (this will move the viewpoint to the desired location) |
| 113 | +* In the bottom bar, update "Scale" to `1:50000` |
| 114 | + |
| 115 | + * If the optional step was followed, QGIS should look something like the image below, otherwise only the DEM will be displayed |
| 116 | + |
| 117 | +\image html files/digital_elevation_models/qgis_satellite_and_dem.png width=80% |
| 118 | + |
| 119 | + |
| 120 | +* If the Processing Toolbox panel isn't open, click the gear icon in the top toolbar |
| 121 | + |
| 122 | + * Search for "Clip raster by extent" and double click to open the dialog |
| 123 | + * Input layer: should be the imported GeoTiff |
| 124 | + * Clipping extent: click the down arrow and select "Draw on Map Canvas" to select your desired region |
| 125 | + |
| 126 | + \image html files/digital_elevation_models/qgis_draw_on_map_canvas.png width=80% |
| 127 | + |
| 128 | + * Clipped (extent): Click the button with the "..." dots > Save to File ... > select the desired save location and give the file a name |
| 129 | + * Click the "Run" button, this will add a new layer to the layers panel (on the left) |
| 130 | + |
| 131 | +## SDF setup |
| 132 | + |
| 133 | +Now let's set up the SDF model, in a terminal run: `gdalinfo -stats <newly_saved.tif>` |
| 134 | + |
| 135 | +Look for the output: `Size is <x_value> <y_value>` |
| 136 | + |
| 137 | +This is the `x` and `y` values that need to be entered in the `<size>` tag. To calculate z, subtract the `Minimum` from the `Maximum` elevation (i.e., `z = Maximum - Minimum`). |
| 138 | + |
| 139 | +Optionally, to move the model down to Gazebo's camera default viewpoint, update the `z` of the `<pos>` tag to be the negative of the `Maximum` elevation (i.e., `<pos>0 0 -Maximum</pos>`). Note when using seabed data (e.g., GEBCO), negate the `Minimum` instead. |
| 140 | + |
| 141 | +The model should look similar to the following: |
| 142 | + |
| 143 | +```xml |
| 144 | +<model name="half_dome"> |
| 145 | + <static>true</static> |
| 146 | + <link name="link"> |
| 147 | + <collision name="collision"> |
| 148 | + <geometry> |
| 149 | + <heightmap> |
| 150 | + <uri>half_dome.tif</uri> |
| 151 | + <!-- gdalinfo -stats <dem_file> --> |
| 152 | + <size>3793 3563 1481.398</size> |
| 153 | + <pos>0 0 -2694.987</pos> <!-- -(max or min elevation) --> |
| 154 | + </heightmap> |
| 155 | + </geometry> |
| 156 | + </collision> |
| 157 | + <visual name="visual"> |
| 158 | + <geometry> |
| 159 | + <heightmap> |
| 160 | + <texture> |
| 161 | + <diffuse>textures/rocks_diffuse.png</diffuse> |
| 162 | + <normal>textures/rocks_normal.png</normal> |
| 163 | + <size>250</size> |
| 164 | + </texture> |
| 165 | + <blend> |
| 166 | + <min_height>2</min_height> |
| 167 | + <fade_dist>5</fade_dist> |
| 168 | + </blend> |
| 169 | + <blend> |
| 170 | + <min_height>4</min_height> |
| 171 | + <fade_dist>5</fade_dist> |
| 172 | + </blend> |
| 173 | + <uri>half_dome.tif</uri> |
| 174 | + <!-- gdalinfo -stats <dem_file> --> |
| 175 | + <size>3793 3563 1481.398</size> |
| 176 | + <pos>0 0 -2694.987</pos> <!-- -(min or max elevation) --> |
| 177 | + </heightmap> |
| 178 | + </geometry> |
| 179 | + </visual> |
| 180 | + </link> |
| 181 | +</model> |
| 182 | +``` |
| 183 | + |
| 184 | +To launch the completed demo yourself, [download the files here](files/digital_elevation_models/half_dome_example/) then run: |
| 185 | + |
| 186 | +```bash |
| 187 | +cd /path/to/half_dome_example/ |
| 188 | + |
| 189 | +gz sim -v 4 half_dome.sdf |
| 190 | +``` |
| 191 | + |
| 192 | +\image html files/digital_elevation_models/gazebo_half_dome.png width=80% |
0 commit comments