Skip to content

Commit

Permalink
Add terrain loader node
Browse files Browse the repository at this point in the history
  • Loading branch information
Jaeyoung-Lim committed Apr 13, 2024
1 parent 41b1186 commit 20c7a7f
Show file tree
Hide file tree
Showing 6 changed files with 422 additions and 6 deletions.
7 changes: 7 additions & 0 deletions grid_map_geo/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
115 changes: 115 additions & 0 deletions grid_map_geo/include/grid_map_geo/geo_conversions.h
Original file line number Diff line number Diff line change
@@ -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 <math.h>

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
13 changes: 13 additions & 0 deletions grid_map_geo/launch/run_terrain_loader.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
<launch>
<arg name="visualization" default="true"/>
<arg name="location" default="hinwil"/>

<node pkg="grid_map_geo" type="terrain_loader" name="terrain_loader" output="screen">
<!-- <param name="terrain_path" value="$(find terrain_models)/models/$(arg location).tif"/> -->
<param name="terrain_path" value="/vsizip/vsicurl/https://terrain.ardupilot.org/SRTM1/ap_srtm1.zip/ap_srtm1.vrt"/>
</node>

<group if="$(arg visualization)">
<node type="rviz" name="rviz" pkg="rviz" args="-d $(find grid_map_geo)/launch/terrain_loader.rviz" output="screen"/>
</group>
</launch>
154 changes: 154 additions & 0 deletions grid_map_geo/launch/terrain_loader.rviz
Original file line number Diff line number Diff line change
@@ -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
10 changes: 4 additions & 6 deletions grid_map_geo/src/grid_map_geo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<ESPG>(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()};

Expand All @@ -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;
Expand Down Expand Up @@ -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;
Expand Down
Loading

0 comments on commit 20c7a7f

Please sign in to comment.