Skip to content

Commit

Permalink
Hide GDAL from public interface, fix export (#59)
Browse files Browse the repository at this point in the history
* Enforce export in CI
* Hide implementation details of GDAL in implementation
* Switch to build-scope includes
* Install headers per latest ament recommendations to allow package: https://docs.ros.org/en/humble/How-To-Guides/Ament-CMake-Documentation.html#adding-targets
* This is crucial before realeasing as a library
* Remove unused yaml dependency
* Add all missing libraries in ament_export_dependencies
* Fix a few typos in comments
* Add badges for all jobs but point them to the default ros2 branch
  rather than any branch
* Fix style check not running on ros2 branch

Signed-off-by: Ryan Friedman <[email protected]>
  • Loading branch information
Ryanf55 authored Jan 28, 2024
1 parent 92dbada commit 3fd9206
Show file tree
Hide file tree
Showing 14 changed files with 133 additions and 67 deletions.
9 changes: 8 additions & 1 deletion .github/workflows/build_test.yml
Original file line number Diff line number Diff line change
Expand Up @@ -28,11 +28,18 @@ jobs:
rosdep install --from-paths src --ignore-src -y
shell: bash
- name: Colcon Build (Release)
working-directory:
run: |
source /opt/ros/${{matrix.config.rosdistro}}/setup.bash
colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release --packages-up-to grid_map_geo
shell: bash
- name: Verify Export
run: |
source /opt/ros/${{matrix.config.rosdistro}}/setup.bash
source install/setup.bash
cd src/grid_map_geo/test/export
colcon build
./build/grid_map_export_test/main
shell: bash
# - name: unit_tests
# working-directory:
# run: |
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/check_style.yml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ name: Style Checks
on:
push:
branches:
- master
- ros2
pull_request:
branches:
- '*'
Expand Down
14 changes: 7 additions & 7 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,6 @@ find_package(rclcpp REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(GDAL 3 REQUIRED)

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
Expand All @@ -37,13 +35,13 @@ endif()
# Build
add_library(${PROJECT_NAME}
src/grid_map_geo.cpp
src/transform.cpp
)

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

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

Expand Down Expand Up @@ -77,7 +75,9 @@ install(
)

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

# Everything in find_package goes here too, ordered alphabetically.
ament_export_dependencies(Eigen3 GDAL grid_map_core grid_map_msgs grid_map_ros tf2_ros rclcpp)

install(
TARGETS
Expand All @@ -103,7 +103,7 @@ install(DIRECTORY
# Test
include(CTest)
if(BUILD_TESTING)
add_subdirectory(test)
add_subdirectory(test/unit)
endif()

ament_package()
4 changes: 3 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
# grid_map_geo

[![Build Test](https://github.com/ethz-asl/grid_map_geo/actions/workflows/build_test.yml/badge.svg)](https://github.com/ethz-asl/grid_map_geo/actions/workflows/build_test.yml)
[![Build Test](https://github.com/ethz-asl/grid_map_geo/actions/workflows/build_test.yml/badge.svg?branch=ros2)](https://github.com/ethz-asl/grid_map_geo/actions/workflows/build_test.yml)
[![Doxygen Build](https://github.com/ethz-asl/grid_map_geo/actions/workflows/doxygen_build.yml/badge.svg?branch=ros2)](https://github.com/ethz-asl/grid_map_geo/actions/workflows/doxygen_build.yml)
[![Style Checks](https://github.com/ethz-asl/grid_map_geo/actions/workflows/check_style.yml/badge.svg?branch=ros2)](https://github.com/ethz-asl/grid_map_geo/actions/workflows/check_style.yml)

This package provides a georeferenced extension to the elevation map [grid_map](https://github.com/ANYbotics/grid_map) using [GDAL](https://gdal.org/), library for raster and vector geospatial data formats

Expand Down
9 changes: 5 additions & 4 deletions include/grid_map_geo/grid_map_geo.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,12 +34,13 @@
#ifndef GRID_MAP_GEO_H
#define GRID_MAP_GEO_H

#include <tf2_ros/transform_broadcaster.h>

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

#include "grid_map_geo/transform.hpp"
#include "tf2_ros/transform_broadcaster.h"
#include "transform.hpp"
struct Location {
ESPG espg{ESPG::WGS84};
Eigen::Vector3d position{Eigen::Vector3d::Zero()};
Expand Down Expand Up @@ -95,7 +96,7 @@ class GridMapGeo {
*
* @param map_path Path to dsm path (Supported formats are *.tif)
*/
bool Load(const std::string& map_path) { Load(map_path, ""); }
bool Load(const std::string& map_path) { return Load(map_path, ""); }

/**
* @brief Helper function for loading terrain from path
Expand Down Expand Up @@ -184,4 +185,4 @@ class GridMapGeo {
std::string frame_id_{""};
std::string coordinate_name_{""};
};
#endif
#endif // GRID_MAP_GEO_H
48 changes: 3 additions & 45 deletions include/grid_map_geo/transform.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,18 +34,6 @@
#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>

enum class ESPG { ECEF = 4978, WGS84 = 4326, WGS84_32N = 32632, CH1903_LV03 = 21781 };
Expand All @@ -58,21 +46,7 @@ enum class ESPG { ECEF = 4978, WGS84 = 4326, WGS84_32N = 32632, CH1903_LV03 = 21
* @param source_coordinates
* @return Eigen::Vector3d
*/
inline Eigen::Vector3d transformCoordinates(ESPG src_coord, ESPG tgt_coord, const Eigen::Vector3d source_coordinates) {
OGRSpatialReference source, target;
source.importFromEPSG(static_cast<int>(src_coord));
target.importFromEPSG(static_cast<int>(tgt_coord));

OGRPoint p;
p.setX(source_coordinates(0));
p.setY(source_coordinates(1));
p.setZ(source_coordinates(2));
p.assignSpatialReference(&source);

p.transformTo(&target);
Eigen::Vector3d target_coordinates(p.getX(), p.getY(), p.getZ());
return target_coordinates;
}
Eigen::Vector3d transformCoordinates(ESPG src_coord, ESPG tgt_coord, const Eigen::Vector3d source_coordinates);

/**
* @brief Helper function for transforming using gdal
Expand All @@ -82,22 +56,6 @@ inline Eigen::Vector3d transformCoordinates(ESPG src_coord, ESPG tgt_coord, cons
* @param source_coordinates
* @return Eigen::Vector3d
*/
inline Eigen::Vector3d transformCoordinates(ESPG src_coord, const std::string wkt,
const Eigen::Vector3d source_coordinates) {
OGRSpatialReference source, target;
char* wkt_string = const_cast<char*>(wkt.c_str());
source.importFromEPSG(static_cast<int>(src_coord));
target.importFromWkt(&wkt_string);

OGRPoint p;
p.setX(source_coordinates(0));
p.setY(source_coordinates(1));
p.setZ(source_coordinates(2));
p.assignSpatialReference(&source);

p.transformTo(&target);
Eigen::Vector3d target_coordinates(p.getX(), p.getY(), p.getZ());
return target_coordinates;
}
Eigen::Vector3d transformCoordinates(ESPG src_coord, const std::string wkt, const Eigen::Vector3d source_coordinates);

#endif
#endif // GRID_MAP_GEO_TRANSFORM_H
2 changes: 1 addition & 1 deletion src/grid_map_geo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
****************************************************************************/

/**
* @brief Terain map representation
* @brief Terrain map representation
*
* @author Jaeyoung Lim <[email protected]>
*/
Expand Down
16 changes: 9 additions & 7 deletions src/test_tif_loader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,19 +31,21 @@
*
****************************************************************************/
/**
* @brief Node to test planner in the view utiltiy map
* @brief Node to test planner in the view utility map
*
*
* @author Jaeyoung Lim <[email protected]>
*/

#include "geometry_msgs/msg/transform_stamped.hpp"
#include <grid_map_msgs/msg/grid_map.h>
#include <tf2_ros/static_transform_broadcaster.h>

#include <geometry_msgs/msg/transform_stamped.hpp>
#include <grid_map_ros/GridMapRosConverter.hpp>
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>

#include "grid_map_geo/grid_map_geo.hpp"
#include "grid_map_msgs/msg/grid_map.h"
#include "grid_map_ros/GridMapRosConverter.hpp"
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "tf2_ros/static_transform_broadcaster.h"

using namespace std::chrono_literals;

Expand Down
79 changes: 79 additions & 0 deletions src/transform.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
/****************************************************************************
*
* Copyright (c) 2022 Jaeyoung Lim, ASL, ETH Zurich, Switzerland
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name terrain-navigation nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/

#include "grid_map_geo/transform.hpp"

#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

Eigen::Vector3d transformCoordinates(ESPG src_coord, ESPG tgt_coord, const Eigen::Vector3d source_coordinates) {
OGRSpatialReference source, target;
source.importFromEPSG(static_cast<int>(src_coord));
target.importFromEPSG(static_cast<int>(tgt_coord));

OGRPoint p;
p.setX(source_coordinates(0));
p.setY(source_coordinates(1));
p.setZ(source_coordinates(2));
p.assignSpatialReference(&source);

p.transformTo(&target);
Eigen::Vector3d target_coordinates(p.getX(), p.getY(), p.getZ());
return target_coordinates;
}

Eigen::Vector3d transformCoordinates(ESPG src_coord, const std::string wkt, const Eigen::Vector3d source_coordinates) {
OGRSpatialReference source, target;
char* wkt_string = const_cast<char*>(wkt.c_str());
source.importFromEPSG(static_cast<int>(src_coord));
target.importFromWkt(&wkt_string);

OGRPoint p;
p.setX(source_coordinates(0));
p.setY(source_coordinates(1));
p.setZ(source_coordinates(2));
p.assignSpatialReference(&source);

p.transformTo(&target);
Eigen::Vector3d target_coordinates(p.getX(), p.getY(), p.getZ());
return target_coordinates;
}
7 changes: 7 additions & 0 deletions test/export/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
# Add gtest based cpp test target and link libraries
cmake_minimum_required(VERSION 3.14)
project(grid_map_export_test)
find_package(grid_map_geo REQUIRED)
add_executable(main main.cpp)
target_link_libraries(main PRIVATE grid_map_geo::grid_map_geo)

10 changes: 10 additions & 0 deletions test/export/main.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
#include <iostream>

#include "grid_map_geo/grid_map_geo.hpp"

int main() {
// Instantiate the class and call it so this doesn't get optimized out.
auto gmg = GridMapGeo();
std::cout << gmg.getCoordinateName() << std::endl;
return 0;
}
File renamed without changes.
File renamed without changes.
File renamed without changes.

0 comments on commit 3fd9206

Please sign in to comment.