Skip to content

Commit

Permalink
Geospatial component for heightmaps and DEM support (#292)
Browse files Browse the repository at this point in the history
Signed-off-by: Jenn Nguyen <[email protected]>
Signed-off-by: Steve Peters <[email protected]>

Co-authored-by: Steve Peters <[email protected]>
Co-authored-by: Jenn Nguyen <[email protected]>
Co-authored-by: Ian Chen <[email protected]>
Co-authored-by: Louise Poubel <[email protected]>
  • Loading branch information
4 people committed Mar 15, 2022
1 parent b960986 commit af583c9
Show file tree
Hide file tree
Showing 19 changed files with 465 additions and 262 deletions.
1 change: 1 addition & 0 deletions .github/ci/packages.apt
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@ libavdevice-dev
libavformat-dev
libavutil-dev
libfreeimage-dev
libgdal-dev
libgts-dev
libignition-cmake2-dev
libignition-math7-dev
Expand Down
11 changes: 9 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ message(STATUS "\n\n-- ====== Finding Dependencies ======")

#--------------------------------------
# Find ignition-math
ign_find_package(ignition-math7 REQUIRED_BY graphics events)
ign_find_package(ignition-math7 REQUIRED_BY geospatial graphics events)
set(IGN_MATH_VER ${ignition-math7_VERSION_MAJOR})

#--------------------------------------
Expand Down Expand Up @@ -94,6 +94,13 @@ ign_find_package(
REQUIRED_BY graphics
PRIVATE_FOR graphics)

#------------------------------------
# Find GDAL
ign_find_package(GDAL VERSION 3.0
PKGCONFIG gdal
PRIVATE_FOR geospatial
REQUIRED_BY geospatial)

#------------------------------------
# Find libswscale
ign_find_package(SWSCALE REQUIRED_BY av PRETTY libswscale)
Expand Down Expand Up @@ -125,7 +132,7 @@ configure_file("${PROJECT_SOURCE_DIR}/cppcheck.suppress.in"
${PROJECT_BINARY_DIR}/cppcheck.suppress)

ign_configure_build(QUIT_IF_BUILD_ERRORS
COMPONENTS av events graphics profiler)
COMPONENTS av events geospatial graphics profiler)

#============================================================================
# Create package information
Expand Down
13 changes: 13 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,21 @@ release will remove the deprecated code.

## Ignition Common 4.X to 5.X

### Additions

1. **geospatial** component that loads heightmap images and DEMs
+ Depends on the ign-common's `graphics` component and the `gdal` library

### Modifications

1. `HeightmapData.hh` and `ImageHeightmap.hh` have been moved out of the
`graphics` component and into the new `geospatial` component
+ To use the heightmap features, users must add the `geospatial` component
to the `find_package` call and update the include paths to use
the geospatial subfolder (`#include <ignition/common/geospatial/HeightmapData.hh>`)

1. `HeightmapData::FillHeightmap` method is now `const`.

1. `Image::AvgColor`, `Image::Data` and `Image::RGBData` methods are now `const`.

## Ignition Common 3.X to 4.X
Expand Down
2 changes: 2 additions & 0 deletions geospatial/include/ignition/common/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@

ign_install_all_headers(COMPONENT geospatial)
Original file line number Diff line number Diff line change
Expand Up @@ -14,30 +14,29 @@
* limitations under the License.
*
*/
#ifndef IGNITION_COMMON_DEM_HH_
#define IGNITION_COMMON_DEM_HH_
#ifndef IGNITION_COMMON_GEOSPATIAL_DEM_HH_
#define IGNITION_COMMON_GEOSPATIAL_DEM_HH_

#include <memory>
#include <string>
#include <vector>

#include <ignition/math/Vector3.hh>
#include <ignition/math/Angle.hh>

#include <ignition/common/graphics/Export.hh>
#include <ignition/common/geospatial/Export.hh>
#include <ignition/common/geospatial/HeightmapData.hh>

#include <ignition/utils/ImplPtr.hh>

#ifdef HAVE_GDAL
# include <string>
# include <vector>

# include <ignition/common/HeightmapData.hh>

namespace ignition
{
namespace common
{
/// \class DEM DEM.hh common/common.hh
/// \brief Encapsulates a DEM (Digital Elevation Model) file.
class IGNITION_COMMON_GRAPHICS_VISIBLE Dem : public HeightmapData
class IGNITION_COMMON_GEOSPATIAL_VISIBLE Dem : public HeightmapData
{
/// \brief Constructor.
public: Dem();
Expand All @@ -53,7 +52,8 @@ namespace ignition
/// \brief Get the elevation of a terrain's point in meters.
/// \param[in] _x X coordinate of the terrain.
/// \param[in] _y Y coordinate of the terrain.
/// \return Terrain's elevation at (x,y) in meters.
/// \return Terrain's elevation at (x,y) in meters or infinity if illegal
/// coordinates were provided.
public: double Elevation(double _x, double _y);

/// \brief Get the terrain's minimum elevation in meters.
Expand All @@ -68,7 +68,8 @@ namespace ignition
/// origin in WGS84.
/// \param[out] _latitude Georeferenced latitude.
/// \param[out] _longitude Georeferenced longitude.
public: void GeoReferenceOrigin(ignition::math::Angle &_latitude,
/// \return True if able to retrieve origin coordinates. False otherwise.
public: bool GeoReferenceOrigin(ignition::math::Angle &_latitude,
ignition::math::Angle &_longitude) const;

/// \brief Get the terrain's height. Due to the Ogre constrains, this
Expand Down Expand Up @@ -112,15 +113,16 @@ namespace ignition
const ignition::math::Vector3d &_size,
const ignition::math::Vector3d &_scale,
const bool _flipY,
std::vector<float> &_heights);
std::vector<float> &_heights) const;

/// \brief Get the georeferenced coordinates (lat, long) of a terrain's
/// pixel in WGS84.
/// \param[in] _x X coordinate of the terrain.
/// \param[in] _y Y coordinate of the terrain.
/// \param[out] _latitude Georeferenced latitude.
/// \param[out] _longitude Georeferenced longitude.
private: void GeoReference(double _x, double _y,
/// \return True if able to retrieve coordinates. False otherwise.
private: bool GeoReference(double _x, double _y,
ignition::math::Angle &_latitude,
ignition::math::Angle &_longitude) const;

Expand All @@ -130,11 +132,13 @@ namespace ignition
/// \return 0 when the operation succeeds to open a file.
private: int LoadData();

// Documentation inherited.
public: std::string Filename() const;

/// internal
/// \brief Pointer to the private data.
IGN_UTILS_IMPL_PTR(dataPtr)
};
}
}
#endif
#endif
Original file line number Diff line number Diff line change
Expand Up @@ -14,19 +14,20 @@
* limitations under the License.
*
*/
#ifndef IGNITION_COMMON_HEIGHTMAPDATA_HH_
#define IGNITION_COMMON_HEIGHTMAPDATA_HH_
#ifndef IGNITION_COMMON_GEOSPATIAL_HEIGHTMAPDATA_HH_
#define IGNITION_COMMON_GEOSPATIAL_HEIGHTMAPDATA_HH_

#include <string>
#include <vector>
#include <ignition/math/Vector3.hh>
#include <ignition/common/graphics/Export.hh>
#include <ignition/common/geospatial/Export.hh>

namespace ignition
{
namespace common
{
/// \brief Encapsulates a generic heightmap data file.
class IGNITION_COMMON_GRAPHICS_VISIBLE HeightmapData
class IGNITION_COMMON_GEOSPATIAL_VISIBLE HeightmapData
{
/// \brief Destructor.
public: virtual ~HeightmapData() = default;
Expand All @@ -44,7 +45,7 @@ namespace ignition
public: virtual void FillHeightMap(int _subSampling,
unsigned int _vertSize, const ignition::math::Vector3d &_size,
const ignition::math::Vector3d &_scale, bool _flipY,
std::vector<float> &_heights) = 0;
std::vector<float> &_heights) const = 0;

/// \brief Get the terrain's height.
/// \return The terrain's height.
Expand All @@ -57,6 +58,17 @@ namespace ignition
/// \brief Get the maximum terrain's elevation.
/// \return The maximum terrain's elevation.
public: virtual float MaxElevation() const = 0;

/// \brief Get the min terrain's elevation.
/// \return The min terrain's elevation.
public: virtual float MinElevation() const
{
return 0.0f;
}

/// \brief Get the full filename of loaded heightmap image/dem
/// \return The filename used to load the heightmap image/dem
public: virtual std::string Filename() const = 0;
};
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,24 +14,24 @@
* limitations under the License.
*
*/
#ifndef IGNITION_COMMON_IMAGEHEIGHTMAPDATA_HH_
#define IGNITION_COMMON_IMAGEHEIGHTMAPDATA_HH_
#ifndef IGNITION_COMMON_GEOSPATIAL_IMAGEHEIGHTMAPDATA_HH_
#define IGNITION_COMMON_GEOSPATIAL_IMAGEHEIGHTMAPDATA_HH_

#include <limits>
#include <string>
#include <vector>
#include <ignition/math/Vector3.hh>

#include <ignition/common/graphics/Export.hh>
#include <ignition/common/HeightmapData.hh>
#include <ignition/common/geospatial/Export.hh>
#include <ignition/common/geospatial/HeightmapData.hh>
#include <ignition/common/Image.hh>

namespace ignition
{
namespace common
{
/// \brief Encapsulates an image that will be interpreted as a heightmap.
class IGNITION_COMMON_GRAPHICS_VISIBLE ImageHeightmap
class IGNITION_COMMON_GEOSPATIAL_VISIBLE ImageHeightmap
: public ignition::common::HeightmapData
{
/// \brief Constructor
Expand All @@ -47,10 +47,9 @@ namespace ignition
public: void FillHeightMap(int _subSampling, unsigned int _vertSize,
const ignition::math::Vector3d &_size,
const ignition::math::Vector3d &_scale, bool _flipY,
std::vector<float> &_heights);
std::vector<float> &_heights) const;

/// \brief Get the full filename of the image
/// \return The filename used to load the image
// Documentation inherited.
public: std::string Filename() const;

// Documentation inherited.
Expand Down Expand Up @@ -80,7 +79,7 @@ namespace ignition
unsigned int _pitch, int _subSampling, unsigned int _vertSize,
const ignition::math::Vector3d &_size,
const ignition::math::Vector3d &_scale,
bool _flipY, std::vector<float> &_heights)
bool _flipY, std::vector<float> &_heights) const
{
// bytes per pixel
const unsigned int bpp = _pitch / _imgWidth;
Expand Down
22 changes: 22 additions & 0 deletions geospatial/src/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@

ign_get_libsources_and_unittests(sources gtest_sources)

ign_add_component(geospatial
SOURCES ${sources}
DEPENDS_ON_COMPONENTS graphics
GET_TARGET_NAME geospatial_target)

target_link_libraries(${geospatial_target}
PUBLIC
${PROJECT_LIBRARY_TARGET_NAME}-graphics
ignition-math${IGN_MATH_VER}::ignition-math${IGN_MATH_VER}
ignition-utils${IGN_UTILS_VER}::ignition-utils${IGN_UTILS_VER}
PRIVATE
${GDAL_LIBRARY})

target_include_directories(${geospatial_target}
PRIVATE
${GDAL_INCLUDE_DIR})

ign_build_tests(TYPE UNIT SOURCES ${gtest_sources}
LIB_DEPS ${geospatial_target})
Loading

0 comments on commit af583c9

Please sign in to comment.