Skip to content

Commit 46fd31d

Browse files
committed
Port terrain loader to ROS 2
* Needs a node instance to get the time * Move rviz config to the rviz directory * Use new grid map shared pointer API for converting to ROS messages * Install new node in the ament index Signed-off-by: Ryan Friedman <[email protected]>
1 parent 51c379a commit 46fd31d

File tree

7 files changed

+39
-31
lines changed

7 files changed

+39
-31
lines changed

README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -77,7 +77,7 @@ ros2 launch grid_map_geo load_tif_launch.xml
7777

7878
One can load a DEM from a terrain server directly.
7979
```
80-
roslaunch grid_map_geo run_terrain_loader.launch
80+
ros2 launch grid_map_geo run_terrain_loader.launch.xml
8181
```
8282

8383
![terrain-loader](https://github.com/ethz-asl/grid_map_geo/assets/5248102/e93b2c86-c26a-477c-8704-dc0233b7ef2e)

grid_map_geo/CMakeLists.txt

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -96,7 +96,8 @@ ament_export_dependencies(Eigen3 GDAL grid_map_core grid_map_msgs grid_map_ros t
9696

9797
install(
9898
TARGETS
99-
test_tif_loader
99+
test_tif_loader
100+
terrain_loader
100101
DESTINATION lib/${PROJECT_NAME}
101102
)
102103

grid_map_geo/include/grid_map_geo/grid_map_geo.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@
3434
#ifndef GRID_MAP_GEO_H
3535
#define GRID_MAP_GEO_H
3636

37-
#include <tf2_ros/transform_broadcaster.h>
37+
#include <tf2_ros/static_transform_broadcaster.h>
3838

3939
#include <grid_map_core/GridMap.hpp>
4040
#include <grid_map_core/iterators/GridMapIterator.hpp>
@@ -117,7 +117,7 @@ class GridMapGeo {
117117
*/
118118
bool initializeFromGeotiff(const std::string& path);
119119

120-
bool initializeFromVrt(const std::string& path, const Eigen::Vector2d& map_center, Eigen::Vector2d& extent);
120+
bool initializeFromVrt(const std::string& path, const Eigen::Vector2d& map_center, Eigen::Vector2d& extent, rclcpp::Node::SharedPtr node_ptr);
121121

122122
/**
123123
* @brief Load a color layer from a geotiff file (orthomosaic)

grid_map_geo/launch/run_terrain_loader.launch renamed to grid_map_geo/launch/run_terrain_loader.launch.xml

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -2,12 +2,12 @@
22
<arg name="visualization" default="true"/>
33
<arg name="location" default="hinwil"/>
44

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

10-
<group if="$(arg visualization)">
11-
<node type="rviz" name="rviz" pkg="rviz" args="-d $(find grid_map_geo)/launch/terrain_loader.rviz" output="screen"/>
10+
<group if="$(var visualization)">
11+
<node exec="rviz2" name="rviz2" pkg="rviz2" args="-d $(find-pkg-share grid_map_geo)/rviz/terrain_loader.rviz" output="screen"/>
1212
</group>
1313
</launch>
File renamed without changes.

grid_map_geo/src/grid_map_geo.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -145,7 +145,7 @@ bool GridMapGeo::initializeFromGeotiff(const std::string &path) {
145145
}
146146

147147
bool GridMapGeo::initializeFromVrt(const std::string &path, const Eigen::Vector2d &map_center,
148-
Eigen::Vector2d &extent) {
148+
Eigen::Vector2d &extent, rclcpp::Node::SharedPtr node_ptr) {
149149
GDALAllRegister();
150150
GDALDataset *dataset = (GDALDataset *)GDALOpen(path.c_str(), GA_ReadOnly);
151151
if (!dataset) {
@@ -223,10 +223,10 @@ bool GridMapGeo::initializeFromVrt(const std::string &path, const Eigen::Vector2
223223
layer_elevation(x, y) = data[gridMapIndex(0) + grid_width * gridMapIndex(1)];
224224
}
225225

226-
static tf2_ros::StaticTransformBroadcaster static_broadcaster;
227-
geometry_msgs::TransformStamped static_transformStamped;
226+
static tf2_ros::StaticTransformBroadcaster static_broadcaster(node_ptr);
227+
geometry_msgs::msg::TransformStamped static_transformStamped;
228228

229-
static_transformStamped.header.stamp = ros::Time::now();
229+
static_transformStamped.header.stamp = node_ptr->now();
230230
static_transformStamped.header.frame_id = name_coordinate;
231231
static_transformStamped.child_frame_id = frame_id_;
232232
static_transformStamped.transform.translation.x = map_center(0);

grid_map_geo/src/terrain_loader.cpp

Lines changed: 27 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -37,12 +37,13 @@
3737
* @author Jaeyoung Lim <[email protected]>
3838
*/
3939

40-
#include <grid_map_geo/grid_map_geo.h>
41-
#include <grid_map_msgs/GridMap.h>
42-
#include <ros/ros.h>
40+
#include <grid_map_geo/grid_map_geo.hpp>
41+
#include <grid_map_msgs/msg/grid_map.hpp>
42+
#include <rclcpp/rclcpp.hpp>
4343
#include <grid_map_ros/GridMapRosConverter.hpp>
4444

4545
#include <gdal/ogr_spatialref.h>
46+
#include <gdal/ogr_geometry.h>
4647

4748
constexpr int ESPG_WGS84 = 4326;
4849
constexpr int ESPG_CH1903_LV03 = 21781;
@@ -67,7 +68,8 @@ void transformCoordinates(int src_coord, const double &x, const double &y, const
6768
}
6869

6970
void LoadTerrainFromVrt(std::string path, const Eigen::Vector3d &query_position, const Eigen::Vector2d &offset,
70-
grid_map::GridMap &map, grid_map::GridMap &vrt_map_object) {
71+
grid_map::GridMap &map, grid_map::GridMap &vrt_map_object,
72+
rclcpp::Node::SharedPtr node_ptr) {
7173
std::shared_ptr<GridMapGeo> vrt_map = std::make_shared<GridMapGeo>();
7274

7375
Eigen::Vector3d query_position_lv03 = query_position;
@@ -80,7 +82,7 @@ void LoadTerrainFromVrt(std::string path, const Eigen::Vector3d &query_position,
8082
std::cout << " - map_center_wgs84:" << map_center_wgs84.transpose() << std::endl;
8183
/// TODO: Discover extent from corners
8284
Eigen::Vector2d extent_wgs84(0.5, 0.5);
83-
vrt_map->initializeFromVrt(path, map_center_wgs84.head(2), extent_wgs84);
85+
vrt_map->initializeFromVrt(path, map_center_wgs84.head(2), extent_wgs84, node_ptr);
8486
std::cout << " - Success!" << std::endl;
8587

8688
/// TODO: Loaded VRT map
@@ -115,15 +117,16 @@ void LoadTerrainFromVrt(std::string path, const Eigen::Vector3d &query_position,
115117
}
116118

117119
int main(int argc, char **argv) {
118-
ros::init(argc, argv, "terrain_loader");
119-
ros::NodeHandle nh("");
120-
ros::NodeHandle nh_private("~");
120+
rclcpp::init(argc, argv);
121+
// ros::init(argc, argv, "terrain_loader");
122+
auto node = rclcpp::Node::make_shared("terrain_loader");
123+
// ros::NodeHandle nh("");
124+
// ros::NodeHandle nh_private("~");
121125

122-
ros::Publisher map_pub = nh.advertise<grid_map_msgs::GridMap>("grid_map", 1, true);
123-
ros::Publisher map_pub2 = nh.advertise<grid_map_msgs::GridMap>("grid_map2", 1, true);
126+
auto map_pub = node->create_publisher<grid_map_msgs::msg::GridMap>("grid_map", rclcpp::QoS(1).transient_local());
127+
auto map_pub2 = node->create_publisher<grid_map_msgs::msg::GridMap>("grid_map2", rclcpp::QoS(1).transient_local());
124128

125-
std::string path;
126-
nh_private.param<std::string>("terrain_path", path, "resources/cadastre.tif");
129+
auto const path = node->declare_parameter("terrain_path", "resources/cadastre.tif");
127130

128131
Eigen::Vector3d test_position = Eigen::Vector3d(783199.15, 187585.10, 0.0);
129132

@@ -133,18 +136,22 @@ int main(int argc, char **argv) {
133136

134137
grid_map::GridMap map;
135138
grid_map::GridMap vrt_map;
136-
LoadTerrainFromVrt(path, query_position, offset.head(2), map, vrt_map);
139+
LoadTerrainFromVrt(path, query_position, offset.head(2), map, vrt_map, node);
137140
std::cout << "i: " << i << " offset: " << offset.transpose() << std::endl;
138141

139-
grid_map_msgs::GridMap msg;
140-
grid_map::GridMapRosConverter::toMessage(map, msg);
141-
map_pub.publish(msg);
142+
// grid_map_msgs::msg::GridMap msg;
143+
auto msg = grid_map::GridMapRosConverter::toMessage(map);
144+
if(msg) {
145+
map_pub->publish(std::move(msg));
146+
}
142147

143-
grid_map_msgs::GridMap msg2;
144-
grid_map::GridMapRosConverter::toMessage(vrt_map, msg2);
145-
map_pub2.publish(msg2);
148+
auto msg2 = grid_map::GridMapRosConverter::toMessage(vrt_map);
149+
if (msg2) {
150+
map_pub2->publish(std::move(msg2));
151+
}
146152
}
147153

148-
ros::spin();
154+
rclcpp::spin(node);
155+
rclcpp::shutdown();
149156
return 0;
150157
}

0 commit comments

Comments
 (0)