Skip to content

Commit 6eea0ef

Browse files
authored
Port to humble (#24)
* Port to ROS 2 Signed-off-by: Ryan Friedman <[email protected]> * Get launch file running aside from resources * Update docs * Remove ROS1 cruft Signed-off-by: Ryan Friedman <[email protected]> --------- Signed-off-by: Ryan Friedman <[email protected]>
1 parent dfb064d commit 6eea0ef

File tree

11 files changed

+110
-81
lines changed

11 files changed

+110
-81
lines changed

CMakeLists.txt

Lines changed: 44 additions & 38 deletions
Original file line numberDiff line numberDiff line change
@@ -1,62 +1,68 @@
1-
cmake_minimum_required(VERSION 3.8)
1+
cmake_minimum_required(VERSION 3.14.4)
22
project(grid_map_geo)
33

4+
if(NOT CMAKE_C_STANDARD)
5+
set(CMAKE_C_STANDARD 99)
6+
endif()
7+
if(NOT CMAKE_CXX_STANDARD)
8+
set(CMAKE_CXX_STANDARD 17)
9+
endif()
410

5-
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
11+
# Set policy for 3.16 for CMP0076 defaulting to ON
12+
cmake_policy(VERSION 3.16)
13+
14+
if(CMAKE_CXX_COMPILER_ID MATCHES "GNU" OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
615
add_compile_options(-Wall -Wextra -Wpedantic)
716
endif()
817

9-
# find dependencies
10-
find_package(GDAL REQUIRED)
11-
find_package(eigen3_cmake_module REQUIRED)
12-
find_package(Eigen3)
13-
18+
find_package(GDAL 3 REQUIRED)
1419
find_package(ament_cmake REQUIRED)
15-
find_package(rclcpp REQUIRED)
16-
find_package(std_msgs REQUIRED)
17-
find_package(geometry_msgs REQUIRED)
18-
find_package(grid_map_core REQUIRED)
1920
find_package(grid_map_ros REQUIRED)
20-
find_package(grid_map_msgs REQUIRED)
21+
find_package(grid_map_core REQUIRED)
22+
find_package(Eigen3 REQUIRED)
2123

24+
add_library(${PROJECT_NAME})
25+
add_subdirectory(src)
2226

23-
include_directories(
24-
include
27+
target_include_directories(${PROJECT_NAME}
28+
PUBLIC
29+
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
30+
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
2531
)
2632

27-
add_library(${PROJECT_NAME}
28-
src/grid_map_geo.cpp
29-
)
30-
ament_target_dependencies(${PROJECT_NAME} rclcpp std_msgs geometry_msgs grid_map_core grid_map_ros grid_map_msgs)
31-
target_include_directories(${PROJECT_NAME} PUBLIC "${Eigen3_INCLUDE_DIRS}")
32-
target_link_libraries(${PROJECT_NAME} ${GDAL_LIBRARY})
33+
# Reverse compatability for GDAL<3.5
34+
# https://gdal.org/development/cmake.html
35+
if(NOT TARGET GDAL::GDAL)
36+
add_library(GDAL::GDAL ALIAS ${GDAL_LIBRARY})
37+
endif()
3338

34-
add_executable(test_tif_loader
35-
src/test_tif_loader.cpp
36-
)
37-
ament_target_dependencies(test_tif_loader rclcpp std_msgs)
38-
target_include_directories(test_tif_loader PUBLIC "${Eigen3_INCLUDE_DIRS}")
39-
target_link_libraries(test_tif_loader ${PROJECT_NAME} ${GDAL_LIBRARY})
39+
target_link_libraries(${PROJECT_NAME} Eigen3::Eigen GDAL::GDAL grid_map_core::grid_map_core)
40+
41+
ament_export_targets(${PROJECT_NAME}Targets HAS_LIBRARY_TARGET)
42+
ament_export_dependencies(GDAL)
4043

41-
install(TARGETS
42-
test_tif_loader
43-
DESTINATION lib/${PROJECT_NAME})
44+
install(
45+
DIRECTORY include/
46+
DESTINATION include
47+
)
4448

4549
install(DIRECTORY
4650
launch
4751
DESTINATION share/${PROJECT_NAME}/
4852
)
4953

54+
install(
55+
TARGETS ${PROJECT_NAME}
56+
EXPORT ${PROJECT_NAME}Targets
57+
LIBRARY DESTINATION lib
58+
ARCHIVE DESTINATION lib
59+
RUNTIME DESTINATION bin
60+
INCLUDES DESTINATION include
61+
)
62+
63+
include(CTest)
5064
if(BUILD_TESTING)
51-
find_package(ament_lint_auto REQUIRED)
52-
# the following line skips the linter which checks for copyrights
53-
# comment the line when a copyright and license is added to all source files
54-
set(ament_cmake_copyright_FOUND TRUE)
55-
# the following line skips cpplint (only works in a git repo)
56-
# comment the line when this package is in a git repo and when
57-
# a copyright and license is added to all source files
58-
set(ament_cmake_cpplint_FOUND TRUE)
59-
ament_lint_auto_find_test_dependencies()
65+
add_subdirectory(test)
6066
endif()
6167

6268
ament_package()

README.md

Lines changed: 7 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -10,30 +10,22 @@ This package provides a georeferenced extension to the elevation map [grid_map](
1010
Affiliation: [ETH Zurich, Autonomous Systems Lab](https://asl.ethz.ch/)<br />**
1111
## Setup
1212
Install the dependencies. This package depends on gdal, to read georeferenced images and GeoTIFF files.
13-
```
14-
apt install libgdal-dev
15-
```
16-
Configure the catkin workspace
17-
```
18-
catkin config --extend "/opt/ros/noetic"
19-
catkin config --merge-devel
20-
```
2113

22-
Pull in dependencies using rosinstall / rosdep
14+
Pull in dependencies using rosdep
2315
```
24-
wstool init src src/grid_map_geo/dependencies.rosinstall
25-
wstool update -t src -j4
16+
source /opt/ros/humble/setup.bash
2617
rosdep update
27-
rosdep install --from-paths src --ignore-src -y --rosdistro noetic
18+
# Assuming the package is cloned in the src folder of a ROS workspace...
19+
rosdep install --from-paths src --ignore-src -y
2820
```
2921

3022
Build the package
3123
```
32-
catkin config --cmake-args -DCMAKE_BUILD_TYPE=Release -DCATKIN_ENABLE_TESTING=False
33-
catkin build -j$(nproc) -l$(nproc) grid_map_geo
24+
colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release -DCATKIN_ENABLE_TESTING=False --packages-up-to grid_map_geo
3425
```
3526
## Running the package
3627
The default launch file can be run as the following command.
3728
```
38-
roslaunch grid_map_geo load_tif.launch
29+
source install/setup.bash
30+
ros2 launch grid_map_geo load_tif_launch.xml
3931
```

include/grid_map_geo/grid_map_geo.h renamed to include/grid_map_geo/grid_map_geo.hpp

Lines changed: 1 addition & 1 deletion
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 "grid_map_geo/transform.h"
37+
#include "grid_map_geo/transform.hpp"
3838

3939
#include <grid_map_core/GridMap.hpp>
4040
#include <grid_map_core/iterators/GridMapIterator.hpp>
File renamed without changes.

launch/load_tif_launch.xml

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
<launch>
2+
<arg name="visualization" default="true"/>
3+
<arg name="location" default="sargans"/>
4+
<node pkg="tf2_ros" exec="static_transform_publisher" name="world_map" args="--frame-id world --child-frame-id map"/>
5+
6+
<node pkg="grid_map_geo" exec="test_tif_loader" name="test_tif_loader" output="screen">
7+
<param name="tif_path" value="$(find-pkg-share grid_map_geo)/resources/sertig.tif"/>
8+
<param name="color_path" value="$(find-pkg-share grid_map_geo)/resources/sertig_color.tif"/>
9+
</node>
10+
11+
<group if="$(var visualization)">
12+
<node exec="rviz" name="rviz" pkg="rviz" args="-d $(find-pkg-share grid_map_geo)/launch/config.rviz" />
13+
</group>
14+
</launch>

package.xml

Lines changed: 16 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -2,18 +2,25 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>grid_map_geo</name>
5-
<version>0.0.0</version>
6-
<description>TODO: Package description</description>
7-
<maintainer email="[email protected]">jaeyoung</maintainer>
8-
<license>TODO: License declaration</license>
5+
<version>0.0.1</version>
6+
<description>Georeferenced grid map</description>
7+
<maintainer email="[email protected]">Jaeyoung Lim</maintainer>
8+
<maintainer email="[email protected]">Ryan Friedman</maintainer>
9+
<author>Jaeyoung Lim</author>
10+
<license>BSD-3</license>
911

10-
<buildtool_depend>ament_cmake</buildtool_depend>
12+
<url type="website">https://github.com/Jaeyoung-Lim/grid_map_geo</url>
13+
<url type="bugtracker">https://github.com/Jaeyoung-Lim/grid_map_geo/issues</url>
1114

12-
<test_depend>ament_lint_auto</test_depend>
13-
<test_depend>ament_lint_common</test_depend>
14-
<depend>rclcpp</depend>
15+
<buildtool_depend>ament_cmake</buildtool_depend>
16+
<depend>eigen</depend>
1517
<depend>grid_map_core</depend>
18+
<depend>grid_map_ros</depend>
19+
<depend>libgdal-dev</depend>
20+
<depend>rclcpp</depend>
21+
<exec_depend>ros2launch</exec_depend>
22+
1623
<export>
1724
<build_type>ament_cmake</build_type>
1825
</export>
19-
</package>
26+
</package>

src/CMakeLists.txt

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
target_sources(${PROJECT_NAME} PRIVATE grid_map_geo.cpp)
2+
3+
4+
find_package(rclcpp REQUIRED)
5+
find_package(grid_map_msgs REQUIRED)
6+
find_package(grid_map_ros REQUIRED)
7+
add_executable(test_tif_loader)
8+
target_sources(test_tif_loader PRIVATE test_tif_loader.cpp)
9+
target_link_libraries(test_tif_loader PRIVATE ${PROJECT_NAME} rclcpp::rclcpp ${grid_map_msgs_TARGETS})
10+
ament_target_dependencies(${PROJECT_NAME} grid_map_ros)

src/grid_map_geo.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@
3737
* @author Jaeyoung Lim <[email protected]>
3838
*/
3939

40-
#include "grid_map_geo/grid_map_geo.h"
40+
#include "grid_map_geo/grid_map_geo.hpp"
4141

4242
#include <grid_map_core/GridMapMath.hpp>
4343
#include <grid_map_core/iterators/CircleIterator.hpp>

src/test_tif_loader.cpp

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

40-
#include "grid_map_geo/grid_map_geo.h"
40+
#include "grid_map_geo/grid_map_geo.hpp"
4141

4242
#include "rclcpp/rclcpp.hpp"
4343
#include "std_msgs/msg/string.hpp"
@@ -52,11 +52,8 @@ class MapPublisher : public rclcpp::Node {
5252
MapPublisher() : Node("map_publisher") {
5353
original_map_pub_ = this->create_publisher<grid_map_msgs::msg::GridMap>("elevation_map", 1);
5454

55-
this->declare_parameter("tif_path", ".");
56-
this->declare_parameter("tif_color_path", ".");
57-
58-
std::string file_path = this->get_parameter("tif_path").as_string();
59-
std::string color_path = this->get_parameter("tif_color_path").as_string();
55+
std::string file_path = this->declare_parameter("tif_path", ".");
56+
std::string color_path = this->declare_parameter("tif_color_path", ".");
6057

6158
map_ = std::make_shared<GridMapGeo>();
6259
map_->Load(file_path, false, color_path);
@@ -68,13 +65,8 @@ class MapPublisher : public rclcpp::Node {
6865
original_map_pub_->publish(std::move(msg));
6966
}
7067
rclcpp::TimerBase::SharedPtr timer_;
71-
size_t count_{0};
7268
rclcpp::Publisher<grid_map_msgs::msg::GridMap>::SharedPtr original_map_pub_;
7369
std::shared_ptr<GridMapGeo> map_;
74-
// void MapPublishOnce(ros::Publisher &pub, grid_map::GridMap &map) {
75-
// map.setTimestamp(ros::Time::now().toNSec());
76-
// pub.publish(message);
77-
// }
7870
};
7971

8072
int main(int argc, char **argv) {

test/CMakeLists.txt

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
# Add gtest based cpp test target and link libraries
2+
find_package(ament_cmake_gtest)
3+
ament_add_gtest(${PROJECT_NAME}-test
4+
main.cpp
5+
test_grid_map_geo.cpp
6+
)
7+
8+
9+
target_link_libraries(${PROJECT_NAME}-test
10+
${PROJECT_NAME}
11+
# ${YAML_CPP_LIBRARIES}
12+
# ${GDAL_LIBRARY}
13+
)

0 commit comments

Comments
 (0)