diff --git a/README.md b/README.md
index 8a5ac56..d62f873 100644
--- a/README.md
+++ b/README.md
@@ -37,3 +37,13 @@ The default launch file can be run as the following command.
```
roslaunch grid_map_geo load_tif.launch
```
+
+
+## Loading teerrain from a VRT server
+
+One can load a DEM from a terrain server directly.
+```
+roslaunch grid_map_geo run_terrain_loader.launch
+```
+
+![terrain-loader](https://github.com/ethz-asl/grid_map_geo/assets/5248102/e93b2c86-c26a-477c-8704-dc0233b7ef2e)
diff --git a/grid_map_geo/CMakeLists.txt b/grid_map_geo/CMakeLists.txt
index ccf006f..8cfeb0b 100644
--- a/grid_map_geo/CMakeLists.txt
+++ b/grid_map_geo/CMakeLists.txt
@@ -34,6 +34,13 @@ add_executable(test_tif_loader
add_dependencies(test_tif_loader ${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS} ${GDAL_LIBRARY})
target_link_libraries(test_tif_loader ${PROJECT_NAME} ${catkin_LIBRARIES} ${GDAL_LIBRARY} ${OpenCV_LIBRARIES})
+add_executable(terrain_loader
+ src/terrain_loader.cpp
+)
+add_dependencies(terrain_loader ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS} ${GDAL_LIBRARY})
+target_link_libraries(terrain_loader ${PROJECT_NAME} ${catkin_LIBRARIES} ${GDAL_LIBRARY} ${OpenCV_LIBRARIES})
+
+
if(CATKIN_ENABLE_TESTING)
# Add gtest based cpp test target and link libraries
catkin_add_gtest(${PROJECT_NAME}-test test/main.cpp
diff --git a/grid_map_geo/include/grid_map_geo/grid_map_geo.h b/grid_map_geo/include/grid_map_geo/grid_map_geo.h
index ac1fec5..60cca6d 100644
--- a/grid_map_geo/include/grid_map_geo/grid_map_geo.h
+++ b/grid_map_geo/include/grid_map_geo/grid_map_geo.h
@@ -107,6 +107,8 @@ class GridMapGeo {
*/
bool initializeFromGeotiff(const std::string& path);
+ bool initializeFromVrt(const std::string& path, const Eigen::Vector2d& map_center, Eigen::Vector2d& extent);
+
/**
* @brief Load a color layer from a geotiff file (orthomosaic)
*
diff --git a/grid_map_geo/launch/run_terrain_loader.launch b/grid_map_geo/launch/run_terrain_loader.launch
new file mode 100644
index 0000000..4ab95a4
--- /dev/null
+++ b/grid_map_geo/launch/run_terrain_loader.launch
@@ -0,0 +1,13 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/grid_map_geo/launch/terrain_loader.rviz b/grid_map_geo/launch/terrain_loader.rviz
new file mode 100644
index 0000000..cd7dd30
--- /dev/null
+++ b/grid_map_geo/launch/terrain_loader.rviz
@@ -0,0 +1,154 @@
+Panels:
+ - Class: rviz/Displays
+ Help Height: 78
+ Name: Displays
+ Property Tree Widget:
+ Expanded:
+ - /Global Options1
+ - /Grid1
+ - /GridMap1
+ Splitter Ratio: 0.5
+ Tree Height: 850
+ - Class: rviz/Selection
+ Name: Selection
+ - Class: rviz/Tool Properties
+ Expanded:
+ - /2D Pose Estimate1
+ - /2D Nav Goal1
+ - /Publish Point1
+ Name: Tool Properties
+ Splitter Ratio: 0.5886790156364441
+ - Class: rviz/Views
+ Expanded:
+ - /Current View1
+ Name: Views
+ Splitter Ratio: 0.5
+ - Class: rviz/Time
+ Name: Time
+ SyncMode: 0
+ SyncSource: ""
+ - Class: rviz_plugin_tutorials/Teleop
+ Name: Teleop
+ Topic: ""
+ - Class: mav_planning_rviz/PlanningPanel
+ Name: PlanningPanel
+ namespace: ""
+ odometry_topic: ""
+ planner_name: sertig
+ planning_budget: 4
+Preferences:
+ PromptSaveOnExit: true
+Toolbars:
+ toolButtonStyle: 2
+Visualization Manager:
+ Class: ""
+ Displays:
+ - Alpha: 0.5
+ Cell Size: 1000
+ Class: rviz/Grid
+ Color: 160; 160; 164
+ Enabled: true
+ Line Style:
+ Line Width: 0.029999999329447746
+ Value: Lines
+ Name: Grid
+ Normal Cell Count: 0
+ Offset:
+ X: 0
+ Y: 0
+ Z: 0
+ Plane: XY
+ Plane Cell Count: 10
+ Reference Frame: map
+ Value: true
+ - Alpha: 0.25
+ Autocompute Intensity Bounds: false
+ Class: grid_map_rviz_plugin/GridMap
+ Color: 200; 200; 200
+ Color Layer: elevation
+ Color Transformer: IntensityLayer
+ Enabled: true
+ Height Layer: elevation
+ Height Transformer: Layer
+ History Length: 5
+ Invert Rainbow: false
+ Max Color: 255; 255; 255
+ Max Intensity: 2200
+ Min Color: 0; 0; 0
+ Min Intensity: 1400
+ Name: GridMap
+ Show Grid Lines: false
+ Topic: /grid_map
+ Unreliable: false
+ Use Rainbow: true
+ Value: true
+ Enabled: true
+ Global Options:
+ Background Color: 255; 255; 255
+ Default Light: true
+ Fixed Frame: map
+ Frame Rate: 30
+ Name: root
+ Tools:
+ - Class: rviz/Interact
+ Hide Inactive Objects: true
+ - Class: rviz/MoveCamera
+ - Class: rviz/Select
+ - Class: rviz/FocusCamera
+ - Class: rviz/Measure
+ - Class: rviz/SetInitialPose
+ Theta std deviation: 0.2617993950843811
+ Topic: /initialpose
+ X std deviation: 0.5
+ Y std deviation: 0.5
+ - Class: rviz/SetGoal
+ Topic: /move_base_simple/goal
+ - Class: rviz/PublishPoint
+ Single click: true
+ Topic: /clicked_point
+ Value: true
+ Views:
+ Current:
+ Class: rviz/Orbit
+ Distance: 30173.89453125
+ Enable Stereo Rendering:
+ Stereo Eye Separation: 0.05999999865889549
+ Stereo Focal Distance: 1
+ Swap Stereo Eyes: false
+ Value: false
+ Field of View: 0.7853981852531433
+ Focal Point:
+ X: 5063.75927734375
+ Y: 2195.057373046875
+ Z: 3253.49755859375
+ Focal Shape Fixed Size: true
+ Focal Shape Size: 0.05000000074505806
+ Invert Z Axis: false
+ Name: Current View
+ Near Clip Distance: 0.009999999776482582
+ Pitch: 0.639797031879425
+ Target Frame: map
+ Yaw: 5.113188743591309
+ Saved: ~
+Window Geometry:
+ Displays:
+ collapsed: false
+ Height: 1136
+ Hide Left Dock: false
+ Hide Right Dock: true
+ PlanningPanel:
+ collapsed: false
+ QMainWindow State: 000000ff00000000fd000000040000000000000247000003dbfc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000007a000003db000000c700fffffffb0000001a0050006c0061006e006e0069006e006700500061006e0065006c0000000255000000ef0000006e00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d006100670065010000020c000001b10000000000000000fb0000000c00540065006c0065006f00700000000368000000b20000004500ffffff000000010000010f000002cafc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000007a000002ca000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b20000000000000000000000020000073800000039fc0100000002fb0000000800540069006d00650100000000000007380000030700fffffffb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000014efc0100000001fb0000000800540069006d00650100000000000004500000000000000000000004eb000003db00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+ Selection:
+ collapsed: false
+ Teleop:
+ collapsed: false
+ Time:
+ collapsed: false
+ Tool Properties:
+ collapsed: false
+ Views:
+ collapsed: true
+ Width: 1848
+ X: 72
+ Y: 27
diff --git a/grid_map_geo/src/grid_map_geo.cpp b/grid_map_geo/src/grid_map_geo.cpp
index 8b16a0e..843aa3a 100644
--- a/grid_map_geo/src/grid_map_geo.cpp
+++ b/grid_map_geo/src/grid_map_geo.cpp
@@ -141,6 +141,102 @@ bool GridMapGeo::initializeFromGeotiff(const std::string &path) {
return true;
}
+bool GridMapGeo::initializeFromVrt(const std::string &path, const Eigen::Vector2d &map_center,
+ Eigen::Vector2d &extent) {
+ GDALAllRegister();
+ GDALDataset *dataset = (GDALDataset *)GDALOpen(path.c_str(), GA_ReadOnly);
+ if (!dataset) {
+ std::cout << "Failed to open" << std::endl;
+ return false;
+ }
+ std::cout << std::endl << "Loading GeoTIFF file for gridmap" << std::endl;
+
+ double originX, originY, pixelSizeX, pixelSizeY;
+ double geoTransform[6];
+ if (dataset->GetGeoTransform(geoTransform) == CE_None) {
+ originX = geoTransform[0];
+ originY = geoTransform[3];
+ pixelSizeX = geoTransform[1];
+ pixelSizeY = geoTransform[5];
+ } else {
+ std::cout << "Failed read geotransform" << std::endl;
+ return false;
+ }
+
+ const char *pszProjection = dataset->GetProjectionRef();
+ std::cout << std::endl << "Wkt ProjectionRef: " << pszProjection << std::endl;
+
+ const OGRSpatialReference *spatial_ref = dataset->GetSpatialRef();
+ std::string name_coordinate = spatial_ref->GetAttrValue("geogcs");
+ std::string epsg_code = spatial_ref->GetAttrValue("AUTHORITY", 1);
+ // Get image metadata
+ unsigned width = dataset->GetRasterXSize();
+ unsigned height = dataset->GetRasterYSize();
+ double resolution = pixelSizeX;
+ std::cout << "Width: " << width << " Height: " << height << " Resolution: " << resolution << std::endl;
+
+ // pixelSizeY is negative because the origin of the image is the north-east corner and positive
+ // Y pixel coordinates go towards the south
+ int grid_width = extent(0) / std::abs(resolution);
+ int grid_height = extent(1) / std::abs(resolution);
+ const double lengthX = resolution * grid_width;
+ const double lengthY = resolution * grid_height;
+ grid_map::Length length(lengthX, lengthY);
+ std::cout << "length: " << length.transpose() << std::endl;
+
+ maporigin_.espg = static_cast(std::stoi(epsg_code));
+ maporigin_.position = map_center.head(2);
+
+ Eigen::Vector2d position{Eigen::Vector2d::Zero()};
+
+ grid_map_.setGeometry(length, resolution, position);
+ std::cout << "position: " << position.transpose() << std::endl;
+ /// TODO: Use TF for geocoordinates
+ grid_map_.setFrameId(frame_id_);
+ grid_map_.add("elevation");
+ GDALRasterBand *elevationBand = dataset->GetRasterBand(1);
+
+ Eigen::Vector2d center_px((map_center(1) - geoTransform[0]) / geoTransform[1],
+ (map_center(0) - geoTransform[3]) / geoTransform[5]);
+
+ const auto raster_io_x_offset = center_px.x() - grid_width / 2;
+ const auto raster_io_y_offset = center_px.y() - grid_height / 2;
+ std::cout << "center_px: " << center_px.transpose() << std::endl;
+
+ std::vector data(grid_width * grid_height, 0.0f);
+ const auto raster_err = elevationBand->RasterIO(GF_Read, raster_io_x_offset, raster_io_y_offset, grid_width,
+ grid_height, &data[0], grid_width, grid_height, GDT_Float32, 0, 0);
+ if (raster_err != CPLE_None) {
+ std::cout << "Error loading raster" << std::endl;
+ return false;
+ }
+ grid_map::Matrix &layer_elevation = grid_map_["elevation"];
+ for (grid_map::GridMapIterator iterator(grid_map_); !iterator.isPastEnd(); ++iterator) {
+ const grid_map::Index gridMapIndex = *iterator;
+ // TODO: This may be wrong if the pixelSizeY > 0
+ int x = grid_width - 1 - gridMapIndex(0);
+ int y = gridMapIndex(1);
+
+ layer_elevation(x, y) = data[gridMapIndex(0) + grid_width * gridMapIndex(1)];
+ }
+
+ static tf2_ros::StaticTransformBroadcaster static_broadcaster;
+ geometry_msgs::TransformStamped static_transformStamped;
+
+ static_transformStamped.header.stamp = ros::Time::now();
+ static_transformStamped.header.frame_id = name_coordinate;
+ static_transformStamped.child_frame_id = frame_id_;
+ static_transformStamped.transform.translation.x = map_center(0);
+ static_transformStamped.transform.translation.y = map_center(1);
+ static_transformStamped.transform.translation.z = 0.0;
+ static_transformStamped.transform.rotation.x = 0.0;
+ static_transformStamped.transform.rotation.y = 0.0;
+ static_transformStamped.transform.rotation.z = 0.0;
+ static_transformStamped.transform.rotation.w = 1.0;
+ static_broadcaster.sendTransform(static_transformStamped);
+ return true;
+}
+
bool GridMapGeo::addColorFromGeotiff(const std::string &path) {
GDALAllRegister();
GDALDataset *dataset = (GDALDataset *)GDALOpen(path.c_str(), GA_ReadOnly);
diff --git a/grid_map_geo/src/terrain_loader.cpp b/grid_map_geo/src/terrain_loader.cpp
new file mode 100644
index 0000000..d1f75c4
--- /dev/null
+++ b/grid_map_geo/src/terrain_loader.cpp
@@ -0,0 +1,150 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2021 Jaeyoung Lim. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+/**
+ * @brief Node to test planner in the view utiltiy map
+ *
+ *
+ * @author Jaeyoung Lim
+ */
+
+#include
+#include
+#include
+#include
+
+#include
+
+constexpr int ESPG_WGS84 = 4326;
+constexpr int ESPG_CH1903_LV03 = 21781;
+
+void transformCoordinates(int src_coord, const double &x, const double &y, const double &z, int tgt_coord, double &x_t,
+ double &y_t, double &z_t) {
+ OGRSpatialReference source, target;
+ source.importFromEPSG(src_coord);
+ target.importFromEPSG(tgt_coord);
+
+ OGRPoint p;
+ p.setX(x);
+ p.setY(y);
+ p.setZ(z);
+ p.assignSpatialReference(&source);
+
+ p.transformTo(&target);
+ x_t = p.getX();
+ y_t = p.getY();
+ z_t = p.getZ();
+ return;
+}
+
+void LoadTerrainFromVrt(std::string path, const Eigen::Vector3d &query_position, const Eigen::Vector2d &offset,
+ grid_map::GridMap &map, grid_map::GridMap &vrt_map_object) {
+ std::shared_ptr vrt_map = std::make_shared();
+
+ Eigen::Vector3d query_position_lv03 = query_position;
+ /// Convert LV03 to WGS84
+ Eigen::Vector3d map_center_wgs84; // Map center in WGS84
+ transformCoordinates(ESPG_CH1903_LV03, query_position_lv03(0), query_position_lv03(1), query_position_lv03(2),
+ ESPG_WGS84, map_center_wgs84.x(), map_center_wgs84.y(), map_center_wgs84.z());
+
+ std::cout << "Loading VRT Map:" << std::endl;
+ std::cout << " - map_center_wgs84:" << map_center_wgs84.transpose() << std::endl;
+ /// TODO: Discover extent from corners
+ Eigen::Vector2d extent_wgs84(0.5, 0.5);
+ vrt_map->initializeFromVrt(path, map_center_wgs84.head(2), extent_wgs84);
+ std::cout << " - Success!" << std::endl;
+
+ /// TODO: Loaded VRT map
+ std::cout << "Reprojecting map" << std::endl;
+ Eigen::Vector2d extent_lv03(12000.0, 12000.0);
+ double resolution{100.0};
+ Eigen::Vector2d position{Eigen::Vector2d::Zero()};
+ map.setGeometry(extent_lv03, resolution, position);
+ map.add("elevation");
+ map.setFrameId("map");
+ for (grid_map::GridMapIterator iterator(map); !iterator.isPastEnd(); ++iterator) {
+ const grid_map::Index index = *iterator;
+ Eigen::Vector2d cell_position; // Position of cell relative to map coordinates
+ map.getPosition(index, cell_position);
+ auto cell_position_lv03 = cell_position + query_position_lv03.head(2); // Position of cell in CH1903/LV03
+ double dummy;
+ Eigen::Vector2d cell_position_wgs84;
+ transformCoordinates(ESPG_CH1903_LV03, cell_position_lv03(0), cell_position_lv03(1), cell_position_lv03(2),
+ ESPG_WGS84, cell_position_wgs84.x(), cell_position_wgs84.y(), dummy);
+ // std::cout << " - cell_position_wgs84:" << cell_position_wgs84.transpose() << std::endl;
+
+ Eigen::Vector2d local_wgs84 = cell_position_wgs84 - map_center_wgs84.head(2);
+ double tmp = local_wgs84(0);
+ local_wgs84(0) = local_wgs84(1);
+ local_wgs84(1) = tmp;
+ // std::cout << " - local_wgs84:" << local_wgs84.transpose() << std::endl;
+ auto elevation = vrt_map->getGridMap().atPosition("elevation", local_wgs84);
+ map.atPosition("elevation", cell_position) = elevation;
+ }
+ map.setPosition(offset);
+ vrt_map_object = vrt_map->getGridMap();
+}
+
+int main(int argc, char **argv) {
+ ros::init(argc, argv, "terrain_loader");
+ ros::NodeHandle nh("");
+ ros::NodeHandle nh_private("~");
+
+ ros::Publisher map_pub = nh.advertise("grid_map", 1, true);
+ ros::Publisher map_pub2 = nh.advertise("grid_map2", 1, true);
+
+ std::string path;
+ nh_private.param("terrain_path", path, "resources/cadastre.tif");
+
+ Eigen::Vector3d test_position = Eigen::Vector3d(783199.15, 187585.10, 0.0);
+
+ for (int i = 0; i < 4; i++) {
+ Eigen::Vector3d offset = static_cast(i) * Eigen::Vector3d(2500.0, 2500.0, 0.0);
+ Eigen::Vector3d query_position = test_position + offset;
+
+ grid_map::GridMap map;
+ grid_map::GridMap vrt_map;
+ LoadTerrainFromVrt(path, query_position, offset.head(2), map, vrt_map);
+ std::cout << "i: " << i << " offset: " << offset.transpose() << std::endl;
+
+ grid_map_msgs::GridMap msg;
+ grid_map::GridMapRosConverter::toMessage(map, msg);
+ map_pub.publish(msg);
+
+ grid_map_msgs::GridMap msg2;
+ grid_map::GridMapRosConverter::toMessage(vrt_map, msg2);
+ map_pub2.publish(msg2);
+ }
+
+ ros::spin();
+ return 0;
+}