Skip to content

Commit

Permalink
Merge da536ed into e0a5490
Browse files Browse the repository at this point in the history
  • Loading branch information
scpeters authored Jan 19, 2022
2 parents e0a5490 + da536ed commit 4548421
Show file tree
Hide file tree
Showing 17 changed files with 118 additions and 266 deletions.
1 change: 0 additions & 1 deletion .github/ci/packages.apt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@ libavdevice-dev
libavformat-dev
libavutil-dev
libfreeimage-dev
libgdal-dev
libgts-dev
libignition-cmake2-dev
libignition-math7-dev
Expand Down
11 changes: 2 additions & 9 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 geospatial graphics events)
ign_find_package(ignition-math7 REQUIRED_BY graphics events)
set(IGN_MATH_VER ${ignition-math7_VERSION_MAJOR})

#--------------------------------------
Expand Down Expand Up @@ -94,13 +94,6 @@ 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 @@ -132,7 +125,7 @@ configure_file("${PROJECT_SOURCE_DIR}/cppcheck.suppress.in"
${PROJECT_BINARY_DIR}/cppcheck.suppress)

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

#============================================================================
# Create package information
Expand Down
16 changes: 1 addition & 15 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,21 +5,6 @@ Deprecated code produces compile-time warnings. These warning serve as
notification to users that their code should be upgraded. The next major
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>`)

## Ignition Common 3.X to 4.X

### Modifications
Expand Down Expand Up @@ -87,3 +72,4 @@ release will remove the deprecated code.
1. **ignition-cmake**
+ Ignition-math now has a build dependency on ignition-cmake, which
allows cmake scripts to be shared across all the ignition packages.

2 changes: 0 additions & 2 deletions geospatial/include/ignition/common/CMakeLists.txt

This file was deleted.

22 changes: 0 additions & 22 deletions geospatial/src/CMakeLists.txt

This file was deleted.

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

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

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

#include <ignition/common/geospatial/Export.hh>
#include <ignition/common/geospatial/HeightmapData.hh>
#include <ignition/common/graphics/Export.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_GEOSPATIAL_VISIBLE Dem : public HeightmapData
class IGNITION_COMMON_GRAPHICS_VISIBLE Dem : public HeightmapData
{
/// \brief Constructor.
public: Dem();
Expand All @@ -52,8 +53,7 @@ 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 or infinity if illegal
/// coordinates were provided.
/// \return Terrain's elevation at (x,y) in meters.
public: double Elevation(double _x, double _y);

/// \brief Get the terrain's minimum elevation in meters.
Expand All @@ -68,8 +68,7 @@ namespace ignition
/// origin in WGS84.
/// \param[out] _latitude Georeferenced latitude.
/// \param[out] _longitude Georeferenced longitude.
/// \return True if able to retrieve origin coordinates. False otherwise.
public: bool GeoReferenceOrigin(ignition::math::Angle &_latitude,
public: void 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 @@ -121,8 +120,7 @@ namespace ignition
/// \param[in] _y Y coordinate of the terrain.
/// \param[out] _latitude Georeferenced latitude.
/// \param[out] _longitude Georeferenced longitude.
/// \return True if able to retrieve coordinates. False otherwise.
private: bool GeoReference(double _x, double _y,
private: void GeoReference(double _x, double _y,
ignition::math::Angle &_latitude,
ignition::math::Angle &_longitude) const;

Expand All @@ -132,13 +130,11 @@ 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,20 +14,19 @@
* limitations under the License.
*
*/
#ifndef IGNITION_COMMON_GEOSPATIAL_HEIGHTMAPDATA_HH_
#define IGNITION_COMMON_GEOSPATIAL_HEIGHTMAPDATA_HH_
#ifndef IGNITION_COMMON_HEIGHTMAPDATA_HH_
#define IGNITION_COMMON_HEIGHTMAPDATA_HH_

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

namespace ignition
{
namespace common
{
/// \brief Encapsulates a generic heightmap data file.
class IGNITION_COMMON_GEOSPATIAL_VISIBLE HeightmapData
class IGNITION_COMMON_GRAPHICS_VISIBLE HeightmapData
{
/// \brief Destructor.
public: virtual ~HeightmapData() = default;
Expand Down Expand Up @@ -58,17 +57,6 @@ 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_GEOSPATIAL_IMAGEHEIGHTMAPDATA_HH_
#define IGNITION_COMMON_GEOSPATIAL_IMAGEHEIGHTMAPDATA_HH_
#ifndef IGNITION_COMMON_IMAGEHEIGHTMAPDATA_HH_
#define IGNITION_COMMON_IMAGEHEIGHTMAPDATA_HH_

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

#include <ignition/common/geospatial/Export.hh>
#include <ignition/common/geospatial/HeightmapData.hh>
#include <ignition/common/graphics/Export.hh>
#include <ignition/common/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_GEOSPATIAL_VISIBLE ImageHeightmap
class IGNITION_COMMON_GRAPHICS_VISIBLE ImageHeightmap
: public ignition::common::HeightmapData
{
/// \brief Constructor
Expand All @@ -49,7 +49,8 @@ namespace ignition
const ignition::math::Vector3d &_scale, bool _flipY,
std::vector<float> &_heights);

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

// Documentation inherited.
Expand Down
Loading

0 comments on commit 4548421

Please sign in to comment.