Skip to content

Commit

Permalink
Align multiple DEMs with TF (#34)
Browse files Browse the repository at this point in the history
* Remove terrain alignment

* Make frame_id a member of GridMapGeo

* Broadcast Tf

* Load multiple tif files
  • Loading branch information
Jaeyoung-Lim authored Jan 11, 2024
1 parent 7c6445d commit e55f57b
Show file tree
Hide file tree
Showing 6 changed files with 124 additions and 68 deletions.
19 changes: 4 additions & 15 deletions include/grid_map_geo/grid_map_geo.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ struct Location {

class GridMapGeo {
public:
GridMapGeo();
GridMapGeo(const std::string frame_id = "map");
virtual ~GridMapGeo();

/**
Expand Down Expand Up @@ -88,33 +88,24 @@ class GridMapGeo {
origin = maporigin_.position;
};

/**
* @brief Set the Altitude Origin object
*
* @param altitude
*/
void setAltitudeOrigin(const double altitude) { localorigin_altitude_ = altitude; };

/**
* @brief Helper function for loading terrain from path
*
* @param map_path Path to dsm path (Supported formats are *.tif)
* @param algin_terrain Geo align terrain
* @param color_map_path Path to color raster files to visualize terrain texture (Supported formats are *.tif)
* @return true Successfully loaded terrain
* @return false Failed to load terrain
*/
bool Load(const std::string& map_path, bool algin_terrain, const std::string color_map_path = "");
bool Load(const std::string& map_path, const std::string color_map_path = "");

/**
* @brief Initialize grid map from a geotiff file
*
* @param path Path to dsm path (Supported formats are *.tif)
* @param align_terrain
* @return true Successfully loaded terrain
* @return false Failed to load terrain
*/
bool initializeFromGeotiff(const std::string& path, bool align_terrain = true);
bool initializeFromGeotiff(const std::string& path);

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

protected:
grid_map::GridMap grid_map_;
double localorigin_e_{789823.93}; // duerrboden berghaus
double localorigin_n_{177416.56};
double localorigin_altitude_{0.0};
Location maporigin_;
std::string frame_id_{""};
};
#endif
81 changes: 65 additions & 16 deletions launch/config.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,12 @@ Panels:
- /Global Options1
- /Status1
- /GridMap1
- /GridMap2
- /GridMap2/Status1
- /TF1
- /TF1/Status1
Splitter Ratio: 0.5
Tree Height: 848
Tree Height: 839
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expand All @@ -24,7 +28,6 @@ Panels:
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: ""
Expand Down Expand Up @@ -59,11 +62,14 @@ Visualization Manager:
Color: 200; 200; 200
Color Layer: color
Color Transformer: ColorLayer
ColorMap: default
Enabled: true
Grid Cell Decimation: 1
Grid Line Thickness: 0.10000000149011612
Height Layer: elevation
Height Transformer: GridMapLayer
History Length: 1
Invert Rainbow: false
Invert ColorMap: false
Max Color: 255; 255; 255
Max Intensity: 10
Min Color: 0; 0; 0
Expand All @@ -72,13 +78,56 @@ Visualization Manager:
Show Grid Lines: false
Topic: /elevation_map
Unreliable: false
Use Rainbow: true
Use ColorMap: true
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Class: grid_map_rviz_plugin/GridMap
Color: 200; 200; 200
Color Layer: elevation
Color Transformer: GridMapLayer
ColorMap: default
Enabled: true
Grid Cell Decimation: 1
Grid Line Thickness: 0.10000000149011612
Height Layer: elevation
Height Transformer: GridMapLayer
History Length: 1
Invert ColorMap: false
Max Color: 255; 255; 255
Max Intensity: 10
Min Color: 0; 0; 0
Min Intensity: 0
Name: GridMap
Show Grid Lines: false
Topic: /elevation2
Unreliable: false
Use ColorMap: true
Value: true
- Class: rviz/TF
Enabled: true
Frame Timeout: 15
Frames:
All Enabled: true
map:
Value: true
world:
Value: true
Marker Alpha: 1
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
{}
Update Interval: 0
Value: true
Enabled: true
Global Options:
Background Color: 255; 255; 255
Default Light: true
Fixed Frame: map
Fixed Frame: sertig
Frame Rate: 30
Name: root
Tools:
Expand All @@ -102,33 +151,33 @@ Visualization Manager:
Views:
Current:
Class: rviz/Orbit
Distance: 2959.1279296875
Distance: 16350.146484375
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: 11.737425804138184
Y: -95.61576843261719
Z: 43.985958099365234
X: -428.4516906738281
Y: -385.00115966796875
Z: 529.86865234375
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.8253984451293945
Pitch: 0.7153984904289246
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 0.6203981637954712
Yaw: 0.48539578914642334
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1145
Height: 1136
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd000000040000000000000156000003dbfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000003db000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000003dbfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000003db000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073d0000003efc0100000002fb0000000800540069006d006501000000000000073d000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000004cc000003db00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
QMainWindow State: 000000ff00000000fd000000040000000000000283000003d2fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000003d2000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000003d2fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000003d2000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007380000003efc0100000002fb0000000800540069006d0065010000000000000738000003bc00fffffffb0000000800540069006d006501000000000000045000000000000000000000039a000003d200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
Expand All @@ -137,6 +186,6 @@ Window Geometry:
collapsed: false
Views:
collapsed: false
Width: 1853
X: 67
Width: 1848
X: 72
Y: 27
22 changes: 22 additions & 0 deletions launch/load_multiple_tif.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
<launch>
<arg name="visualization" default="true"/>
<arg name="location" default="sargans"/>
<node pkg="tf" type="static_transform_publisher" name="world_map" args="0 0 0 0 0 0 world map 10"/>

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

<node pkg="grid_map_geo" type="test_tif_loader" name="second_tif_loader2" output="screen">
<param name="frame_id" value="dischma_valley"/>
<param name="tif_path" value="$(find terrain_models)/models/dischma_valley.tif"/>
<param name="color_path" value="$(find terrain_models)/models/dischma_valley_color.tif"/>
<param name="topic_name" value="elevation2"/>
</node>

<group if="$(arg visualization)">
<node type="rviz" name="rviz" pkg="rviz" args="-d $(find grid_map_geo)/launch/config.rviz" />
</group>
</launch>
1 change: 1 addition & 0 deletions launch/load_tif.launch
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
<node pkg="tf" type="static_transform_publisher" name="world_map" args="0 0 0 0 0 0 world map 10"/>

<node pkg="grid_map_geo" type="test_tif_loader" name="test_tif_loader" output="screen">
<param name="frame_id" value="map"/>
<param name="tif_path" value="$(find grid_map_geo)/resources/sertig.tif"/>
<!-- <param name="color_path" value="$(find grid_map_geo)/resources/sertig_color.tif"/> -->
</node>
Expand Down
54 changes: 24 additions & 30 deletions src/grid_map_geo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,20 +43,23 @@
#include <grid_map_core/iterators/CircleIterator.hpp>
#include <grid_map_core/iterators/GridMapIterator.hpp>

GridMapGeo::GridMapGeo() {}
#include <geometry_msgs/TransformStamped.h>
#include <tf2_ros/static_transform_broadcaster.h>

GridMapGeo::GridMapGeo(const std::string frame_id) { frame_id_ = frame_id; }

GridMapGeo::~GridMapGeo() {}

bool GridMapGeo::Load(const std::string &map_path, bool algin_terrain, const std::string color_map_path) {
bool loaded = initializeFromGeotiff(map_path, algin_terrain);
bool GridMapGeo::Load(const std::string &map_path, const std::string color_map_path) {
bool loaded = initializeFromGeotiff(map_path);
if (!color_map_path.empty()) { // Load color layer if the color path is nonempty
bool color_loaded = addColorFromGeotiff(color_map_path);
}
if (!loaded) return false;
return true;
}

bool GridMapGeo::initializeFromGeotiff(const std::string &path, bool align_terrain) {
bool GridMapGeo::initializeFromGeotiff(const std::string &path) {
GDALAllRegister();
GDALDataset *dataset = (GDALDataset *)GDALOpen(path.c_str(), GA_ReadOnly);
if (!dataset) {
Expand All @@ -80,6 +83,8 @@ bool GridMapGeo::initializeFromGeotiff(const std::string &path, bool align_terra
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");
// Get image metadata
unsigned width = dataset->GetRasterXSize();
unsigned height = dataset->GetRasterYSize();
Expand All @@ -99,24 +104,9 @@ bool GridMapGeo::initializeFromGeotiff(const std::string &path, bool align_terra

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

/// TODO: Generalize to set local origin as center of map position
// Eigen::Vector3d origin_lv03 =
// transformCoordinates(ESPG::WGS84, std::string(pszProjection), localorigin_wgs84_.position);
// localorigin_e_ = origin_lv03(0);
// localorigin_n_ = origin_lv03(1);
// localorigin_altitude_ = origin_lv03(2);
// if (align_terrain) {
// std::cout << "[GridMapGeo] Aligning terrain!" << std::endl;
// double map_position_x = mapcenter_e - localorigin_e_;
// double map_position_y = mapcenter_n - localorigin_n_;
// position = Eigen::Vector2d(map_position_x, map_position_y);
// } else {
// std::cout << "[GridMapGeo] Not aligning terrain!" << std::endl;
// }

grid_map_.setGeometry(length, resolution, position);
/// TODO: Use TF for geocoordinates
grid_map_.setFrameId("map");
grid_map_.setFrameId(frame_id_);
grid_map_.add("elevation");
GDALRasterBand *elevationBand = dataset->GetRasterBand(1);

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

/// TODO: This is a workaround with the problem of gdal 3 not translating altitude correctly.
/// This section just levels the current position to the ground
double altitude{0.0};
if (grid_map_.isInside(Eigen::Vector2d(0.0, 0.0))) {
altitude = grid_map_.atPosition("elevation", Eigen::Vector2d(0.0, 0.0));
}
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 = mapcenter_e;
static_transformStamped.transform.translation.y = mapcenter_n;
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);

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

Expand Down
15 changes: 8 additions & 7 deletions src/test_tif_loader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,20 +54,21 @@ int main(int argc, char **argv) {
ros::NodeHandle nh("");
ros::NodeHandle nh_private("~");

ros::Publisher original_map_pub = nh.advertise<grid_map_msgs::GridMap>("elevation_map", 1, true);

std::string file_path, color_path;
std::string frame_id, file_path, color_path, topic_name;
nh_private.param<std::string>("frame_id", frame_id, "map");
nh_private.param<std::string>("tif_path", file_path, "");
nh_private.param<std::string>("color_path", color_path, "");
nh_private.param<std::string>("topic_name", topic_name, "elevation_map");

ros::Publisher original_map_pub = nh.advertise<grid_map_msgs::GridMap>(topic_name, 1, true);

std::shared_ptr<GridMapGeo> map = std::make_shared<GridMapGeo>();
map->Load(file_path, false, color_path);
std::shared_ptr<GridMapGeo> map = std::make_shared<GridMapGeo>(frame_id);
map->Load(file_path, color_path);

while (true) {
/// TODO: Publish gridmap
MapPublishOnce(original_map_pub, map->getGridMap());
ros::Duration(10.0).sleep();
ros::Duration(3.0).sleep();
ros::Duration(1.0).sleep();
}

ros::spin();
Expand Down

0 comments on commit e55f57b

Please sign in to comment.