Skip to content

Commit e55f57b

Browse files
authored
Align multiple DEMs with TF (#34)
* Remove terrain alignment * Make frame_id a member of GridMapGeo * Broadcast Tf * Load multiple tif files
1 parent 7c6445d commit e55f57b

File tree

6 files changed

+124
-68
lines changed

6 files changed

+124
-68
lines changed

include/grid_map_geo/grid_map_geo.h

Lines changed: 4 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ struct Location {
5252

5353
class GridMapGeo {
5454
public:
55-
GridMapGeo();
55+
GridMapGeo(const std::string frame_id = "map");
5656
virtual ~GridMapGeo();
5757

5858
/**
@@ -88,33 +88,24 @@ class GridMapGeo {
8888
origin = maporigin_.position;
8989
};
9090

91-
/**
92-
* @brief Set the Altitude Origin object
93-
*
94-
* @param altitude
95-
*/
96-
void setAltitudeOrigin(const double altitude) { localorigin_altitude_ = altitude; };
97-
9891
/**
9992
* @brief Helper function for loading terrain from path
10093
*
10194
* @param map_path Path to dsm path (Supported formats are *.tif)
102-
* @param algin_terrain Geo align terrain
10395
* @param color_map_path Path to color raster files to visualize terrain texture (Supported formats are *.tif)
10496
* @return true Successfully loaded terrain
10597
* @return false Failed to load terrain
10698
*/
107-
bool Load(const std::string& map_path, bool algin_terrain, const std::string color_map_path = "");
99+
bool Load(const std::string& map_path, const std::string color_map_path = "");
108100

109101
/**
110102
* @brief Initialize grid map from a geotiff file
111103
*
112104
* @param path Path to dsm path (Supported formats are *.tif)
113-
* @param align_terrain
114105
* @return true Successfully loaded terrain
115106
* @return false Failed to load terrain
116107
*/
117-
bool initializeFromGeotiff(const std::string& path, bool align_terrain = true);
108+
bool initializeFromGeotiff(const std::string& path);
118109

119110
/**
120111
* @brief Load a color layer from a geotiff file (orthomosaic)
@@ -178,9 +169,7 @@ class GridMapGeo {
178169

179170
protected:
180171
grid_map::GridMap grid_map_;
181-
double localorigin_e_{789823.93}; // duerrboden berghaus
182-
double localorigin_n_{177416.56};
183-
double localorigin_altitude_{0.0};
184172
Location maporigin_;
173+
std::string frame_id_{""};
185174
};
186175
#endif

launch/config.rviz

Lines changed: 65 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -7,8 +7,12 @@ Panels:
77
- /Global Options1
88
- /Status1
99
- /GridMap1
10+
- /GridMap2
11+
- /GridMap2/Status1
12+
- /TF1
13+
- /TF1/Status1
1014
Splitter Ratio: 0.5
11-
Tree Height: 848
15+
Tree Height: 839
1216
- Class: rviz/Selection
1317
Name: Selection
1418
- Class: rviz/Tool Properties
@@ -24,7 +28,6 @@ Panels:
2428
Name: Views
2529
Splitter Ratio: 0.5
2630
- Class: rviz/Time
27-
Experimental: false
2831
Name: Time
2932
SyncMode: 0
3033
SyncSource: ""
@@ -59,11 +62,14 @@ Visualization Manager:
5962
Color: 200; 200; 200
6063
Color Layer: color
6164
Color Transformer: ColorLayer
65+
ColorMap: default
6266
Enabled: true
67+
Grid Cell Decimation: 1
68+
Grid Line Thickness: 0.10000000149011612
6369
Height Layer: elevation
6470
Height Transformer: GridMapLayer
6571
History Length: 1
66-
Invert Rainbow: false
72+
Invert ColorMap: false
6773
Max Color: 255; 255; 255
6874
Max Intensity: 10
6975
Min Color: 0; 0; 0
@@ -72,13 +78,56 @@ Visualization Manager:
7278
Show Grid Lines: false
7379
Topic: /elevation_map
7480
Unreliable: false
75-
Use Rainbow: true
81+
Use ColorMap: true
82+
Value: true
83+
- Alpha: 1
84+
Autocompute Intensity Bounds: true
85+
Class: grid_map_rviz_plugin/GridMap
86+
Color: 200; 200; 200
87+
Color Layer: elevation
88+
Color Transformer: GridMapLayer
89+
ColorMap: default
90+
Enabled: true
91+
Grid Cell Decimation: 1
92+
Grid Line Thickness: 0.10000000149011612
93+
Height Layer: elevation
94+
Height Transformer: GridMapLayer
95+
History Length: 1
96+
Invert ColorMap: false
97+
Max Color: 255; 255; 255
98+
Max Intensity: 10
99+
Min Color: 0; 0; 0
100+
Min Intensity: 0
101+
Name: GridMap
102+
Show Grid Lines: false
103+
Topic: /elevation2
104+
Unreliable: false
105+
Use ColorMap: true
106+
Value: true
107+
- Class: rviz/TF
108+
Enabled: true
109+
Frame Timeout: 15
110+
Frames:
111+
All Enabled: true
112+
map:
113+
Value: true
114+
world:
115+
Value: true
116+
Marker Alpha: 1
117+
Marker Scale: 1
118+
Name: TF
119+
Show Arrows: true
120+
Show Axes: true
121+
Show Names: true
122+
Tree:
123+
{}
124+
Update Interval: 0
76125
Value: true
77126
Enabled: true
78127
Global Options:
79128
Background Color: 255; 255; 255
80129
Default Light: true
81-
Fixed Frame: map
130+
Fixed Frame: sertig
82131
Frame Rate: 30
83132
Name: root
84133
Tools:
@@ -102,33 +151,33 @@ Visualization Manager:
102151
Views:
103152
Current:
104153
Class: rviz/Orbit
105-
Distance: 2959.1279296875
154+
Distance: 16350.146484375
106155
Enable Stereo Rendering:
107156
Stereo Eye Separation: 0.05999999865889549
108157
Stereo Focal Distance: 1
109158
Swap Stereo Eyes: false
110159
Value: false
160+
Field of View: 0.7853981852531433
111161
Focal Point:
112-
X: 11.737425804138184
113-
Y: -95.61576843261719
114-
Z: 43.985958099365234
162+
X: -428.4516906738281
163+
Y: -385.00115966796875
164+
Z: 529.86865234375
115165
Focal Shape Fixed Size: true
116166
Focal Shape Size: 0.05000000074505806
117167
Invert Z Axis: false
118168
Name: Current View
119169
Near Clip Distance: 0.009999999776482582
120-
Pitch: 0.8253984451293945
170+
Pitch: 0.7153984904289246
121171
Target Frame: <Fixed Frame>
122-
Value: Orbit (rviz)
123-
Yaw: 0.6203981637954712
172+
Yaw: 0.48539578914642334
124173
Saved: ~
125174
Window Geometry:
126175
Displays:
127176
collapsed: false
128-
Height: 1145
177+
Height: 1136
129178
Hide Left Dock: false
130179
Hide Right Dock: false
131-
QMainWindow State: 000000ff00000000fd000000040000000000000156000003dbfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000003db000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000003dbfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000003db000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073d0000003efc0100000002fb0000000800540069006d006501000000000000073d000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000004cc000003db00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
180+
QMainWindow State: 000000ff00000000fd000000040000000000000283000003d2fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000003d2000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000003d2fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000003d2000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007380000003efc0100000002fb0000000800540069006d0065010000000000000738000003bc00fffffffb0000000800540069006d006501000000000000045000000000000000000000039a000003d200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
132181
Selection:
133182
collapsed: false
134183
Time:
@@ -137,6 +186,6 @@ Window Geometry:
137186
collapsed: false
138187
Views:
139188
collapsed: false
140-
Width: 1853
141-
X: 67
189+
Width: 1848
190+
X: 72
142191
Y: 27

launch/load_multiple_tif.launch

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,22 @@
1+
<launch>
2+
<arg name="visualization" default="true"/>
3+
<arg name="location" default="sargans"/>
4+
<node pkg="tf" type="static_transform_publisher" name="world_map" args="0 0 0 0 0 0 world map 10"/>
5+
6+
<node pkg="grid_map_geo" type="test_tif_loader" name="first_tif_loader" output="screen">
7+
<param name="frame_id" value="map"/>
8+
<param name="tif_path" value="$(find grid_map_geo)/resources/sertig.tif"/>
9+
<!-- <param name="color_path" value="$(find grid_map_geo)/resources/sertig_color.tif"/> -->
10+
</node>
11+
12+
<node pkg="grid_map_geo" type="test_tif_loader" name="second_tif_loader2" output="screen">
13+
<param name="frame_id" value="dischma_valley"/>
14+
<param name="tif_path" value="$(find terrain_models)/models/dischma_valley.tif"/>
15+
<param name="color_path" value="$(find terrain_models)/models/dischma_valley_color.tif"/>
16+
<param name="topic_name" value="elevation2"/>
17+
</node>
18+
19+
<group if="$(arg visualization)">
20+
<node type="rviz" name="rviz" pkg="rviz" args="-d $(find grid_map_geo)/launch/config.rviz" />
21+
</group>
22+
</launch>

launch/load_tif.launch

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44
<node pkg="tf" type="static_transform_publisher" name="world_map" args="0 0 0 0 0 0 world map 10"/>
55

66
<node pkg="grid_map_geo" type="test_tif_loader" name="test_tif_loader" output="screen">
7+
<param name="frame_id" value="map"/>
78
<param name="tif_path" value="$(find grid_map_geo)/resources/sertig.tif"/>
89
<!-- <param name="color_path" value="$(find grid_map_geo)/resources/sertig_color.tif"/> -->
910
</node>

src/grid_map_geo.cpp

Lines changed: 24 additions & 30 deletions
Original file line numberDiff line numberDiff line change
@@ -43,20 +43,23 @@
4343
#include <grid_map_core/iterators/CircleIterator.hpp>
4444
#include <grid_map_core/iterators/GridMapIterator.hpp>
4545

46-
GridMapGeo::GridMapGeo() {}
46+
#include <geometry_msgs/TransformStamped.h>
47+
#include <tf2_ros/static_transform_broadcaster.h>
48+
49+
GridMapGeo::GridMapGeo(const std::string frame_id) { frame_id_ = frame_id; }
4750

4851
GridMapGeo::~GridMapGeo() {}
4952

50-
bool GridMapGeo::Load(const std::string &map_path, bool algin_terrain, const std::string color_map_path) {
51-
bool loaded = initializeFromGeotiff(map_path, algin_terrain);
53+
bool GridMapGeo::Load(const std::string &map_path, const std::string color_map_path) {
54+
bool loaded = initializeFromGeotiff(map_path);
5255
if (!color_map_path.empty()) { // Load color layer if the color path is nonempty
5356
bool color_loaded = addColorFromGeotiff(color_map_path);
5457
}
5558
if (!loaded) return false;
5659
return true;
5760
}
5861

59-
bool GridMapGeo::initializeFromGeotiff(const std::string &path, bool align_terrain) {
62+
bool GridMapGeo::initializeFromGeotiff(const std::string &path) {
6063
GDALAllRegister();
6164
GDALDataset *dataset = (GDALDataset *)GDALOpen(path.c_str(), GA_ReadOnly);
6265
if (!dataset) {
@@ -80,6 +83,8 @@ bool GridMapGeo::initializeFromGeotiff(const std::string &path, bool align_terra
8083
const char *pszProjection = dataset->GetProjectionRef();
8184
std::cout << std::endl << "Wkt ProjectionRef: " << pszProjection << std::endl;
8285

86+
const OGRSpatialReference *spatial_ref = dataset->GetSpatialRef();
87+
std::string name_coordinate = spatial_ref->GetAttrValue("geogcs");
8388
// Get image metadata
8489
unsigned width = dataset->GetRasterXSize();
8590
unsigned height = dataset->GetRasterYSize();
@@ -99,24 +104,9 @@ bool GridMapGeo::initializeFromGeotiff(const std::string &path, bool align_terra
99104

100105
Eigen::Vector2d position{Eigen::Vector2d::Zero()};
101106

102-
/// TODO: Generalize to set local origin as center of map position
103-
// Eigen::Vector3d origin_lv03 =
104-
// transformCoordinates(ESPG::WGS84, std::string(pszProjection), localorigin_wgs84_.position);
105-
// localorigin_e_ = origin_lv03(0);
106-
// localorigin_n_ = origin_lv03(1);
107-
// localorigin_altitude_ = origin_lv03(2);
108-
// if (align_terrain) {
109-
// std::cout << "[GridMapGeo] Aligning terrain!" << std::endl;
110-
// double map_position_x = mapcenter_e - localorigin_e_;
111-
// double map_position_y = mapcenter_n - localorigin_n_;
112-
// position = Eigen::Vector2d(map_position_x, map_position_y);
113-
// } else {
114-
// std::cout << "[GridMapGeo] Not aligning terrain!" << std::endl;
115-
// }
116-
117107
grid_map_.setGeometry(length, resolution, position);
118108
/// TODO: Use TF for geocoordinates
119-
grid_map_.setFrameId("map");
109+
grid_map_.setFrameId(frame_id_);
120110
grid_map_.add("elevation");
121111
GDALRasterBand *elevationBand = dataset->GetRasterBand(1);
122112

@@ -133,17 +123,21 @@ bool GridMapGeo::initializeFromGeotiff(const std::string &path, bool align_terra
133123
layer_elevation(x, y) = data[gridMapIndex(0) + width * gridMapIndex(1)];
134124
}
135125

136-
/// TODO: This is a workaround with the problem of gdal 3 not translating altitude correctly.
137-
/// This section just levels the current position to the ground
138-
double altitude{0.0};
139-
if (grid_map_.isInside(Eigen::Vector2d(0.0, 0.0))) {
140-
altitude = grid_map_.atPosition("elevation", Eigen::Vector2d(0.0, 0.0));
141-
}
126+
static tf2_ros::StaticTransformBroadcaster static_broadcaster;
127+
geometry_msgs::TransformStamped static_transformStamped;
128+
129+
static_transformStamped.header.stamp = ros::Time::now();
130+
static_transformStamped.header.frame_id = name_coordinate;
131+
static_transformStamped.child_frame_id = frame_id_;
132+
static_transformStamped.transform.translation.x = mapcenter_e;
133+
static_transformStamped.transform.translation.y = mapcenter_n;
134+
static_transformStamped.transform.translation.z = 0.0;
135+
static_transformStamped.transform.rotation.x = 0.0;
136+
static_transformStamped.transform.rotation.y = 0.0;
137+
static_transformStamped.transform.rotation.z = 0.0;
138+
static_transformStamped.transform.rotation.w = 1.0;
139+
static_broadcaster.sendTransform(static_transformStamped);
142140

143-
// Eigen::Translation3d meshlab_translation(0.0, 0.0, -altitude);
144-
// Eigen::AngleAxisd meshlab_rotation(Eigen::AngleAxisd::Identity());
145-
// Eigen::Isometry3d transform = meshlab_translation * meshlab_rotation; // Apply affine transformation.
146-
// grid_map_ = grid_map_.getTransformedMap(transform, "elevation", grid_map_.getFrameId(), true);
147141
return true;
148142
}
149143

src/test_tif_loader.cpp

Lines changed: 8 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -54,20 +54,21 @@ int main(int argc, char **argv) {
5454
ros::NodeHandle nh("");
5555
ros::NodeHandle nh_private("~");
5656

57-
ros::Publisher original_map_pub = nh.advertise<grid_map_msgs::GridMap>("elevation_map", 1, true);
58-
59-
std::string file_path, color_path;
57+
std::string frame_id, file_path, color_path, topic_name;
58+
nh_private.param<std::string>("frame_id", frame_id, "map");
6059
nh_private.param<std::string>("tif_path", file_path, "");
6160
nh_private.param<std::string>("color_path", color_path, "");
61+
nh_private.param<std::string>("topic_name", topic_name, "elevation_map");
62+
63+
ros::Publisher original_map_pub = nh.advertise<grid_map_msgs::GridMap>(topic_name, 1, true);
6264

63-
std::shared_ptr<GridMapGeo> map = std::make_shared<GridMapGeo>();
64-
map->Load(file_path, false, color_path);
65+
std::shared_ptr<GridMapGeo> map = std::make_shared<GridMapGeo>(frame_id);
66+
map->Load(file_path, color_path);
6567

6668
while (true) {
6769
/// TODO: Publish gridmap
6870
MapPublishOnce(original_map_pub, map->getGridMap());
69-
ros::Duration(10.0).sleep();
70-
ros::Duration(3.0).sleep();
71+
ros::Duration(1.0).sleep();
7172
}
7273

7374
ros::spin();

0 commit comments

Comments
 (0)