Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
107 changes: 75 additions & 32 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,62 +1,105 @@
cmake_minimum_required(VERSION 3.8)
cmake_minimum_required(VERSION 3.14.4)
project(grid_map_geo)

if(NOT CMAKE_C_STANDARD)
set(CMAKE_C_STANDARD 99)
endif()
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
# Set policy for 3.16 for CMP0076 defaulting to ON
cmake_policy(VERSION 3.16)

if(CMAKE_CXX_COMPILER_ID MATCHES "GNU" OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(GDAL REQUIRED)
find_package(eigen3_cmake_module REQUIRED)
find_package(Eigen3)

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(grid_map_core REQUIRED)
find_package(grid_map_ros REQUIRED)
find_package(grid_map_msgs REQUIRED)
find_package(grid_map_ros REQUIRED)
find_package(grid_map_core REQUIRED)
find_package(rclcpp REQUIRED)

find_package(Eigen3 REQUIRED)
find_package(GDAL 3 REQUIRED)

include_directories(
include
)
find_package(yaml_cpp_vendor REQUIRED)
link_directories(${yaml_cpp_vendor_LIBRARY_DIRS})

# Reverse compatability for GDAL<3.5
# https://gdal.org/development/cmake.html
if(NOT TARGET GDAL::GDAL)
add_library(GDAL::GDAL ALIAS ${GDAL_LIBRARY})
endif()

# Build
add_library(${PROJECT_NAME}
src/grid_map_geo.cpp
)
ament_target_dependencies(${PROJECT_NAME} rclcpp std_msgs geometry_msgs grid_map_core grid_map_ros grid_map_msgs)
target_include_directories(${PROJECT_NAME} PUBLIC "${Eigen3_INCLUDE_DIRS}")
target_link_libraries(${PROJECT_NAME} ${GDAL_LIBRARY})

target_include_directories(${PROJECT_NAME}
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)

target_link_libraries(${PROJECT_NAME} Eigen3::Eigen GDAL::GDAL)

ament_target_dependencies(${PROJECT_NAME} SYSTEM
grid_map_core
Copy link
Owner Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

grid_map_core was already linked before through the namespaced target (preferred) compared to ament_target_dependencies. In conversations with the ROS maintainers, seems like the only thing ament_target_dependencies exists for these days is message packages because those can't use namespaced export targets yet.

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If:

ament_target_dependencies(${PROJECT_NAME} SYSTEM
  grid_map_core
  grid_map_ros
)

is replaced with:

target_link_libraries(${PROJECT_NAME}
  Eigen3::Eigen
  GDAL::GDAL
  grid_map_core
  grid_map_ros
)

then there is an error:

In file included from /Users/rhys/Code/ros2/humble/ros2-aerial/src/grid_map_geo/src/grid_map_geo.cpp:40:
In file included from /Users/rhys/Code/ros2/humble/ros2-aerial/src/grid_map_geo/include/grid_map_geo/grid_map_geo.hpp:37:
In file included from /Users/rhys/Code/ros2/humble/ros2-aerial/src/grid_map_geo/include/grid_map_geo/transform.hpp:49:
In file included from /opt/homebrew/include/eigen3/Eigen/Dense:1:
In file included from /opt/homebrew/include/eigen3/Eigen/Core:256:
/opt/homebrew/include/eigen3/Eigen/src/Core/functors/StlFunctors.h:159:10: fatal error: 'grid_map_core/eigen_plugins/FunctorsPlugin.hpp' file not found
#include EIGEN_FUNCTORS_PLUGIN
         ^~~~~~~~~~~~~~~~~~~~~
<command line>:2:31: note: expanded from macro 'EIGEN_FUNCTORS_PLUGIN'
#define EIGEN_FUNCTORS_PLUGIN "grid_map_core/eigen_plugins/FunctorsPlugin.hpp"
                              ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1 error generated.

The target grid_map_core::grid_map_core is not available. Something needing fixing upstream?

Copy link
Owner Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ah yes, try my patch here: ANYbotics/grid_map#404

Since grid_map seems largely unmaintained, we may have trouble getting changes in.

grid_map_ros
)

add_executable(test_tif_loader
src/test_tif_loader.cpp
)
ament_target_dependencies(test_tif_loader rclcpp std_msgs)
target_include_directories(test_tif_loader PUBLIC "${Eigen3_INCLUDE_DIRS}")
target_link_libraries(test_tif_loader ${PROJECT_NAME} ${GDAL_LIBRARY})

install(TARGETS
target_link_libraries(test_tif_loader
${PROJECT_NAME}
)

# Install
install(
DIRECTORY include/
DESTINATION include/${PROJECT_NAME}
)

install(
TARGETS
${PROJECT_NAME}
EXPORT export_${PROJECT_NAME}
ARCHIVE DESTINATION lib/${PROJECT_NAME}
LIBRARY DESTINATION lib/${PROJECT_NAME}
RUNTIME DESTINATION bin/${PROJECT_NAME}
)

ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET)
ament_export_dependencies(GDAL)

# NOTE: if RUNTIME DESTINATION is set to bin/${PROJECT_NAME} the executable
# is not found by ros2 launch:
#
# Caught exception in launch (see debug for traceback): executable
# 'test_tif_loader' not found on the libexec directory
# '<ws_path>/ros2-aerial/install/grid_map_geo/lib/grid_map_geo'
install(
TARGETS
test_tif_loader
DESTINATION lib/${PROJECT_NAME})
ARCHIVE DESTINATION lib/${PROJECT_NAME}
LIBRARY DESTINATION lib/${PROJECT_NAME}
RUNTIME DESTINATION lib/${PROJECT_NAME}
)

install(DIRECTORY
launch
DESTINATION share/${PROJECT_NAME}/
)

# Test
include(CTest)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# comment the line when a copyright and license is added to all source files
set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# comment the line when this package is in a git repo and when
# a copyright and license is added to all source files
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
add_subdirectory(test)
endif()

ament_package()
22 changes: 7 additions & 15 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,30 +10,22 @@ This package provides a georeferenced extension to the elevation map [grid_map](
Affiliation: [ETH Zurich, Autonomous Systems Lab](https://asl.ethz.ch/)<br />**
## Setup
Install the dependencies. This package depends on gdal, to read georeferenced images and GeoTIFF files.
```
apt install libgdal-dev
```
Configure the catkin workspace
```
catkin config --extend "/opt/ros/noetic"
catkin config --merge-devel
```

Pull in dependencies using rosinstall / rosdep
Pull in dependencies using rosdep
```
wstool init src src/grid_map_geo/dependencies.rosinstall
wstool update -t src -j4
source /opt/ros/humble/setup.bash
rosdep update
rosdep install --from-paths src --ignore-src -y --rosdistro noetic
# Assuming the package is cloned in the src folder of a ROS workspace...
rosdep install --from-paths src --ignore-src -y
```

Build the package
```
catkin config --cmake-args -DCMAKE_BUILD_TYPE=Release -DCATKIN_ENABLE_TESTING=False
catkin build -j$(nproc) -l$(nproc) grid_map_geo
colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release -DCATKIN_ENABLE_TESTING=False --packages-up-to grid_map_geo
```
## Running the package
The default launch file can be run as the following command.
```
roslaunch grid_map_geo load_tif.launch
source install/setup.bash
ros2 launch grid_map_geo load_tif_launch.xml
```
Original file line number Diff line number Diff line change
Expand Up @@ -34,16 +34,25 @@
#ifndef GRID_MAP_GEO_H
#define GRID_MAP_GEO_H

#include "grid_map_geo/transform.h"
#include "grid_map_geo/transform.hpp"

#include <grid_map_core/GridMap.hpp>
#include <grid_map_core/iterators/GridMapIterator.hpp>

#if __APPLE__
#include <cpl_string.h>
#include <gdal.h>
#include <gdal_priv.h>
#include <ogr_p.h>
#include <ogr_spatialref.h>
#else
#include <gdal/cpl_string.h>
#include <gdal/gdal.h>
#include <gdal/gdal_priv.h>
#include <gdal/ogr_p.h>
#include <gdal/ogr_spatialref.h>
#endif

#include <iostream>
struct Location {
ESPG espg{ESPG::WGS84};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,10 +34,17 @@
#ifndef GRID_MAP_GEO_TRANSFORM_H
#define GRID_MAP_GEO_TRANSFORM_H

#if __APPLE__
#include <gdal.h>
#include <gdal_priv.h>
#include <ogr_p.h>
#include <ogr_spatialref.h>
#else
#include <gdal/gdal.h>
#include <gdal/gdal_priv.h>
#include <gdal/ogr_p.h>
#include <gdal/ogr_spatialref.h>
#endif

#include <Eigen/Dense>

Expand Down
84 changes: 84 additions & 0 deletions launch/load_tif.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
import os

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.conditions import IfCondition
from launch.substitutions import LaunchConfiguration

from launch_ros.actions import Node


def generate_launch_description():
"""Generate a launch description."""

pkg_grid_map_geo = get_package_share_directory("grid_map_geo")

# static transform node
static_transform_publisher = Node(
package="tf2_ros",
executable="static_transform_publisher",
name="world_map",
arguments=[
"--frame-id",
"world",
"--child-frame-id",
"map",
],
)

# tif loader node
tif_loader = Node(
package="grid_map_geo",
namespace="grid_map_geo",
executable="test_tif_loader",
name="tif_loader",
parameters=[
{"tif_path": LaunchConfiguration("tif_path")},
{"tif_color_path": LaunchConfiguration("tif_color_path")},
],
output="screen",
emulate_tty=True,
)

# rviz node
rviz = Node(
package="rviz2",
executable="rviz2",
arguments=["-d", os.path.join(pkg_grid_map_geo, "launch", "config.rviz")],
condition=IfCondition(LaunchConfiguration("rviz")),
)

default_location = "sargans"
default_tif_file = "sargans.tif"
default_tif_color_file = "sargans_color.tif"
return LaunchDescription(
[
DeclareLaunchArgument(
"rviz", default_value="true", description="Open RViz."
),
DeclareLaunchArgument(
"location",
default_value=default_location,
description="Location.",
),
DeclareLaunchArgument(
"tif_path",
default_value=os.path.join(
pkg_grid_map_geo, "resources", default_tif_file
),
description="Full path to the elevation map file.",
),
DeclareLaunchArgument(
"tif_color_path",
default_value=os.path.join(
pkg_grid_map_geo, "resources", default_tif_color_file
),
description="Full path to the elevation texture file.",
),
static_transform_publisher,
tif_loader,
rviz,
]
)
14 changes: 14 additions & 0 deletions launch/load_tif_launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
<launch>
<arg name="rviz" default="true"/>
<arg name="location" default="sargans"/>
<node pkg="tf2_ros" exec="static_transform_publisher" name="world_map" args="--frame-id world --child-frame-id map"/>

<node pkg="grid_map_geo" exec="test_tif_loader" name="test_tif_loader" output="screen">
<param name="tif_path" value="$(find-pkg-share grid_map_geo)/resources/sargans.tif"/>
<param name="tif_color_path" value="$(find-pkg-share grid_map_geo)/resources/sargans_color.tif"/>
</node>

<group if="$(var rviz)">
<node exec="rviz2" name="rviz2" pkg="rviz2" args="-d $(find-pkg-share grid_map_geo)/launch/config.rviz" />
</group>
</launch>
30 changes: 0 additions & 30 deletions launch/run.launch.py

This file was deleted.

26 changes: 17 additions & 9 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,18 +2,26 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>grid_map_geo</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="[email protected]">jaeyoung</maintainer>
<license>TODO: License declaration</license>
<version>0.0.1</version>
<description>Georeferenced grid map</description>
<maintainer email="[email protected]">Jaeyoung Lim</maintainer>
<maintainer email="[email protected]">Ryan Friedman</maintainer>
<author>Jaeyoung Lim</author>
<license>BSD-3</license>

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

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<depend>rclcpp</depend>
<buildtool_depend>ament_cmake</buildtool_depend>
<depend>eigen</depend>
<depend>grid_map_core</depend>
<depend>grid_map_ros</depend>
<depend>libgdal-dev</depend>
<depend>rclcpp</depend>
<depend>yaml_cpp_vendor</depend>
<exec_depend>ros2launch</exec_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
</package>
2 changes: 1 addition & 1 deletion src/grid_map_geo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
* @author Jaeyoung Lim <[email protected]>
*/

#include "grid_map_geo/grid_map_geo.h"
#include "grid_map_geo/grid_map_geo.hpp"

#include <grid_map_core/GridMapMath.hpp>
#include <grid_map_core/iterators/CircleIterator.hpp>
Expand Down
Loading