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/geo_conversions.h b/grid_map_geo/include/grid_map_geo/geo_conversions.h new file mode 100644 index 0000000..65edc95 --- /dev/null +++ b/grid_map_geo/include/grid_map_geo/geo_conversions.h @@ -0,0 +1,115 @@ +/**************************************************************************** + * + * Copyright (c) 2023 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 terrain-navigation 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. + * + ****************************************************************************/ + +#ifndef GEOCONVERSIONS_H +#define GEOCONVERSIONS_H + +#include + +class GeoConversions { + public: + GeoConversions(); + virtual ~GeoConversions(); + + /** + * @brief Convert WGS84 (LLA) to LV03/CH1903 + * + * @param lat latitude (degrees) WGS84 + * @param lon lontitude (degrees) WGS84 + * @param alt Altitude WGS84 + * @param x + * @param y + * @param h + */ + static void forward(const double lat, const double lon, const double alt, double &y, double &x, double &h) { + // 1. Convert the ellipsoidal latitudes φ and longitudes λ into arcseconds ["] + const double lat_arc = lat * 3600.0; + const double lon_arc = lon * 3600.0; + + // 2. Calculate the auxiliary values (differences of latitude and longitude relative to Bern in the unit [10000"]): + // φ' = (φ – 169028.66 ")/10000 + // λ' = (λ – 26782.5 ")/10000 + const double lat_aux = (lat_arc - 169028.66) / 10000.0; + const double lon_aux = (lon_arc - 26782.5) / 10000.0; + + // 3. Calculate projection coordinates in LV95 (E, N, h) or in LV03 (y, x, h) + // E [m] = 2600072.37 + 211455.93 * λ' - 10938.51 * λ' * φ' - 0.36 * λ' * φ'2 - 44.54 * λ'3 + // y [m] = E – 2000000.00 N [m] = 1200147.07 + 308807.95 * φ' + 3745.25 * λ'2 + 76.63 * φ'2 - 194.56 * λ'2 * φ' + + // 119.79 * φ'3 x [m] = N – 1000000.00 + // hCH [m] =hWGS – 49.55 + 2.73 * λ' + 6.94 * φ' + const double E = 2600072.37 + 211455.93 * lon_aux - 10938.51 * lon_aux * lat_aux - + 0.36 * lon_aux * std::pow(lat_aux, 2) - 44.54 * std::pow(lon_aux, 3); + y = E - 2000000.00; + const double N = 1200147.07 + 308807.95 * lat_aux + 3745.25 * std::pow(lon_aux, 2) + 76.63 * std::pow(lat_aux, 2) - + 194.56 * std::pow(lon_aux, 2) * lat_aux + 119.79 * std::pow(lat_aux, 3); + x = N - 1000000.00; + + h = alt - 49.55 + 2.73 * lon_aux + 6.84 * lat_aux; + }; + + /** + * @brief LV03/CH1903 to Convert WGS84 (LLA) + * + * @param x + * @param y + * @param h + * @param lat latitude + * @param lon longitude + * @param alt altitude + */ + static void reverse(const double y, const double x, const double h, double &lat, double &lon, double &alt) { + // 1. Convert the projection coordinates E (easting) and N (northing) in LV95 (or y / x in LV03) into the civilian + // system (Bern = 0 / 0) and express in the unit [1000 km]: E' = (E – 2600000 m)/1000000 = (y – 600000 m)/1000000 + // N' = (N – 1200000 m)/1000000 = (x – 200000 m)/1000000 + const double y_aux = (y - 600000.0) / 1000000.0; + const double x_aux = (x - 200000.0) / 1000000.0; + + // 2. Calculate longitude λ and latitude φ in the unit [10000"]: + // λ' = 2.6779094 + 4.728982 * y' + 0.791484* y' * x' + 0.1306 * y' * x'2 - 0.0436 * y'3 + // φ' = 16.9023892 + 3.238272 * x' - 0.270978 * y'2 - 0.002528 * x'2 - 0.0447 * y'2 * x' - 0.0140 * x'3 + // hWGS [m] = hCH + 49.55 - 12.60 * y' - 22.64 * x' + const double lon_aux = 2.6779094 + 4.728982 * y_aux + 0.791484 * y_aux * x_aux + + 0.1306 * y_aux * std::pow(x_aux, 2) - 0.0436 * std::pow(y_aux, 3); + const double lat_aux = 16.9023892 + 3.238272 * x_aux - 0.270978 * std::pow(y_aux, 2) - + 0.002528 * std::pow(x_aux, 2) - 0.0447 * std::pow(y_aux, 2) * x_aux - + 0.0140 * std::pow(x_aux, 3); + alt = h + 49.55 - 12.60 * y_aux - 22.64 * x_aux; + + lon = lon_aux * 100.0 / 36.0; + lat = lat_aux * 100.0 / 36.0; + }; + + private: +}; + +#endif 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 45903ab..03298f9 100644 --- a/grid_map_geo/src/grid_map_geo.cpp +++ b/grid_map_geo/src/grid_map_geo.cpp @@ -184,10 +184,8 @@ bool GridMapGeo::initializeFromVrt(const std::string &path, const Eigen::Vector2 grid_map::Length length(lengthX, lengthY); std::cout << "length: " << length.transpose() << std::endl; - double mapcenter_e = map_center(0); - double mapcenter_n = map_center(1); maporigin_.espg = static_cast(std::stoi(epsg_code)); - maporigin_.position = Eigen::Vector3d(mapcenter_e, mapcenter_n, 0.0); + maporigin_.position = map_center.head(2); Eigen::Vector2d position{Eigen::Vector2d::Zero()}; @@ -198,7 +196,7 @@ bool GridMapGeo::initializeFromVrt(const std::string &path, const Eigen::Vector2 grid_map_.add("elevation"); GDALRasterBand *elevationBand = dataset->GetRasterBand(1); - Eigen::Vector2d center_px((mapcenter_e - geoTransform[0])/geoTransform[1], (mapcenter_n - geoTransform[3])/geoTransform[5]); + 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; @@ -228,8 +226,8 @@ bool GridMapGeo::initializeFromVrt(const std::string &path, const Eigen::Vector2 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 = mapcenter_e; - static_transformStamped.transform.translation.y = mapcenter_n; + 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; diff --git a/grid_map_geo/src/terrain_loader.cpp b/grid_map_geo/src/terrain_loader.cpp new file mode 100644 index 0000000..6e1ed60 --- /dev/null +++ b/grid_map_geo/src/terrain_loader.cpp @@ -0,0 +1,129 @@ +/**************************************************************************** + * + * 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 "grid_map_geo/geo_conversions.h" + +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 + GeoConversions::reverse(query_position_lv03(0), query_position_lv03(1), query_position_lv03(2), 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; + GeoConversions::reverse(cell_position_lv03(0), cell_position_lv03(1), 0.0, 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; +}